From 59ae7c58d102613e1fafc60b5e16e5768310976b Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Sat, 29 Jun 2024 09:17:04 +0900 Subject: [PATCH] fix: autoware_msgs (#68) Signed-off-by: kosuke55 Signed-off-by: temkei.kem <1041084556@qq.com> --- .../planning_debug_tools/scripts/closest_velocity_checker.py | 4 ++-- .../publishers/ackermann_control_command.py | 2 +- .../test_base/test_03_longitudinal_command_and_report.py | 4 ++-- .../test_base/test_04_lateral_command_and_report.py | 2 +- 4 files changed, 6 insertions(+), 6 deletions(-) diff --git a/planning/planning_debug_tools/scripts/closest_velocity_checker.py b/planning/planning_debug_tools/scripts/closest_velocity_checker.py index a8a553a3..f04c5206 100755 --- a/planning/planning_debug_tools/scripts/closest_velocity_checker.py +++ b/planning/planning_debug_tools/scripts/closest_velocity_checker.py @@ -274,13 +274,13 @@ def CallBackScenarioTrajectory(self, msg): def CallBackControlCmd(self, msg): # self.get_logger().info('CONTROL_CMD called') - self.data_arr[CONTROL_CMD] = msg.longitudinal.speed + self.data_arr[CONTROL_CMD] = msg.longitudinal.velocity self.data_arr[CONTROL_CMD_ACC] = msg.longitudinal.acceleration return def CallBackVehicleCmd(self, msg): # self.get_logger().info('VEHICLE_CMD called') - self.data_arr[VEHICLE_CMD] = msg.longitudinal.speed + self.data_arr[VEHICLE_CMD] = msg.longitudinal.velocity self.data_arr[VEHICLE_CMD_ACC] = msg.longitudinal.acceleration return diff --git a/simulator/simulator_compatibility_test/simulator_compatibility_test/publishers/ackermann_control_command.py b/simulator/simulator_compatibility_test/simulator_compatibility_test/publishers/ackermann_control_command.py index 9c643fbb..3951984b 100644 --- a/simulator/simulator_compatibility_test/simulator_compatibility_test/publishers/ackermann_control_command.py +++ b/simulator/simulator_compatibility_test/simulator_compatibility_test/publishers/ackermann_control_command.py @@ -38,7 +38,7 @@ def publish_msg(self, control_cmd): ] longitudinal_cmd.stamp.sec = stamp.sec longitudinal_cmd.stamp.nanosec = stamp.nanosec - longitudinal_cmd.speed = control_cmd["longitudinal"]["speed"] + longitudinal_cmd.velocity = control_cmd["longitudinal"]["speed"] longitudinal_cmd.acceleration = control_cmd["longitudinal"]["acceleration"] longitudinal_cmd.jerk = control_cmd["longitudinal"]["jerk"] diff --git a/simulator/simulator_compatibility_test/test_base/test_03_longitudinal_command_and_report.py b/simulator/simulator_compatibility_test/test_base/test_03_longitudinal_command_and_report.py index 176ef5a8..eeeb423d 100644 --- a/simulator/simulator_compatibility_test/test_base/test_03_longitudinal_command_and_report.py +++ b/simulator/simulator_compatibility_test/test_base/test_03_longitudinal_command_and_report.py @@ -82,7 +82,7 @@ def generate_control_msg(self, control_cmd): ] longitudinal_cmd.stamp.sec = stamp.sec longitudinal_cmd.stamp.nanosec = stamp.nanosec - longitudinal_cmd.speed = control_cmd["longitudinal"]["speed"] + longitudinal_cmd.velocity = control_cmd["longitudinal"]["speed"] longitudinal_cmd.acceleration = control_cmd["longitudinal"]["acceleration"] longitudinal_cmd.jerk = control_cmd["longitudinal"]["jerk"] @@ -101,7 +101,7 @@ def set_speed(self, speed): if len(self.msgs_rx) > 2: break received = self.msgs_rx[-1] - assert received.longitudinal.speed == speed + assert received.longitudinal.velocity == speed self.msgs_rx.clear() def set_acceleration(self, acceleration): diff --git a/simulator/simulator_compatibility_test/test_base/test_04_lateral_command_and_report.py b/simulator/simulator_compatibility_test/test_base/test_04_lateral_command_and_report.py index 5959bdef..2e0934ef 100644 --- a/simulator/simulator_compatibility_test/test_base/test_04_lateral_command_and_report.py +++ b/simulator/simulator_compatibility_test/test_base/test_04_lateral_command_and_report.py @@ -81,7 +81,7 @@ def generate_control_msg(self, control_cmd): ] longitudinal_cmd.stamp.sec = stamp.sec longitudinal_cmd.stamp.nanosec = stamp.nanosec - longitudinal_cmd.speed = control_cmd["longitudinal"]["speed"] + longitudinal_cmd.velocity = control_cmd["longitudinal"]["speed"] longitudinal_cmd.acceleration = control_cmd["longitudinal"]["acceleration"] longitudinal_cmd.jerk = control_cmd["longitudinal"]["jerk"]