Skip to content

Commit 337f0ac

Browse files
authored
fix(planning, control): reuse stamp of subscribed topic to measure component latency (#10201)
* fix(behavior_velocity_planner): reuse timestamp of recieved path Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * fix(behavior_path_planner): check timestamp first in timer driven callback Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * fix(trajectory_follower_node): check timestamp first in timer driven callback Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * fix(vehicle_cmd_gate): reuse timestamp of recieved path Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> --------- Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent 58ce127 commit 337f0ac

File tree

4 files changed

+10
-5
lines changed

4 files changed

+10
-5
lines changed

control/autoware_trajectory_follower_node/src/controller_node.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -204,6 +204,9 @@ boost::optional<trajectory_follower::InputData> Controller::createInputData(rclc
204204

205205
void Controller::callbackTimerControl()
206206
{
207+
autoware_control_msgs::msg::Control out;
208+
out.stamp = this->now();
209+
207210
// 1. create input data
208211
const auto input_data = createInputData(*get_clock());
209212
if (!input_data) {
@@ -239,8 +242,6 @@ void Controller::callbackTimerControl()
239242
if (isTimeOut(lon_out, lat_out)) return;
240243

241244
// 5. publish control command
242-
autoware_control_msgs::msg::Control out;
243-
out.stamp = this->now();
244245
out.lateral = lat_out.control_cmd;
245246
out.longitudinal = lon_out.control_cmd;
246247
control_cmd_pub_->publish(out);

control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp

+2
Original file line numberDiff line numberDiff line change
@@ -569,13 +569,15 @@ void VehicleCmdGate::publishControlCommands(const Commands & commands)
569569
filtered_control.longitudinal = createLongitudinalStopControlCmd();
570570
} else {
571571
filtered_control = createStopControlCmd();
572+
filtered_control.stamp = commands.control.stamp;
572573
}
573574
}
574575

575576
// Check if command filtering option is enable
576577
if (enable_cmd_limit_filter_) {
577578
// Apply limit filtering
578579
filtered_control = filterControlCommand(filtered_control);
580+
filtered_control.stamp = commands.control.stamp;
579581
}
580582
// tmp: Publish vehicle emergency status
581583
VehicleEmergencyStamped vehicle_cmd_emergency;

planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -300,6 +300,8 @@ bool BehaviorPathPlannerNode::isDataReady()
300300

301301
void BehaviorPathPlannerNode::run()
302302
{
303+
const auto stamp = this->now();
304+
303305
takeData();
304306

305307
if (!isDataReady()) {
@@ -372,6 +374,7 @@ void BehaviorPathPlannerNode::run()
372374

373375
// path handling
374376
const auto path = getPath(output, planner_data_, planner_manager_);
377+
path->header.stamp = stamp;
375378
// update planner data
376379
planner_data_->prev_output_path = path;
377380

@@ -714,7 +717,6 @@ PathWithLaneId::SharedPtr BehaviorPathPlannerNode::getPath(
714717
auto path = !output.path.points.empty() ? std::make_shared<PathWithLaneId>(output.path)
715718
: planner_data->prev_output_path;
716719
path->header = planner_data->route_handler->getRouteHeader();
717-
path->header.stamp = this->now();
718720

719721
PathWithLaneId connected_path;
720722
const auto module_status_ptr_vec = planner_manager->getSceneModuleStatus();

planning/behavior_velocity_planner/autoware_behavior_velocity_planner/src/node.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -344,7 +344,7 @@ autoware_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generatePath(
344344
"Backward path is NOT supported. just converting path_with_lane_id to path");
345345
output_path_msg = to_path(*input_path_msg);
346346
output_path_msg.header.frame_id = "map";
347-
output_path_msg.header.stamp = this->now();
347+
output_path_msg.header.stamp = input_path_msg->header.stamp;
348348
output_path_msg.left_bound = input_path_msg->left_bound;
349349
output_path_msg.right_bound = input_path_msg->right_bound;
350350
return output_path_msg;
@@ -366,7 +366,7 @@ autoware_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generatePath(
366366
output_path_msg = autoware::behavior_velocity_planner::filterStopPathPoint(interpolated_path_msg);
367367

368368
output_path_msg.header.frame_id = "map";
369-
output_path_msg.header.stamp = this->now();
369+
output_path_msg.header.stamp = input_path_msg->header.stamp;
370370

371371
// TODO(someone): This must be updated in each scene module, but copy from input message for now.
372372
output_path_msg.left_bound = input_path_msg->left_bound;

0 commit comments

Comments
 (0)