From c013e832c7402210f5b721b9d6aaabd7a00597e6 Mon Sep 17 00:00:00 2001 From: mitsudome-r Date: Thu, 25 Apr 2024 16:40:05 +0900 Subject: [PATCH] feat!: replace autoware_auto_msgs with autoware_msgs Signed-off-by: mitsudome-r --- build_depends.repos | 4 --- .../lateral_error_publisher.hpp | 8 +++--- common/tier4_debug_tools/package.xml | 2 +- .../src/lateral_error_publisher.cpp | 4 +-- .../driving_environment_analyzer/node.hpp | 14 +++++------ driving_environment_analyzer/package.xml | 5 ++-- driving_environment_analyzer/src/node.cpp | 8 +++--- .../trajectory_analyzer.hpp | 12 ++++----- .../include/planning_debug_tools/util.hpp | 12 ++++----- planning/planning_debug_tools/package.xml | 2 +- .../scripts/closest_velocity_checker.py | 12 ++++----- .../perception_replayer_common.py | 25 ++++++------------- .../scripts/trajectory_visualizer.py | 14 +++++------ .../simulator_compatibility_test/README.md | 22 ++++++++-------- .../simulator_compatibility_test/package.xml | 16 ++++++------ .../publishers/ackermann_control_command.py | 16 ++++++------ .../publishers/control_mode_command.py | 2 +- .../publishers/gear_command.py | 2 +- .../subscribers/control_mode_report.py | 2 +- .../subscribers/gear_report.py | 2 +- .../subscribers/hazard_lights_report.py | 2 +- .../subscribers/steering_report.py | 2 +- .../subscribers/turn_indicators_report.py | 2 +- .../subscribers/velocity_report.py | 2 +- .../test_01_control_mode_and_report.py | 2 +- .../test_02_change_gear_and_report.py | 2 +- ...test_03_longitudinal_command_and_report.py | 14 +++++------ .../test_04_lateral_command_and_report.py | 14 +++++------ .../test_05_turn_indicators_cmd_and_report.py | 2 +- .../test_06_hazard_lights_cmd_and_report.py | 2 +- 30 files changed, 106 insertions(+), 122 deletions(-) diff --git a/build_depends.repos b/build_depends.repos index a675c92d..825fbf65 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -20,10 +20,6 @@ repositories: type: git url: https://github.com/autowarefoundation/autoware_internal_msgs.git version: main - core/external/autoware_auto_msgs: - type: git - url: https://github.com/tier4/autoware_auto_msgs.git - version: tier4/main # universe universe/autoware.universe: type: git diff --git a/common/tier4_debug_tools/include/tier4_debug_tools/lateral_error_publisher.hpp b/common/tier4_debug_tools/include/tier4_debug_tools/lateral_error_publisher.hpp index 962fee8a..163f4995 100644 --- a/common/tier4_debug_tools/include/tier4_debug_tools/lateral_error_publisher.hpp +++ b/common/tier4_debug_tools/include/tier4_debug_tools/lateral_error_publisher.hpp @@ -22,7 +22,7 @@ #include #include -#include +#include #include #include @@ -36,7 +36,7 @@ class LateralErrorPublisher : public rclcpp::Node double yaw_threshold_to_search_closest_; /* States */ - autoware_auto_planning_msgs::msg::Trajectory::SharedPtr + autoware_planning_msgs::msg::Trajectory::SharedPtr current_trajectory_ptr_; //!< @brief reference trajectory geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr current_vehicle_pose_ptr_; //!< @brief current EKF pose @@ -44,7 +44,7 @@ class LateralErrorPublisher : public rclcpp::Node current_ground_truth_pose_ptr_; //!< @brief current GNSS pose /* Publishers and Subscribers */ - rclcpp::Subscription::SharedPtr + rclcpp::Subscription::SharedPtr sub_trajectory_; //!< @brief subscription for reference trajectory rclcpp::Subscription::SharedPtr sub_vehicle_pose_; //!< @brief subscription for vehicle pose @@ -60,7 +60,7 @@ class LateralErrorPublisher : public rclcpp::Node /** * @brief set current_trajectory_ with received message */ - void onTrajectory(const autoware_auto_planning_msgs::msg::Trajectory::SharedPtr); + void onTrajectory(const autoware_planning_msgs::msg::Trajectory::SharedPtr); /** * @brief set current_vehicle_pose_ with received message */ diff --git a/common/tier4_debug_tools/package.xml b/common/tier4_debug_tools/package.xml index 8f03a3b5..3a028c90 100644 --- a/common/tier4_debug_tools/package.xml +++ b/common/tier4_debug_tools/package.xml @@ -10,7 +10,7 @@ ament_cmake_auto autoware_cmake - autoware_auto_planning_msgs + autoware_planning_msgs geometry_msgs motion_utils rclcpp diff --git a/common/tier4_debug_tools/src/lateral_error_publisher.cpp b/common/tier4_debug_tools/src/lateral_error_publisher.cpp index 18c97a47..13c87223 100644 --- a/common/tier4_debug_tools/src/lateral_error_publisher.cpp +++ b/common/tier4_debug_tools/src/lateral_error_publisher.cpp @@ -26,7 +26,7 @@ LateralErrorPublisher::LateralErrorPublisher(const rclcpp::NodeOptions & node_op declare_parameter("yaw_threshold_to_search_closest", M_PI / 4.0); /* Publishers and Subscribers */ - sub_trajectory_ = create_subscription( + sub_trajectory_ = create_subscription( "~/input/reference_trajectory", rclcpp::QoS{1}, std::bind(&LateralErrorPublisher::onTrajectory, this, _1)); sub_vehicle_pose_ = create_subscription( @@ -44,7 +44,7 @@ LateralErrorPublisher::LateralErrorPublisher(const rclcpp::NodeOptions & node_op } void LateralErrorPublisher::onTrajectory( - const autoware_auto_planning_msgs::msg::Trajectory::SharedPtr msg) + const autoware_planning_msgs::msg::Trajectory::SharedPtr msg) { current_trajectory_ptr_ = msg; } diff --git a/driving_environment_analyzer/include/driving_environment_analyzer/node.hpp b/driving_environment_analyzer/include/driving_environment_analyzer/node.hpp index da2677b0..1418d515 100644 --- a/driving_environment_analyzer/include/driving_environment_analyzer/node.hpp +++ b/driving_environment_analyzer/include/driving_environment_analyzer/node.hpp @@ -20,8 +20,8 @@ #include -#include -#include +#include +#include #include #include #include @@ -36,9 +36,9 @@ namespace driving_environment_analyzer { -using autoware_auto_mapping_msgs::msg::HADMapBin; -using autoware_auto_perception_msgs::msg::PredictedObject; -using autoware_auto_perception_msgs::msg::PredictedObjects; +using autoware_map_msgs::msg::LaneletMapBin; +using autoware_perception_msgs::msg::PredictedObject; +using autoware_perception_msgs::msg::PredictedObjects; using autoware_planning_msgs::msg::LaneletRoute; using geometry_msgs::msg::AccelWithCovarianceStamped; using nav_msgs::msg::Odometry; @@ -50,7 +50,7 @@ class DrivingEnvironmentAnalyzer : public rclcpp::Node private: bool isDataReady(const bool use_map_in_bag); - void onMap(const HADMapBin::ConstSharedPtr map_msg); + void onMap(const LaneletMapBin::ConstSharedPtr map_msg); void analyze(); bool has_map_data_{false}; @@ -59,7 +59,7 @@ class DrivingEnvironmentAnalyzer : public rclcpp::Node route_handler::RouteHandler route_handler_; LaneletRoute::ConstSharedPtr route_ptr_{nullptr}; - rclcpp::Subscription::SharedPtr sub_map_; + rclcpp::Subscription::SharedPtr sub_map_; rclcpp::TimerBase::SharedPtr timer_; rosbag2_cpp::Reader reader_; }; diff --git a/driving_environment_analyzer/package.xml b/driving_environment_analyzer/package.xml index 3446de71..f6b66ef2 100644 --- a/driving_environment_analyzer/package.xml +++ b/driving_environment_analyzer/package.xml @@ -15,11 +15,10 @@ autoware_cmake autoware_adapi_v1_msgs - autoware_auto_perception_msgs - autoware_auto_planning_msgs autoware_auto_tf2 - autoware_auto_vehicle_msgs autoware_perception_msgs + autoware_planning_msgs + autoware_vehicle_msgs behavior_path_planner_common geometry_msgs interpolation diff --git a/driving_environment_analyzer/src/node.cpp b/driving_environment_analyzer/src/node.cpp index b9496710..12d74acd 100644 --- a/driving_environment_analyzer/src/node.cpp +++ b/driving_environment_analyzer/src/node.cpp @@ -275,7 +275,7 @@ DrivingEnvironmentAnalyzer::DrivingEnvironmentAnalyzer(const rclcpp::NodeOptions timer_ = rclcpp::create_timer( this, get_clock(), 100ms, std::bind(&DrivingEnvironmentAnalyzer::analyze, this)); - sub_map_ = create_subscription( + sub_map_ = create_subscription( "input/lanelet2_map", rclcpp::QoS{1}.transient_local(), std::bind(&DrivingEnvironmentAnalyzer::onMap, this, _1)); @@ -292,7 +292,7 @@ bool DrivingEnvironmentAnalyzer::isDataReady(const bool use_map_in_bag) const std::string topic_map = "/map/vector_map"; rclcpp::Serialization serializer_route; - rclcpp::Serialization serializer_map; + rclcpp::Serialization serializer_map; rosbag2_storage::StorageFilter filter; filter.topics.emplace_back(topic_route); @@ -311,7 +311,7 @@ bool DrivingEnvironmentAnalyzer::isDataReady(const bool use_map_in_bag) if (data->topic_name == topic_map) { rclcpp::SerializedMessage serialized_msg(*data->serialized_data); - const auto deserialized_message = std::make_shared(); + const auto deserialized_message = std::make_shared(); serializer_route.deserialize_message(&serialized_msg, deserialized_message.get()); route_handler_.setMap(*deserialized_message); has_map_data_ = true; @@ -331,7 +331,7 @@ bool DrivingEnvironmentAnalyzer::isDataReady(const bool use_map_in_bag) return true; } -void DrivingEnvironmentAnalyzer::onMap(const HADMapBin::ConstSharedPtr msg) +void DrivingEnvironmentAnalyzer::onMap(const LaneletMapBin::ConstSharedPtr msg) { route_handler_.setMap(*msg); has_map_data_ = true; diff --git a/planning/planning_debug_tools/include/planning_debug_tools/trajectory_analyzer.hpp b/planning/planning_debug_tools/include/planning_debug_tools/trajectory_analyzer.hpp index d460cbf0..72ce45cf 100644 --- a/planning/planning_debug_tools/include/planning_debug_tools/trajectory_analyzer.hpp +++ b/planning/planning_debug_tools/include/planning_debug_tools/trajectory_analyzer.hpp @@ -21,11 +21,11 @@ #include "rclcpp/rclcpp.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" -#include "autoware_auto_planning_msgs/msg/path.hpp" -#include "autoware_auto_planning_msgs/msg/path_with_lane_id.hpp" -#include "autoware_auto_planning_msgs/msg/trajectory.hpp" +#include "autoware_planning_msgs/msg/path.hpp" +#include "autoware_planning_msgs/msg/trajectory.hpp" #include "nav_msgs/msg/odometry.hpp" #include "tier4_debug_msgs/msg/float64_multi_array_stamped.hpp" +#include "tier4_planning_msgs/msg/path_with_lane_id.hpp" #include #include @@ -35,11 +35,11 @@ namespace planning_debug_tools { -using autoware_auto_planning_msgs::msg::Path; -using autoware_auto_planning_msgs::msg::PathWithLaneId; -using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_planning_msgs::msg::Path; +using autoware_planning_msgs::msg::Trajectory; using nav_msgs::msg::Odometry; using planning_debug_tools::msg::TrajectoryDebugInfo; +using tier4_planning_msgs::msg::PathWithLaneId; template class TrajectoryAnalyzer diff --git a/planning/planning_debug_tools/include/planning_debug_tools/util.hpp b/planning/planning_debug_tools/include/planning_debug_tools/util.hpp index 1f0b9a93..99230de9 100644 --- a/planning/planning_debug_tools/include/planning_debug_tools/util.hpp +++ b/planning/planning_debug_tools/include/planning_debug_tools/util.hpp @@ -19,21 +19,21 @@ #include "rclcpp/rclcpp.hpp" #include "tier4_autoware_utils/geometry/geometry.hpp" -#include "autoware_auto_planning_msgs/msg/path.hpp" -#include "autoware_auto_planning_msgs/msg/path_with_lane_id.hpp" -#include "autoware_auto_planning_msgs/msg/trajectory.hpp" +#include "autoware_planning_msgs/msg/path.hpp" +#include "autoware_planning_msgs/msg/trajectory.hpp" +#include "tier4_planning_msgs/msg/path_with_lane_id.hpp" #include namespace planning_debug_tools { -using autoware_auto_planning_msgs::msg::PathPoint; -using autoware_auto_planning_msgs::msg::PathPointWithLaneId; -using autoware_auto_planning_msgs::msg::TrajectoryPoint; +using autoware_planning_msgs::msg::PathPoint; +using autoware_planning_msgs::msg::TrajectoryPoint; using tier4_autoware_utils::calcDistance2d; using tier4_autoware_utils::getPoint; using tier4_autoware_utils::getRPY; +using tier4_planning_msgs::msg::PathPointWithLaneId; double getVelocity(const PathPoint & p) { diff --git a/planning/planning_debug_tools/package.xml b/planning/planning_debug_tools/package.xml index 14db1277..010e9325 100644 --- a/planning/planning_debug_tools/package.xml +++ b/planning/planning_debug_tools/package.xml @@ -17,7 +17,7 @@ rosidl_default_generators - autoware_auto_planning_msgs + autoware_planning_msgs geometry_msgs motion_utils nav_msgs diff --git a/planning/planning_debug_tools/scripts/closest_velocity_checker.py b/planning/planning_debug_tools/scripts/closest_velocity_checker.py index 4123766a..bf7f2517 100755 --- a/planning/planning_debug_tools/scripts/closest_velocity_checker.py +++ b/planning/planning_debug_tools/scripts/closest_velocity_checker.py @@ -16,12 +16,12 @@ import time -from autoware_auto_control_msgs.msg import AckermannControlCommand -from autoware_auto_planning_msgs.msg import Path -from autoware_auto_planning_msgs.msg import PathWithLaneId -from autoware_auto_planning_msgs.msg import Trajectory -from autoware_auto_vehicle_msgs.msg import Engage -from autoware_auto_vehicle_msgs.msg import VelocityReport +from autoware_control_msgs.msg import Control +from autoware_planning_msgs.msg import Path +from tier4_planning_msgs.msg import PathWithLaneId +from autoware_planning_msgs.msg import Trajectory +from autoware_vehicle_msgs.msg import Engage +from autoware_vehicle_msgs.msg import VelocityReport from geometry_msgs.msg import Pose from nav_msgs.msg import Odometry import numpy as np 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 a30ac9b2..5f83b950 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 @@ -19,11 +19,10 @@ from subprocess import check_output import time -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 as AutoTrafficSignalArray -from autoware_perception_msgs.msg import TrafficSignalArray +from autoware_perception_msgs.msg import DetectedObjects +from autoware_perception_msgs.msg import PredictedObjects +from autoware_perception_msgs.msg import TrackedObjects +from autoware_perception_msgs.msg import TrafficLightGroupArray from geometry_msgs.msg import PoseStamped from geometry_msgs.msg import PoseWithCovarianceStamped from nav_msgs.msg import Odometry @@ -45,7 +44,6 @@ def __init__(self, args, name): self.rosbag_objects_data = [] self.rosbag_ego_odom_data = [] self.rosbag_traffic_signals_data = [] - self.is_auto_traffic_signals = False # subscriber self.sub_odom = self.create_subscription( @@ -91,15 +89,9 @@ def __init__(self, args, name): self.load_rosbag(args.bag) print("Ended loading rosbag") - # temporary support old auto msgs - if self.is_auto_traffic_signals: - self.auto_traffic_signals_pub = self.create_publisher( - AutoTrafficSignalArray, "/perception/traffic_light_recognition/traffic_signals", 1 - ) - else: - self.traffic_signals_pub = self.create_publisher( - TrafficSignalArray, "/perception/traffic_light_recognition/traffic_signals", 1 - ) + self.traffic_signals_pub = self.create_publisher( + TrafficLightGroupArray, "/perception/traffic_light_recognition/traffic_signals", 1 + ) # wait for ready to publish/subscribe time.sleep(1.0) @@ -136,9 +128,6 @@ def load_rosbag(self, rosbag2_path: str): self.rosbag_ego_odom_data.append((stamp, msg)) if topic == traffic_signals_topic: self.rosbag_traffic_signals_data.append((stamp, msg)) - self.is_auto_traffic_signals = ( - "autoware_auto_perception_msgs" in type(msg).__module__ - ) def kill_online_perception_node(self): # kill node if required diff --git a/planning/planning_debug_tools/scripts/trajectory_visualizer.py b/planning/planning_debug_tools/scripts/trajectory_visualizer.py index 10bd41c5..dfa16d49 100755 --- a/planning/planning_debug_tools/scripts/trajectory_visualizer.py +++ b/planning/planning_debug_tools/scripts/trajectory_visualizer.py @@ -16,13 +16,11 @@ import argparse -from autoware_auto_planning_msgs.msg import Path -from autoware_auto_planning_msgs.msg import PathPoint -from autoware_auto_planning_msgs.msg import PathPointWithLaneId -from autoware_auto_planning_msgs.msg import PathWithLaneId -from autoware_auto_planning_msgs.msg import Trajectory -from autoware_auto_planning_msgs.msg import TrajectoryPoint -from autoware_auto_vehicle_msgs.msg import VelocityReport +from autoware_planning_msgs.msg import Path +from autoware_planning_msgs.msg import PathPoint +from autoware_planning_msgs.msg import Trajectory +from autoware_planning_msgs.msg import TrajectoryPoint +from autoware_vehicle_msgs.msg import VelocityReport from geometry_msgs.msg import Pose from matplotlib import animation import matplotlib.pyplot as plt @@ -33,6 +31,8 @@ from rclpy.node import Node from tf2_ros.buffer import Buffer from tf2_ros.transform_listener import TransformListener +from tier4_planning_msgs.msg import PathPointWithLaneId +from tier4_planning_msgs.msg import PathWithLaneId from tier4_planning_msgs.msg import VelocityLimit parser = argparse.ArgumentParser() diff --git a/simulator/simulator_compatibility_test/README.md b/simulator/simulator_compatibility_test/README.md index 5dc9d233..97a5e598 100644 --- a/simulator/simulator_compatibility_test/README.md +++ b/simulator/simulator_compatibility_test/README.md @@ -147,22 +147,22 @@ Detailed process | Name | Type | Description | | ---------------------------------------- | ------------------------------------------------------- | ------------------ | -| `/vehicle/status/control_mode` | `autoware_auto_vehicle_msgs::msg::ControlModeReport` | for [Test Case #1] | -| `/vehicle/status/gear_status` | `autoware_auto_vehicle_msgs::msg::GearReport` | for [Test Case #2] | -| `/vehicle/status/velocity_status` | `autoware_auto_vehicle_msgs::msg::VelocityReport` | for [Test Case #3] | -| `/vehicle/status/steering_status` | `autoware_auto_vehicle_msgs::msg::SteeringReport` | for [Test Case #4] | -| `/vehicle/status/turn_indicators_status` | `autoware_auto_vehicle_msgs::msg::TurnIndicatorsReport` | for [Test Case #5] | -| `/vehicle/status/hazard_lights_status` | `autoware_auto_vehicle_msgs::msg::HazardLightsReport` | for [Test Case #6] | +| `/vehicle/status/control_mode` | `autoware_vehicle_msgs::msg::ControlModeReport` | for [Test Case #1] | +| `/vehicle/status/gear_status` | `autoware_vehicle_msgs::msg::GearReport` | for [Test Case #2] | +| `/vehicle/status/velocity_status` | `autoware_vehicle_msgs::msg::VelocityReport` | for [Test Case #3] | +| `/vehicle/status/steering_status` | `autoware_vehicle_msgs::msg::SteeringReport` | for [Test Case #4] | +| `/vehicle/status/turn_indicators_status` | `autoware_vehicle_msgs::msg::TurnIndicatorsReport` | for [Test Case #5] | +| `/vehicle/status/hazard_lights_status` | `autoware_vehicle_msgs::msg::HazardLightsReport` | for [Test Case #6] | ### Output | Name | Type | Description | | -------------------------------------- | ---------------------------------------------------- | ---------------------- | -| `/control/command/control_mode_cmd` | `autoware_auto_vehicle_msgs/ControlModeCommand` | for [Test Case #1] | -| `/control/command/gear_cmd` | `autoware_auto_vehicle_msgs/GearCommand` | for [Test Case #2] | -| `/control/command/control_cmd` | `autoware_auto_vehicle_msgs/AckermannControlCommand` | for [Test Case #3, #4] | -| `/vehicle/status/steering_status` | `autoware_auto_vehicle_msgs/TurnIndicatorsCommand` | for [Test Case #5] | -| `/control/command/turn_indicators_cmd` | `autoware_auto_vehicle_msgs/HazardLightsCommand` | for [Test Case #6] | +| `/control/command/control_mode_cmd` | `autoware_vehicle_msgs/ControlModeCommand` | for [Test Case #1] | +| `/control/command/gear_cmd` | `autoware_vehicle_msgs/GearCommand` | for [Test Case #2] | +| `/control/command/control_cmd` | `autoware_vehicle_msgs/AckermannControlCommand` | for [Test Case #3, #4] | +| `/vehicle/status/steering_status` | `autoware_vehicle_msgs/TurnIndicatorsCommand` | for [Test Case #5] | +| `/control/command/turn_indicators_cmd` | `autoware_vehicle_msgs/HazardLightsCommand` | for [Test Case #6] | ## Parameters diff --git a/simulator/simulator_compatibility_test/package.xml b/simulator/simulator_compatibility_test/package.xml index d0ed3e69..51f09080 100644 --- a/simulator/simulator_compatibility_test/package.xml +++ b/simulator/simulator_compatibility_test/package.xml @@ -9,14 +9,14 @@ Shumpei Wakabayashi TODO: License declaration - autoware_auto_control_msgs - autoware_auto_geometry_msgs - autoware_auto_mapping_msgs - autoware_auto_msgs - autoware_auto_perception_msgs - autoware_auto_planning_msgs - autoware_auto_system_msgs - autoware_auto_vehicle_msgs + autoware_control_msgs + autoware_geometry_msgs + autoware_map_msgs + autoware_msgs + autoware_perception_msgs + autoware_planning_msgs + autoware_system_msgs + autoware_vehicle_msgs rclpy ament_copyright 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 9e5b0dfb..037c2f93 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 @@ -1,6 +1,6 @@ -from autoware_auto_control_msgs.msg import AckermannControlCommand -from autoware_auto_control_msgs.msg import AckermannLateralCommand -from autoware_auto_control_msgs.msg import LongitudinalCommand +from autoware_control_msgs.msg import Control as ControlCommand +from autoware_control_msgs.msg import Lateral as LateralCommand +from autoware_control_msgs.msg import Longitudinal as LongitudinalCommand import rclpy from rclpy.node import Node from rclpy.qos import QoSDurabilityPolicy @@ -9,7 +9,7 @@ from rclpy.qos import QoSReliabilityPolicy -class PublisherAckermannControlCommand(Node): +class ControlCommand(Node): def __init__(self): super().__init__("ackermann_control_command_publisher") @@ -23,12 +23,12 @@ def __init__(self): durability=QoSDurabilityPolicy.TRANSIENT_LOCAL, ) self.topic = "/control/command/control_cmd" - self.publisher_ = self.create_publisher(AckermannControlCommand, self.topic, QOS_RKL10TL) + self.publisher_ = self.create_publisher(ControlCommand, self.topic, QOS_RKL10TL) def publish_msg(self, control_cmd): stamp = self.get_clock().now().to_msg() - msg = AckermannControlCommand() - lateral_cmd = AckermannLateralCommand() + msg = ControlCommand() + lateral_cmd = LateralCommand() longitudinal_cmd = LongitudinalCommand() lateral_cmd.stamp.sec = stamp.sec lateral_cmd.stamp.nanosec = stamp.nanosec @@ -53,7 +53,7 @@ def publish_msg(self, control_cmd): def main(args=None): rclpy.init(args=args) - node = PublisherAckermannControlCommand() + node = ControlCommand() try: rclpy.spin(node) except KeyboardInterrupt: diff --git a/simulator/simulator_compatibility_test/simulator_compatibility_test/publishers/control_mode_command.py b/simulator/simulator_compatibility_test/simulator_compatibility_test/publishers/control_mode_command.py index c39c7848..aaac318b 100644 --- a/simulator/simulator_compatibility_test/simulator_compatibility_test/publishers/control_mode_command.py +++ b/simulator/simulator_compatibility_test/simulator_compatibility_test/publishers/control_mode_command.py @@ -1,6 +1,6 @@ from enum import Enum -from autoware_auto_vehicle_msgs.msg import ControlModeCommand +from autoware_vehicle_msgs.msg import ControlModeCommand import rclpy from rclpy.node import Node from rclpy.qos import QoSDurabilityPolicy diff --git a/simulator/simulator_compatibility_test/simulator_compatibility_test/publishers/gear_command.py b/simulator/simulator_compatibility_test/simulator_compatibility_test/publishers/gear_command.py index d17329df..dbb6cc17 100644 --- a/simulator/simulator_compatibility_test/simulator_compatibility_test/publishers/gear_command.py +++ b/simulator/simulator_compatibility_test/simulator_compatibility_test/publishers/gear_command.py @@ -1,6 +1,6 @@ from enum import Enum -from autoware_auto_vehicle_msgs.msg import GearCommand +from autoware_vehicle_msgs.msg import GearCommand import rclpy from rclpy.node import Node from rclpy.qos import QoSDurabilityPolicy diff --git a/simulator/simulator_compatibility_test/simulator_compatibility_test/subscribers/control_mode_report.py b/simulator/simulator_compatibility_test/simulator_compatibility_test/subscribers/control_mode_report.py index 965d2ac7..347f7326 100644 --- a/simulator/simulator_compatibility_test/simulator_compatibility_test/subscribers/control_mode_report.py +++ b/simulator/simulator_compatibility_test/simulator_compatibility_test/subscribers/control_mode_report.py @@ -1,6 +1,6 @@ from enum import Enum -from autoware_auto_vehicle_msgs.msg import ControlModeReport +from autoware_vehicle_msgs.msg import ControlModeReport import rclpy from rclpy.node import Node from rclpy.qos import QoSDurabilityPolicy diff --git a/simulator/simulator_compatibility_test/simulator_compatibility_test/subscribers/gear_report.py b/simulator/simulator_compatibility_test/simulator_compatibility_test/subscribers/gear_report.py index f8c9ec30..ebbe470f 100644 --- a/simulator/simulator_compatibility_test/simulator_compatibility_test/subscribers/gear_report.py +++ b/simulator/simulator_compatibility_test/simulator_compatibility_test/subscribers/gear_report.py @@ -1,6 +1,6 @@ from enum import Enum -from autoware_auto_vehicle_msgs.msg import GearReport +from autoware_vehicle_msgs.msg import GearReport import rclpy from rclpy.node import Node from rclpy.qos import QoSDurabilityPolicy diff --git a/simulator/simulator_compatibility_test/simulator_compatibility_test/subscribers/hazard_lights_report.py b/simulator/simulator_compatibility_test/simulator_compatibility_test/subscribers/hazard_lights_report.py index b9399137..10b30d3a 100644 --- a/simulator/simulator_compatibility_test/simulator_compatibility_test/subscribers/hazard_lights_report.py +++ b/simulator/simulator_compatibility_test/simulator_compatibility_test/subscribers/hazard_lights_report.py @@ -1,6 +1,6 @@ from enum import Enum -from autoware_auto_vehicle_msgs.msg import HazardLightsReport +from autoware_vehicle_msgs.msg import HazardLightsReport import rclpy from rclpy.node import Node from rclpy.qos import QoSDurabilityPolicy diff --git a/simulator/simulator_compatibility_test/simulator_compatibility_test/subscribers/steering_report.py b/simulator/simulator_compatibility_test/simulator_compatibility_test/subscribers/steering_report.py index 64967239..493637fd 100644 --- a/simulator/simulator_compatibility_test/simulator_compatibility_test/subscribers/steering_report.py +++ b/simulator/simulator_compatibility_test/simulator_compatibility_test/subscribers/steering_report.py @@ -1,4 +1,4 @@ -from autoware_auto_vehicle_msgs.msg import SteeringReport +from autoware_vehicle_msgs.msg import SteeringReport import rclpy from rclpy.node import Node from rclpy.qos import QoSDurabilityPolicy diff --git a/simulator/simulator_compatibility_test/simulator_compatibility_test/subscribers/turn_indicators_report.py b/simulator/simulator_compatibility_test/simulator_compatibility_test/subscribers/turn_indicators_report.py index 6d3727ea..599c918d 100644 --- a/simulator/simulator_compatibility_test/simulator_compatibility_test/subscribers/turn_indicators_report.py +++ b/simulator/simulator_compatibility_test/simulator_compatibility_test/subscribers/turn_indicators_report.py @@ -1,6 +1,6 @@ from enum import Enum -from autoware_auto_vehicle_msgs.msg import TurnIndicatorsReport +from autoware_vehicle_msgs.msg import TurnIndicatorsReport import rclpy from rclpy.node import Node from rclpy.qos import QoSDurabilityPolicy diff --git a/simulator/simulator_compatibility_test/simulator_compatibility_test/subscribers/velocity_report.py b/simulator/simulator_compatibility_test/simulator_compatibility_test/subscribers/velocity_report.py index c83f1b09..0e632c87 100644 --- a/simulator/simulator_compatibility_test/simulator_compatibility_test/subscribers/velocity_report.py +++ b/simulator/simulator_compatibility_test/simulator_compatibility_test/subscribers/velocity_report.py @@ -1,4 +1,4 @@ -from autoware_auto_vehicle_msgs.msg import VelocityReport +from autoware_vehicle_msgs.msg import VelocityReport import rclpy from rclpy.node import Node from rclpy.qos import QoSDurabilityPolicy diff --git a/simulator/simulator_compatibility_test/test_base/test_01_control_mode_and_report.py b/simulator/simulator_compatibility_test/test_base/test_01_control_mode_and_report.py index d1aad9c9..d6e4d96c 100644 --- a/simulator/simulator_compatibility_test/test_base/test_01_control_mode_and_report.py +++ b/simulator/simulator_compatibility_test/test_base/test_01_control_mode_and_report.py @@ -1,7 +1,7 @@ from enum import Enum import time -from autoware_auto_vehicle_msgs.msg import ControlModeCommand +from autoware_vehicle_msgs.msg import ControlModeCommand import pytest import rclpy from rclpy.executors import MultiThreadedExecutor diff --git a/simulator/simulator_compatibility_test/test_base/test_02_change_gear_and_report.py b/simulator/simulator_compatibility_test/test_base/test_02_change_gear_and_report.py index d86a569c..75207bb5 100644 --- a/simulator/simulator_compatibility_test/test_base/test_02_change_gear_and_report.py +++ b/simulator/simulator_compatibility_test/test_base/test_02_change_gear_and_report.py @@ -1,6 +1,6 @@ import time -from autoware_auto_vehicle_msgs.msg import GearCommand +from autoware_vehicle_msgs.msg import GearCommand import rclpy from rclpy.executors import MultiThreadedExecutor from rclpy.qos import QoSDurabilityPolicy 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 d55fa7eb..176ef5a8 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 @@ -1,8 +1,8 @@ import time -from autoware_auto_control_msgs.msg import AckermannControlCommand -from autoware_auto_control_msgs.msg import AckermannLateralCommand -from autoware_auto_control_msgs.msg import LongitudinalCommand +from autoware_control_msgs.msg import Control as ControlCommand +from autoware_control_msgs.msg import Lateral as LateralCommand +from autoware_control_msgs.msg import Longitudinal as LongitudinalCommand import pytest import rclpy from rclpy.executors import MultiThreadedExecutor @@ -39,13 +39,13 @@ def setup_class(cls) -> None: cls.node = rclpy.create_node("test_03_longitudinal_command_and_report_base") cls.sub = cls.node.create_subscription( - AckermannControlCommand, + ControlCommand, "/control/command/control_cmd", lambda msg: cls.msgs_rx.append(msg), 10, ) cls.pub = cls.node.create_publisher( - AckermannControlCommand, "/control/command/control_cmd", QOS_RKL10TL + ControlCommand, "/control/command/control_cmd", QOS_RKL10TL ) cls.sub_velocity_report = SubscriberVelocityReport() cls.executor = MultiThreadedExecutor() @@ -71,8 +71,8 @@ def init_vehicle(self): def generate_control_msg(self, control_cmd): stamp = self.node.get_clock().now().to_msg() - msg = AckermannControlCommand() - lateral_cmd = AckermannLateralCommand() + msg = ControlCommand() + lateral_cmd = LateralCommand() longitudinal_cmd = LongitudinalCommand() lateral_cmd.stamp.sec = stamp.sec lateral_cmd.stamp.nanosec = stamp.nanosec 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 0648ffd2..5959bdef 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 @@ -1,8 +1,8 @@ import time -from autoware_auto_control_msgs.msg import AckermannControlCommand -from autoware_auto_control_msgs.msg import AckermannLateralCommand -from autoware_auto_control_msgs.msg import LongitudinalCommand +from autoware_control_msgs.msg import Control as ControlCommand +from autoware_control_msgs.msg import Lateral as LateralCommand +from autoware_control_msgs.msg import Longitudinal as LongitudinalCommand import pytest import rclpy from rclpy.executors import MultiThreadedExecutor @@ -38,13 +38,13 @@ def setup_class(cls) -> None: } cls.node = rclpy.create_node("test_04_lateral_command_and_report_base") cls.sub = cls.node.create_subscription( - AckermannControlCommand, + ControlCommand, "/control/command/control_cmd", lambda msg: cls.msgs_rx.append(msg), 10, ) cls.pub = cls.node.create_publisher( - AckermannControlCommand, "/control/command/control_cmd", QOS_RKL10TL + ControlCommand, "/control/command/control_cmd", QOS_RKL10TL ) cls.sub_steering_report = SubscriberSteeringReport() cls.executor = MultiThreadedExecutor() @@ -70,8 +70,8 @@ def init_vehicle(self): def generate_control_msg(self, control_cmd): stamp = self.node.get_clock().now().to_msg() - msg = AckermannControlCommand() - lateral_cmd = AckermannLateralCommand() + msg = ControlCommand() + lateral_cmd = LateralCommand() longitudinal_cmd = LongitudinalCommand() lateral_cmd.stamp.sec = stamp.sec lateral_cmd.stamp.nanosec = stamp.nanosec diff --git a/simulator/simulator_compatibility_test/test_base/test_05_turn_indicators_cmd_and_report.py b/simulator/simulator_compatibility_test/test_base/test_05_turn_indicators_cmd_and_report.py index 974f61e1..c26f7d2f 100644 --- a/simulator/simulator_compatibility_test/test_base/test_05_turn_indicators_cmd_and_report.py +++ b/simulator/simulator_compatibility_test/test_base/test_05_turn_indicators_cmd_and_report.py @@ -1,7 +1,7 @@ from enum import Enum import time -from autoware_auto_vehicle_msgs.msg import TurnIndicatorsCommand +from autoware_vehicle_msgs.msg import TurnIndicatorsCommand import pytest import rclpy from rclpy.executors import MultiThreadedExecutor diff --git a/simulator/simulator_compatibility_test/test_base/test_06_hazard_lights_cmd_and_report.py b/simulator/simulator_compatibility_test/test_base/test_06_hazard_lights_cmd_and_report.py index 7e361d54..950eabcb 100644 --- a/simulator/simulator_compatibility_test/test_base/test_06_hazard_lights_cmd_and_report.py +++ b/simulator/simulator_compatibility_test/test_base/test_06_hazard_lights_cmd_and_report.py @@ -1,7 +1,7 @@ from enum import Enum import time -from autoware_auto_vehicle_msgs.msg import HazardLightsCommand +from autoware_vehicle_msgs.msg import HazardLightsCommand import pytest import rclpy from rclpy.executors import MultiThreadedExecutor