From 64486635cabe1d47796fe8b55a9eafb5ac932a68 Mon Sep 17 00:00:00 2001 From: Tomohito Ando Date: Mon, 21 Aug 2023 11:08:35 +0900 Subject: [PATCH] fix the traffic signal type in perception reproducer Signed-off-by: Tomohito Ando --- .../scripts/perception_replayer/perception_replayer.py | 4 ++-- .../scripts/perception_replayer/perception_replayer_common.py | 2 +- .../scripts/perception_replayer/perception_reproducer.py | 4 ++-- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer.py b/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer.py index b45357c7bd8b2..9d8fa4a32a93d 100755 --- a/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer.py +++ b/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer.py @@ -93,11 +93,11 @@ def on_timer(self): # traffic signals if traffic_signals_msg: - traffic_signals_msg.header.stamp = timestamp + traffic_signals_msg.stamp = timestamp self.traffic_signals_pub.publish(traffic_signals_msg) self.prev_traffic_signals_msg = traffic_signals_msg elif self.prev_traffic_signals_msg: - self.prev_traffic_signals_msg.header.stamp = timestamp + self.prev_traffic_signals_msg.stamp = timestamp self.traffic_signals_pub.publish(self.prev_traffic_signals_msg) def onPushed(self, event): diff --git a/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer_common.py b/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer_common.py index a86a9ae9b2bb0..7774a8c82daf6 100644 --- a/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer_common.py +++ b/planning/planning_debug_tools/scripts/perception_replayer/perception_replayer_common.py @@ -22,7 +22,7 @@ from autoware_auto_perception_msgs.msg import DetectedObjects from autoware_auto_perception_msgs.msg import PredictedObjects from autoware_auto_perception_msgs.msg import TrackedObjects -from autoware_auto_perception_msgs.msg import TrafficSignalArray +from autoware_perception_msgs.msg import TrafficSignalArray from nav_msgs.msg import Odometry import psutil from rclpy.node import Node diff --git a/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py b/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py index 4228d506d5bec..5344e622be38e 100755 --- a/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py +++ b/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py @@ -67,11 +67,11 @@ def on_timer(self): # traffic signals if traffic_signals_msg: - traffic_signals_msg.header.stamp = timestamp + traffic_signals_msg.stamp = timestamp self.traffic_signals_pub.publish(traffic_signals_msg) self.prev_traffic_signals_msg = traffic_signals_msg elif self.prev_traffic_signals_msg: - self.prev_traffic_signals_msg.header.stamp = timestamp + self.prev_traffic_signals_msg.stamp = timestamp self.traffic_signals_pub.publish(self.prev_traffic_signals_msg) def find_nearest_ego_odom_by_observation(self, ego_pose):