@@ -316,16 +316,18 @@ void ScenarioSelectorNode::onParkingTrajectory(
316
316
void ScenarioSelectorNode::publishTrajectory (
317
317
const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr msg)
318
318
{
319
- const auto now = this ->now ();
320
- const auto delay_sec = (now - msg->header .stamp ).seconds ();
321
- if (delay_sec <= th_max_message_delay_sec_) {
322
- pub_trajectory_->publish (*msg);
323
- } else {
324
- RCLCPP_WARN_THROTTLE (
325
- this ->get_logger (), *this ->get_clock (), std::chrono::milliseconds (1000 ).count (),
326
- " trajectory is delayed: scenario = %s, delay = %f, th_max_message_delay = %f" ,
327
- current_scenario_.c_str (), delay_sec, th_max_message_delay_sec_);
328
- }
319
+ auto msg_sent = *msg;
320
+ msg_sent.header .stamp = this ->now ();
321
+ pub_trajectory_->publish (msg_sent);
322
+
323
+ // const auto delay_sec = (now - msg->header.stamp).seconds();
324
+ // if (delay_sec <= th_max_message_delay_sec_) {
325
+ // } else {
326
+ // RCLCPP_WARN_THROTTLE(
327
+ // this->get_logger(), *this->get_clock(), std::chrono::milliseconds(1000).count(),
328
+ // "trajectory is delayed: scenario = %s, delay = %f, th_max_message_delay = %f",
329
+ // current_scenario_.c_str(), delay_sec, th_max_message_delay_sec_);
330
+ // }
329
331
}
330
332
331
333
ScenarioSelectorNode::ScenarioSelectorNode (const rclcpp::NodeOptions & node_options)
0 commit comments