File tree 4 files changed +10
-5
lines changed
autoware_trajectory_follower_node/src
autoware_vehicle_cmd_gate/src
behavior_path_planner/autoware_behavior_path_planner/src
behavior_velocity_planner/autoware_behavior_velocity_planner/src
4 files changed +10
-5
lines changed Original file line number Diff line number Diff line change @@ -204,6 +204,9 @@ boost::optional<trajectory_follower::InputData> Controller::createInputData(rclc
204
204
205
205
void Controller::callbackTimerControl ()
206
206
{
207
+ autoware_control_msgs::msg::Control out;
208
+ out.stamp = this ->now ();
209
+
207
210
// 1. create input data
208
211
const auto input_data = createInputData (*get_clock ());
209
212
if (!input_data) {
@@ -239,8 +242,6 @@ void Controller::callbackTimerControl()
239
242
if (isTimeOut (lon_out, lat_out)) return ;
240
243
241
244
// 5. publish control command
242
- autoware_control_msgs::msg::Control out;
243
- out.stamp = this ->now ();
244
245
out.lateral = lat_out.control_cmd ;
245
246
out.longitudinal = lon_out.control_cmd ;
246
247
control_cmd_pub_->publish (out);
Original file line number Diff line number Diff line change @@ -569,13 +569,15 @@ void VehicleCmdGate::publishControlCommands(const Commands & commands)
569
569
filtered_control.longitudinal = createLongitudinalStopControlCmd ();
570
570
} else {
571
571
filtered_control = createStopControlCmd ();
572
+ filtered_control.stamp = commands.control .stamp ;
572
573
}
573
574
}
574
575
575
576
// Check if command filtering option is enable
576
577
if (enable_cmd_limit_filter_) {
577
578
// Apply limit filtering
578
579
filtered_control = filterControlCommand (filtered_control);
580
+ filtered_control.stamp = commands.control .stamp ;
579
581
}
580
582
// tmp: Publish vehicle emergency status
581
583
VehicleEmergencyStamped vehicle_cmd_emergency;
Original file line number Diff line number Diff line change @@ -300,6 +300,8 @@ bool BehaviorPathPlannerNode::isDataReady()
300
300
301
301
void BehaviorPathPlannerNode::run ()
302
302
{
303
+ const auto stamp = this ->now ();
304
+
303
305
takeData ();
304
306
305
307
if (!isDataReady ()) {
@@ -372,6 +374,7 @@ void BehaviorPathPlannerNode::run()
372
374
373
375
// path handling
374
376
const auto path = getPath (output, planner_data_, planner_manager_);
377
+ path->header .stamp = stamp;
375
378
// update planner data
376
379
planner_data_->prev_output_path = path;
377
380
@@ -714,7 +717,6 @@ PathWithLaneId::SharedPtr BehaviorPathPlannerNode::getPath(
714
717
auto path = !output.path .points .empty () ? std::make_shared<PathWithLaneId>(output.path )
715
718
: planner_data->prev_output_path ;
716
719
path->header = planner_data->route_handler ->getRouteHeader ();
717
- path->header .stamp = this ->now ();
718
720
719
721
PathWithLaneId connected_path;
720
722
const auto module_status_ptr_vec = planner_manager->getSceneModuleStatus ();
Original file line number Diff line number Diff line change @@ -344,7 +344,7 @@ autoware_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generatePath(
344
344
" Backward path is NOT supported. just converting path_with_lane_id to path" );
345
345
output_path_msg = to_path (*input_path_msg);
346
346
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 ;
348
348
output_path_msg.left_bound = input_path_msg->left_bound ;
349
349
output_path_msg.right_bound = input_path_msg->right_bound ;
350
350
return output_path_msg;
@@ -366,7 +366,7 @@ autoware_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generatePath(
366
366
output_path_msg = autoware::behavior_velocity_planner::filterStopPathPoint (interpolated_path_msg);
367
367
368
368
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 ;
370
370
371
371
// TODO(someone): This must be updated in each scene module, but copy from input message for now.
372
372
output_path_msg.left_bound = input_path_msg->left_bound ;
You can’t perform that action at this time.
0 commit comments