Skip to content

Commit 0a81beb

Browse files
add header to criticscores msg
1 parent 154feba commit 0a81beb

File tree

2 files changed

+2
-0
lines changed

2 files changed

+2
-0
lines changed
Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,2 +1,3 @@
1+
std_msgs/Header header # ROS time that this log message was sent.
12
std_msgs/String[] critic_names
23
std_msgs/Float32[] critic_scores

nav2_mppi_controller/src/controller.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -138,6 +138,7 @@ geometry_msgs::msg::TwistStamped MPPIController::computeVelocityCommands(
138138
cost_msg.data = critic_costs[i];
139139
critic_scores_->critic_scores.push_back(std::move(cost_msg));
140140
}
141+
critic_scores_->header.stamp = clock_->now();
141142
critics_publisher_->publish(std::move(critic_scores_));
142143
}
143144

0 commit comments

Comments
 (0)