diff --git a/control/vehicle_cmd_gate/script/delays_checker.py b/control/vehicle_cmd_gate/script/delays_checker.py index 72cc2307ac270..1f2633f73dd68 100644 --- a/control/vehicle_cmd_gate/script/delays_checker.py +++ b/control/vehicle_cmd_gate/script/delays_checker.py @@ -14,7 +14,7 @@ # See the License for the specific language governing permissions and # limitations under the License. -from autoware_auto_control_msgs.msg import Control +from autoware_control_msgs.msg import Control from autoware_auto_vehicle_msgs.msg import Engage from geometry_msgs.msg import AccelWithCovarianceStamped from nav_msgs.msg import Odometry diff --git a/planning/planning_debug_tools/scripts/closest_velocity_checker.py b/planning/planning_debug_tools/scripts/closest_velocity_checker.py index a1021ff4db065..15e61613376b9 100755 --- a/planning/planning_debug_tools/scripts/closest_velocity_checker.py +++ b/planning/planning_debug_tools/scripts/closest_velocity_checker.py @@ -16,7 +16,7 @@ import time -from autoware_auto_control_msgs.msg import Control +from autoware_control_msgs.msg import Control from autoware_auto_planning_msgs.msg import Path from autoware_auto_planning_msgs.msg import PathWithLaneId from autoware_auto_planning_msgs.msg import Trajectory diff --git a/tools/simulator_test/simulator_compatibility_test/simulator_compatibility_test/publishers/ackermann_control_command.py b/tools/simulator_test/simulator_compatibility_test/simulator_compatibility_test/publishers/ackermann_control_command.py index be77088e660c7..bc2ac0ad20b4a 100644 --- a/tools/simulator_test/simulator_compatibility_test/simulator_compatibility_test/publishers/ackermann_control_command.py +++ b/tools/simulator_test/simulator_compatibility_test/simulator_compatibility_test/publishers/ackermann_control_command.py @@ -1,6 +1,5 @@ -from autoware_auto_control_msgs.msg import Control -from autoware_auto_control_msgs.msg import Lateral -from autoware_auto_control_msgs.msg import LongitudinalCommand +from autoware_control_msgs.msg import Control +from autoware_control_msgs.msg import Lateral import rclpy from rclpy.node import Node from rclpy.qos import QoSDurabilityPolicy @@ -29,7 +28,7 @@ def publish_msg(self, control_cmd): stamp = self.get_clock().now().to_msg() msg = Control() lateral_cmd = Lateral() - longitudinal_cmd = LongitudinalCommand() + longitudinal_cmd = Longitudinal() lateral_cmd.stamp.sec = stamp.sec lateral_cmd.stamp.nanosec = stamp.nanosec lateral_cmd.steering_tire_angle = control_cmd["lateral"]["steering_tire_angle"] @@ -38,7 +37,7 @@ def publish_msg(self, control_cmd): ] longitudinal_cmd.stamp.sec = stamp.sec longitudinal_cmd.stamp.nanosec = stamp.nanosec - longitudinal_cmd.velocity = control_cmd["longitudinal"]["speed"] + longitudinal_cmd.speed = control_cmd["longitudinal"]["speed"] longitudinal_cmd.acceleration = control_cmd["longitudinal"]["acceleration"] longitudinal_cmd.jerk = control_cmd["longitudinal"]["jerk"] diff --git a/tools/simulator_test/simulator_compatibility_test/test_base/test_03_longitudinal_command_and_report.py b/tools/simulator_test/simulator_compatibility_test/test_base/test_03_longitudinal_command_and_report.py index b2e9341bf5d82..91a86e4e559d3 100644 --- a/tools/simulator_test/simulator_compatibility_test/test_base/test_03_longitudinal_command_and_report.py +++ b/tools/simulator_test/simulator_compatibility_test/test_base/test_03_longitudinal_command_and_report.py @@ -1,8 +1,8 @@ import time -from autoware_auto_control_msgs.msg import Control -from autoware_auto_control_msgs.msg import Lateral -from autoware_auto_control_msgs.msg import LongitudinalCommand +from autoware_control_msgs.msg import Control +from autoware_control_msgs.msg import Lateral +from autoware_control_msgs.msg import Longitudinal import pytest import rclpy from rclpy.executors import MultiThreadedExecutor @@ -71,7 +71,7 @@ def generate_control_msg(self, control_cmd): stamp = self.node.get_clock().now().to_msg() msg = Control() lateral_cmd = Lateral() - longitudinal_cmd = LongitudinalCommand() + longitudinal_cmd = Longitudinal() lateral_cmd.stamp.sec = stamp.sec lateral_cmd.stamp.nanosec = stamp.nanosec lateral_cmd.steering_tire_angle = control_cmd["lateral"]["steering_tire_angle"] @@ -80,7 +80,7 @@ def generate_control_msg(self, control_cmd): ] longitudinal_cmd.stamp.sec = stamp.sec longitudinal_cmd.stamp.nanosec = stamp.nanosec - longitudinal_cmd.velocity = control_cmd["longitudinal"]["speed"] + longitudinal_cmd.speed = control_cmd["longitudinal"]["speed"] longitudinal_cmd.acceleration = control_cmd["longitudinal"]["acceleration"] longitudinal_cmd.jerk = control_cmd["longitudinal"]["jerk"] @@ -99,7 +99,7 @@ def set_speed(self, speed): if len(self.msgs_rx) > 2: break received = self.msgs_rx[-1] - assert received.longitudinal.velocity == speed + assert received.longitudinal.speed == speed self.msgs_rx.clear() def set_acceleration(self, acceleration): diff --git a/tools/simulator_test/simulator_compatibility_test/test_base/test_04_lateral_command_and_report.py b/tools/simulator_test/simulator_compatibility_test/test_base/test_04_lateral_command_and_report.py index 017a2f8c57549..b126f9e979628 100644 --- a/tools/simulator_test/simulator_compatibility_test/test_base/test_04_lateral_command_and_report.py +++ b/tools/simulator_test/simulator_compatibility_test/test_base/test_04_lateral_command_and_report.py @@ -1,8 +1,8 @@ import time -from autoware_auto_control_msgs.msg import Control -from autoware_auto_control_msgs.msg import Lateral -from autoware_auto_control_msgs.msg import LongitudinalCommand +from autoware_control_msgs.msg import Control +from autoware_control_msgs.msg import Lateral +from autoware_control_msgs.msg import Longitudinal import pytest import rclpy from rclpy.executors import MultiThreadedExecutor @@ -70,7 +70,7 @@ def generate_control_msg(self, control_cmd): stamp = self.node.get_clock().now().to_msg() msg = Control() lateral_cmd = Lateral() - longitudinal_cmd = LongitudinalCommand() + longitudinal_cmd = Longitudinal() lateral_cmd.stamp.sec = stamp.sec lateral_cmd.stamp.nanosec = stamp.nanosec lateral_cmd.steering_tire_angle = control_cmd["lateral"]["steering_tire_angle"] @@ -79,7 +79,7 @@ def generate_control_msg(self, control_cmd): ] longitudinal_cmd.stamp.sec = stamp.sec longitudinal_cmd.stamp.nanosec = stamp.nanosec - longitudinal_cmd.velocity = control_cmd["longitudinal"]["speed"] + longitudinal_cmd.speed = control_cmd["longitudinal"]["speed"] longitudinal_cmd.acceleration = control_cmd["longitudinal"]["acceleration"] longitudinal_cmd.jerk = control_cmd["longitudinal"]["jerk"]