From 35de87462fed7454daf6a7ecbe5409d6ed629490 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Wed, 5 Jun 2024 03:17:53 +0900 Subject: [PATCH] feat!: change from autoware_auto_msgs to autoware_msgs (#30) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * feat!: replace autoware_auto_msgs with autoware_msgs Signed-off-by: mitsudome-r * style(pre-commit): autofix * feat: port remaining autoware_auto_msgs to autoware_msgs (#32) * feat: port remaining autoware_auto_msgs to autoware_msgs Signed-off-by: Ryohsuke Mitsudome * style(pre-commit): autofix --------- Signed-off-by: Ryohsuke Mitsudome Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * remove autoware_msgs Signed-off-by: M. Fatih Cırıt * remove non-existent dep Signed-off-by: M. Fatih Cırıt --------- Signed-off-by: mitsudome-r Signed-off-by: Ryohsuke Mitsudome Signed-off-by: M. Fatih Cırıt Co-authored-by: mitsudome-r Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com> Co-authored-by: M. Fatih Cırıt --- build_depends.repos | 4 --- common/tier4_control_rviz_plugin/README.md | 22 +++++++------- common/tier4_control_rviz_plugin/package.xml | 4 +-- .../src/tools/manual_controller.cpp | 22 +++++++------- .../src/tools/manual_controller.hpp | 22 +++++++------- .../lateral_error_publisher.hpp | 8 ++--- common/tier4_debug_tools/package.xml | 2 +- .../src/lateral_error_publisher.cpp | 4 +-- .../analyzer_core.hpp | 2 +- .../driving_environment_analyzer_node.hpp | 4 +-- ...iving_environment_analyzer_rviz_plugin.hpp | 4 +-- .../type_alias.hpp | 10 +++---- driving_environment_analyzer/package.xml | 5 ++-- .../src/analyzer_core.cpp | 2 +- .../src/driving_environment_analyzer_node.cpp | 4 +-- ...iving_environment_analyzer_rviz_plugin.cpp | 4 +-- .../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 | 30 +++++++++---------- .../simulator_compatibility_test/package.xml | 14 ++++----- .../publishers/ackermann_control_command.py | 12 ++++---- .../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 +- 39 files changed, 145 insertions(+), 163 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_control_rviz_plugin/README.md b/common/tier4_control_rviz_plugin/README.md index 8bca7777..aed5a92b 100644 --- a/common/tier4_control_rviz_plugin/README.md +++ b/common/tier4_control_rviz_plugin/README.md @@ -6,20 +6,20 @@ This package is to mimic external control for simulation. ### Input -| Name | Type | Description | -| --------------------------------- | ------------------------------------------------- | ----------------------- | -| `/control/current_gate_mode` | `tier4_control_msgs::msg::GateMode` | Current GATE mode | -| `/vehicle/status/velocity_status` | `autoware_auto_vehicle_msgs::msg::VelocityReport` | Current velocity status | -| `/api/autoware/get/engage` | `tier4_external_api_msgs::srv::Engage` | Getting Engage | -| `/vehicle/status/gear_status` | `autoware_auto_vehicle_msgs::msg::GearReport` | The state of GEAR | +| Name | Type | Description | +| --------------------------------- | -------------------------------------------- | ----------------------- | +| `/control/current_gate_mode` | `tier4_control_msgs::msg::GateMode` | Current GATE mode | +| `/vehicle/status/velocity_status` | `autoware_vehicle_msgs::msg::VelocityReport` | Current velocity status | +| `/api/autoware/get/engage` | `tier4_external_api_msgs::srv::Engage` | Getting Engage | +| `/vehicle/status/gear_status` | `autoware_vehicle_msgs::msg::GearReport` | The state of GEAR | ### Output -| Name | Type | Description | -| -------------------------------- | ---------------------------------------------------------- | ----------------------- | -| `/control/gate_mode_cmd` | `tier4_control_msgs::msg::GateMode` | GATE mode | -| `/external/selected/control_cmd` | `autoware_auto_control_msgs::msg::AckermannControlCommand` | AckermannControlCommand | -| `/external/selected/gear_cmd` | `autoware_auto_vehicle_msgs::msg::GearCommand` | GEAR | +| Name | Type | Description | +| -------------------------------- | -------------------------------------------- | --------------- | +| `/control/gate_mode_cmd` | `tier4_control_msgs::msg::GateMode` | GATE mode | +| `/external/selected/control_cmd` | `autoware_control_msgs::msg::ControlCommand` | Control command | +| `/external/selected/gear_cmd` | `autoware_vehicle_msgs::msg::GearCommand` | GEAR | ## Usage diff --git a/common/tier4_control_rviz_plugin/package.xml b/common/tier4_control_rviz_plugin/package.xml index 73562a76..bec78de0 100644 --- a/common/tier4_control_rviz_plugin/package.xml +++ b/common/tier4_control_rviz_plugin/package.xml @@ -10,8 +10,8 @@ ament_cmake_auto autoware_cmake - autoware_auto_control_msgs - autoware_auto_vehicle_msgs + autoware_control_msgs + autoware_vehicle_msgs libqt5-core libqt5-gui libqt5-widgets diff --git a/common/tier4_control_rviz_plugin/src/tools/manual_controller.cpp b/common/tier4_control_rviz_plugin/src/tools/manual_controller.cpp index 8bbb096f..7fd700b2 100644 --- a/common/tier4_control_rviz_plugin/src/tools/manual_controller.cpp +++ b/common/tier4_control_rviz_plugin/src/tools/manual_controller.cpp @@ -102,11 +102,11 @@ ManualController::ManualController(QWidget * parent) : rviz_common::Panel(parent void ManualController::update() { if (!raw_node_) return; - AckermannControlCommand ackermann; + Control control_cmd; { - ackermann.stamp = raw_node_->get_clock()->now(); - ackermann.lateral.steering_tire_angle = steering_angle_; - ackermann.longitudinal.speed = cruise_velocity_; + control_cmd.stamp = raw_node_->get_clock()->now(); + control_cmd.lateral.steering_tire_angle = steering_angle_; + control_cmd.longitudinal.velocity = cruise_velocity_; /** * @brief Calculate desired acceleration by simple BackSteppingControl * V = 0.5*(v-v_des)^2 >= 0 @@ -118,21 +118,21 @@ void ManualController::update() const double v_des = cruise_velocity_; const double a = current_acceleration_; const double a_des = k * (v - v_des) + a; - ackermann.longitudinal.acceleration = std::clamp(a_des, -1.0, 1.0); + control_cmd.longitudinal.acceleration = std::clamp(a_des, -1.0, 1.0); } GearCommand gear_cmd; { const double eps = 0.001; - if (ackermann.longitudinal.speed > eps && current_velocity_ > -eps) { + if (control_cmd.longitudinal.velocity > eps && current_velocity_ > -eps) { gear_cmd.command = GearCommand::DRIVE; - } else if (ackermann.longitudinal.speed < -eps && current_velocity_ < eps) { + } else if (control_cmd.longitudinal.velocity < -eps && current_velocity_ < eps) { gear_cmd.command = GearCommand::REVERSE; - ackermann.longitudinal.acceleration *= -1.0; + control_cmd.longitudinal.acceleration *= -1.0; } else { gear_cmd.command = GearCommand::PARK; } } - pub_control_command_->publish(ackermann); + pub_control_command_->publish(control_cmd); pub_gear_cmd_->publish(gear_cmd); } @@ -170,8 +170,8 @@ void ManualController::onInitialize() pub_gate_mode_ = raw_node_->create_publisher("/control/gate_mode_cmd", rclcpp::QoS(1)); - pub_control_command_ = raw_node_->create_publisher( - "/external/selected/control_cmd", rclcpp::QoS(1)); + pub_control_command_ = + raw_node_->create_publisher("/external/selected/control_cmd", rclcpp::QoS(1)); pub_gear_cmd_ = raw_node_->create_publisher("/external/selected/gear_cmd", 1); } diff --git a/common/tier4_control_rviz_plugin/src/tools/manual_controller.hpp b/common/tier4_control_rviz_plugin/src/tools/manual_controller.hpp index aaa625bf..61b4f2a0 100644 --- a/common/tier4_control_rviz_plugin/src/tools/manual_controller.hpp +++ b/common/tier4_control_rviz_plugin/src/tools/manual_controller.hpp @@ -24,13 +24,13 @@ #include #include -#include "autoware_auto_vehicle_msgs/msg/velocity_report.hpp" +#include "autoware_vehicle_msgs/msg/velocity_report.hpp" #include "geometry_msgs/msg/accel_with_covariance_stamped.hpp" #include "geometry_msgs/msg/twist.hpp" -#include -#include -#include -#include +#include +#include +#include +#include #include #include @@ -38,15 +38,15 @@ namespace rviz_plugins { -using autoware_auto_control_msgs::msg::AckermannControlCommand; -using autoware_auto_vehicle_msgs::msg::GearCommand; -using autoware_auto_vehicle_msgs::msg::VelocityReport; +using autoware_control_msgs::msg::Control; +using autoware_vehicle_msgs::msg::GearCommand; +using autoware_vehicle_msgs::msg::VelocityReport; using geometry_msgs::msg::AccelWithCovarianceStamped; using geometry_msgs::msg::Twist; using tier4_control_msgs::msg::GateMode; using EngageSrv = tier4_external_api_msgs::srv::Engage; -using autoware_auto_vehicle_msgs::msg::Engage; -using autoware_auto_vehicle_msgs::msg::GearReport; +using autoware_vehicle_msgs::msg::Engage; +using autoware_vehicle_msgs::msg::GearReport; class ManualController : public rviz_common::Panel { @@ -77,7 +77,7 @@ public Q_SLOTS: // NOLINT for Qt rclcpp::Subscription::SharedPtr sub_velocity_; rclcpp::Subscription::SharedPtr sub_engage_; rclcpp::Publisher::SharedPtr pub_gate_mode_; - rclcpp::Publisher::SharedPtr pub_control_command_; + rclcpp::Publisher::SharedPtr pub_control_command_; rclcpp::Publisher::SharedPtr pub_gear_cmd_; rclcpp::Client::SharedPtr client_engage_; rclcpp::Subscription::SharedPtr sub_gear_; 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/analyzer_core.hpp b/driving_environment_analyzer/include/driving_environment_analyzer/analyzer_core.hpp index 09188fc4..3227faa6 100644 --- a/driving_environment_analyzer/include/driving_environment_analyzer/analyzer_core.hpp +++ b/driving_environment_analyzer/include/driving_environment_analyzer/analyzer_core.hpp @@ -60,7 +60,7 @@ class AnalyzerCore odd_raw_data_ = getRawData(timestamp); } - void setMap(const HADMapBin & msg) { route_handler_.setMap(msg); } + void setMap(const LaneletMapBin & msg) { route_handler_.setMap(msg); } void clearData() { odd_raw_data_ = std::nullopt; } diff --git a/driving_environment_analyzer/include/driving_environment_analyzer/driving_environment_analyzer_node.hpp b/driving_environment_analyzer/include/driving_environment_analyzer/driving_environment_analyzer_node.hpp index b6ddc1ad..aed631cb 100644 --- a/driving_environment_analyzer/include/driving_environment_analyzer/driving_environment_analyzer_node.hpp +++ b/driving_environment_analyzer/include/driving_environment_analyzer/driving_environment_analyzer_node.hpp @@ -31,12 +31,12 @@ class DrivingEnvironmentAnalyzerNode : public rclcpp::Node explicit DrivingEnvironmentAnalyzerNode(const rclcpp::NodeOptions & node_options); private: - void onMap(const HADMapBin::ConstSharedPtr map_msg); + void onMap(const LaneletMapBin::ConstSharedPtr map_msg); void analyze(); std::shared_ptr analyzer_; - rclcpp::Subscription::SharedPtr sub_map_; + rclcpp::Subscription::SharedPtr sub_map_; rclcpp::TimerBase::SharedPtr timer_; rosbag2_cpp::Reader reader_; }; diff --git a/driving_environment_analyzer/include/driving_environment_analyzer/driving_environment_analyzer_rviz_plugin.hpp b/driving_environment_analyzer/include/driving_environment_analyzer/driving_environment_analyzer_rviz_plugin.hpp index caba7599..3d12c350 100644 --- a/driving_environment_analyzer/include/driving_environment_analyzer/driving_environment_analyzer_rviz_plugin.hpp +++ b/driving_environment_analyzer/include/driving_environment_analyzer/driving_environment_analyzer_rviz_plugin.hpp @@ -58,7 +58,7 @@ public Q_SLOTS: void onClickAnalyzeDynamicODDFactor(); private: - void onMap(const HADMapBin::ConstSharedPtr map_msg); + void onMap(const LaneletMapBin::ConstSharedPtr map_msg); std::shared_ptr analyzer_; @@ -75,7 +75,7 @@ public Q_SLOTS: QPushButton * set_timestamp_btn_; rclcpp::Node::SharedPtr raw_node_; - rclcpp::Subscription::SharedPtr sub_map_; + rclcpp::Subscription::SharedPtr sub_map_; rclcpp::Publisher::SharedPtr pub_odometry_; rclcpp::Publisher::SharedPtr pub_objects_; rclcpp::Publisher::SharedPtr pub_tf_; diff --git a/driving_environment_analyzer/include/driving_environment_analyzer/type_alias.hpp b/driving_environment_analyzer/include/driving_environment_analyzer/type_alias.hpp index 30721bed..a0c4625d 100644 --- a/driving_environment_analyzer/include/driving_environment_analyzer/type_alias.hpp +++ b/driving_environment_analyzer/include/driving_environment_analyzer/type_alias.hpp @@ -21,8 +21,8 @@ #include "tier4_rtc_msgs/msg/command.hpp" #include "tier4_rtc_msgs/msg/cooperate_status_array.hpp" #include "tier4_rtc_msgs/msg/module.hpp" -#include -#include +#include +#include #include #include #include @@ -40,9 +40,9 @@ using nav_msgs::msg::Odometry; using tf2_msgs::msg::TFMessage; // autoware -using autoware_auto_mapping_msgs::msg::HADMapBin; -using autoware_auto_perception_msgs::msg::ObjectClassification; -using autoware_auto_perception_msgs::msg::PredictedObjects; +using autoware_map_msgs::msg::LaneletMapBin; +using autoware_perception_msgs::msg::ObjectClassification; +using autoware_perception_msgs::msg::PredictedObjects; using autoware_planning_msgs::msg::LaneletRoute; using tier4_rtc_msgs::msg::Command; using tier4_rtc_msgs::msg::CooperateStatusArray; diff --git a/driving_environment_analyzer/package.xml b/driving_environment_analyzer/package.xml index bc77925a..df2ea6b4 100644 --- a/driving_environment_analyzer/package.xml +++ b/driving_environment_analyzer/package.xml @@ -15,10 +15,9 @@ autoware_cmake autoware_adapi_v1_msgs - autoware_auto_perception_msgs - autoware_auto_planning_msgs - 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/analyzer_core.cpp b/driving_environment_analyzer/src/analyzer_core.cpp index 4ff435ef..06d0fda9 100644 --- a/driving_environment_analyzer/src/analyzer_core.cpp +++ b/driving_environment_analyzer/src/analyzer_core.cpp @@ -53,7 +53,7 @@ void AnalyzerCore::setBagFile(const std::string & file_name) route_handler_.setRoute(opt_route.value()); } - const auto opt_map = getLastTopic("/map/vector_map"); + const auto opt_map = getLastTopic("/map/vector_map"); if (opt_map.has_value()) { route_handler_.setMap(opt_map.value()); } diff --git a/driving_environment_analyzer/src/driving_environment_analyzer_node.cpp b/driving_environment_analyzer/src/driving_environment_analyzer_node.cpp index 2517509d..6ec4b567 100644 --- a/driving_environment_analyzer/src/driving_environment_analyzer_node.cpp +++ b/driving_environment_analyzer/src/driving_environment_analyzer_node.cpp @@ -33,7 +33,7 @@ DrivingEnvironmentAnalyzerNode::DrivingEnvironmentAnalyzerNode( timer_ = rclcpp::create_timer( this, get_clock(), 100ms, std::bind(&DrivingEnvironmentAnalyzerNode::analyze, this)); - sub_map_ = create_subscription( + sub_map_ = create_subscription( "input/lanelet2_map", rclcpp::QoS{1}.transient_local(), std::bind(&DrivingEnvironmentAnalyzerNode::onMap, this, _1)); @@ -42,7 +42,7 @@ DrivingEnvironmentAnalyzerNode::DrivingEnvironmentAnalyzerNode( analyzer_->setBagFile(declare_parameter("bag_path")); } -void DrivingEnvironmentAnalyzerNode::onMap(const HADMapBin::ConstSharedPtr msg) +void DrivingEnvironmentAnalyzerNode::onMap(const LaneletMapBin::ConstSharedPtr msg) { analyzer_->setMap(*msg); } diff --git a/driving_environment_analyzer/src/driving_environment_analyzer_rviz_plugin.cpp b/driving_environment_analyzer/src/driving_environment_analyzer_rviz_plugin.cpp index 65717e8f..6045ef72 100644 --- a/driving_environment_analyzer/src/driving_environment_analyzer_rviz_plugin.cpp +++ b/driving_environment_analyzer/src/driving_environment_analyzer_rviz_plugin.cpp @@ -112,7 +112,7 @@ void DrivingEnvironmentAnalyzerPanel::onInitialize() raw_node_ = this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); - sub_map_ = raw_node_->create_subscription( + sub_map_ = raw_node_->create_subscription( "/map/vector_map", rclcpp::QoS{1}.transient_local(), std::bind(&DrivingEnvironmentAnalyzerPanel::onMap, this, _1)); @@ -126,7 +126,7 @@ void DrivingEnvironmentAnalyzerPanel::onInitialize() analyzer_ = std::make_shared(*raw_node_); } -void DrivingEnvironmentAnalyzerPanel::onMap(const HADMapBin::ConstSharedPtr msg) +void DrivingEnvironmentAnalyzerPanel::onMap(const LaneletMapBin::ConstSharedPtr msg) { analyzer_->setMap(*msg); } 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..a8a553a3 100755 --- a/planning/planning_debug_tools/scripts/closest_velocity_checker.py +++ b/planning/planning_debug_tools/scripts/closest_velocity_checker.py @@ -16,12 +16,11 @@ 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 as AckermannControlCommand +from autoware_planning_msgs.msg import Path +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 @@ -32,6 +31,7 @@ from tf2_ros.transform_listener import TransformListener from tier4_debug_msgs.msg import Float32MultiArrayStamped from tier4_debug_msgs.msg import Float32Stamped +from tier4_planning_msgs.msg import PathWithLaneId from tier4_planning_msgs.msg import VelocityLimit REF_LINK = "map" 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..1fcd0ca2 100644 --- a/simulator/simulator_compatibility_test/README.md +++ b/simulator/simulator_compatibility_test/README.md @@ -145,24 +145,24 @@ Detailed process ### Input -| 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] | +| Name | Type | Description | +| ---------------------------------------- | -------------------------------------------------- | ------------------ | +| `/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] | +| Name | Type | Description | +| -------------------------------------- | --------------------------------------------- | ---------------------- | +| `/control/command/control_cmd` | `autoware_control_msgs/Control` | for [Test Case #3, #4] | +| `/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] | +| `/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..fe7f0cd6 100644 --- a/simulator/simulator_compatibility_test/package.xml +++ b/simulator/simulator_compatibility_test/package.xml @@ -9,14 +9,12 @@ 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_map_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..9c643fbb 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 AckermannControlCommand +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") @@ -28,7 +28,7 @@ def __init__(self): def publish_msg(self, control_cmd): stamp = self.get_clock().now().to_msg() msg = AckermannControlCommand() - lateral_cmd = AckermannLateralCommand() + 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