Skip to content

Commit 09d7b81

Browse files
committed
tmp scenario_selector header update
1 parent 4702e8e commit 09d7b81

File tree

1 file changed

+12
-10
lines changed

1 file changed

+12
-10
lines changed

planning/scenario_selector/src/scenario_selector_node/scenario_selector_node.cpp

+12-10
Original file line numberDiff line numberDiff line change
@@ -316,16 +316,18 @@ void ScenarioSelectorNode::onParkingTrajectory(
316316
void ScenarioSelectorNode::publishTrajectory(
317317
const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr msg)
318318
{
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+
// }
329331
}
330332

331333
ScenarioSelectorNode::ScenarioSelectorNode(const rclcpp::NodeOptions & node_options)

0 commit comments

Comments
 (0)