diff --git a/common/tier4_control_rviz_plugin/README.md b/common/tier4_control_rviz_plugin/README.md
index 8bca77771..aed5a92b7 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 73562a766..bec78de02 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 8bbb096f7..7fd700b22 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 aaa625bff..61b4f2a0b 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/driving_environment_analyzer/include/driving_environment_analyzer/analyzer_core.hpp b/driving_environment_analyzer/include/driving_environment_analyzer/analyzer_core.hpp
index 09188fc49..3227faa63 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 b6ddc1ad4..aed631cb6 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 caba75997..3d12c3500 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 30721beda..a0c4625db 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/src/analyzer_core.cpp b/driving_environment_analyzer/src/analyzer_core.cpp
index 4ff435ef3..06d0fda90 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 2517509d5..6ec4b567f 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 65717e8f6..6045ef721 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/scripts/closest_velocity_checker.py b/planning/planning_debug_tools/scripts/closest_velocity_checker.py
index 2a4a5bfdd..a8a553a38 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_control_msgs.msg import Control
+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
diff --git a/simulator/simulator_compatibility_test/README.md b/simulator/simulator_compatibility_test/README.md
index c8af542cc..1fcd0ca24 100644
--- a/simulator/simulator_compatibility_test/README.md
+++ b/simulator/simulator_compatibility_test/README.md
@@ -156,13 +156,13 @@ Detailed process
### Output
-| Name | Type | Description |
-| -------------------------------------- | ----------------------------------------------- | ---------------------- |
-| `/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] |
+| 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/simulator_compatibility_test/publishers/ackermann_control_command.py b/simulator/simulator_compatibility_test/simulator_compatibility_test/publishers/ackermann_control_command.py
index 037c2f930..9c643fbb9 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,4 +1,4 @@
-from autoware_control_msgs.msg import Control as ControlCommand
+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
@@ -23,11 +23,11 @@ def __init__(self):
durability=QoSDurabilityPolicy.TRANSIENT_LOCAL,
)
self.topic = "/control/command/control_cmd"
- self.publisher_ = self.create_publisher(ControlCommand, self.topic, QOS_RKL10TL)
+ self.publisher_ = self.create_publisher(AckermannControlCommand, self.topic, QOS_RKL10TL)
def publish_msg(self, control_cmd):
stamp = self.get_clock().now().to_msg()
- msg = ControlCommand()
+ msg = AckermannControlCommand()
lateral_cmd = LateralCommand()
longitudinal_cmd = LongitudinalCommand()
lateral_cmd.stamp.sec = stamp.sec