diff --git a/vehicle/accel_brake_map_calibrator/include/accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp b/vehicle/accel_brake_map_calibrator/include/accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp index 3580f0546bbfb..6b94b7301540c 100644 --- a/vehicle/accel_brake_map_calibrator/include/accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp +++ b/vehicle/accel_brake_map_calibrator/include/accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp @@ -27,8 +27,8 @@ #include -#include "autoware_auto_vehicle_msgs/msg/steering_report.hpp" -#include "autoware_auto_vehicle_msgs/msg/velocity_report.hpp" +#include "autoware_vehicle_msgs/msg/steering_report.hpp" +#include "autoware_vehicle_msgs/msg/velocity_report.hpp" #include "geometry_msgs/msg/twist_stamped.hpp" #include "nav_msgs/msg/occupancy_grid.hpp" #include "std_msgs/msg/bool.hpp" @@ -56,8 +56,8 @@ namespace accel_brake_map_calibrator { -using autoware_auto_vehicle_msgs::msg::SteeringReport; -using autoware_auto_vehicle_msgs::msg::VelocityReport; +using autoware_vehicle_msgs::msg::SteeringReport; +using autoware_vehicle_msgs::msg::VelocityReport; using geometry_msgs::msg::TwistStamped; using nav_msgs::msg::OccupancyGrid; using raw_vehicle_cmd_converter::AccelMap; diff --git a/vehicle/accel_brake_map_calibrator/package.xml b/vehicle/accel_brake_map_calibrator/package.xml index 64e7d1fb105cf..4c4eadea5e1ce 100644 --- a/vehicle/accel_brake_map_calibrator/package.xml +++ b/vehicle/accel_brake_map_calibrator/package.xml @@ -13,7 +13,7 @@ ament_cmake_auto autoware_cmake - autoware_auto_vehicle_msgs + autoware_vehicle_msgs diagnostic_updater geometry_msgs motion_utils diff --git a/vehicle/accel_brake_map_calibrator/scripts/actuation_cmd_publisher.py b/vehicle/accel_brake_map_calibrator/scripts/actuation_cmd_publisher.py index 749c9e429bf06..3a029e193f41f 100755 --- a/vehicle/accel_brake_map_calibrator/scripts/actuation_cmd_publisher.py +++ b/vehicle/accel_brake_map_calibrator/scripts/actuation_cmd_publisher.py @@ -15,7 +15,7 @@ # See the License for the specific language governing permissions and # limitations under the License. -from autoware_auto_vehicle_msgs.msg import GearCommand +from autoware_vehicle_msgs.msg import GearCommand import rclpy from rclpy.node import Node from tier4_debug_msgs.msg import Float32Stamped diff --git a/vehicle/accel_brake_map_calibrator/test/sim_actuation_status_publisher.py b/vehicle/accel_brake_map_calibrator/test/sim_actuation_status_publisher.py index 9e57813bd4010..cd2205f8b269f 100755 --- a/vehicle/accel_brake_map_calibrator/test/sim_actuation_status_publisher.py +++ b/vehicle/accel_brake_map_calibrator/test/sim_actuation_status_publisher.py @@ -15,7 +15,7 @@ # limitations under the License. -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/vehicle/external_cmd_converter/README.md b/vehicle/external_cmd_converter/README.md index 3c4181a6f093b..ef5865debd4d4 100644 --- a/vehicle/external_cmd_converter/README.md +++ b/vehicle/external_cmd_converter/README.md @@ -7,16 +7,16 @@ | Name | Type | Description | | --------------------------- | -------------------------------------------- | ----------------------------------------------------------------------------------------------------------------- | | `~/in/external_control_cmd` | tier4_external_api_msgs::msg::ControlCommand | target `throttle/brake/steering_angle/steering_angle_velocity` is necessary to calculate desired control command. | -| `~/input/shift_cmd"` | autoware_auto_vehicle_msgs::GearCommand | current command of gear. | +| `~/input/shift_cmd"` | autoware_vehicle_msgs::GearCommand | current command of gear. | | `~/input/emergency_stop` | tier4_external_api_msgs::msg::Heartbeat | emergency heart beat for external command. | | `~/input/current_gate_mode` | tier4_control_msgs::msg::GateMode | topic for gate mode. | | `~/input/odometry` | navigation_msgs::Odometry | twist topic in odometry is used. | ## Output topics -| Name | Type | Description | -| ------------------- | -------------------------------------------------------- | ------------------------------------------------------------------ | -| `~/out/control_cmd` | autoware_auto_control_msgs::msg::AckermannControlCommand | ackermann control command converted from selected external command | +| Name | Type | Description | +| ------------------- | ----------------------------------- | ------------------------------------------------------------------ | +| `~/out/control_cmd` | autoware_control_msgs::msg::Control | ackermann control command converted from selected external command | ## Parameters diff --git a/vehicle/external_cmd_converter/include/external_cmd_converter/node.hpp b/vehicle/external_cmd_converter/include/external_cmd_converter/node.hpp index f5a52ad4a6032..2488c8ea7f300 100644 --- a/vehicle/external_cmd_converter/include/external_cmd_converter/node.hpp +++ b/vehicle/external_cmd_converter/include/external_cmd_converter/node.hpp @@ -20,8 +20,8 @@ #include #include -#include -#include +#include +#include #include #include #include @@ -32,13 +32,12 @@ namespace external_cmd_converter { -using GearCommand = autoware_auto_vehicle_msgs::msg::GearCommand; -using AckermannControlCommand = autoware_auto_control_msgs::msg::AckermannControlCommand; +using GearCommand = autoware_vehicle_msgs::msg::GearCommand; +using Control = autoware_control_msgs::msg::Control; using ExternalControlCommand = tier4_external_api_msgs::msg::ControlCommandStamped; using Odometry = nav_msgs::msg::Odometry; using raw_vehicle_cmd_converter::AccelMap; using raw_vehicle_cmd_converter::BrakeMap; -using ControlCommandStamped = autoware_auto_control_msgs::msg::AckermannControlCommand; using Odometry = nav_msgs::msg::Odometry; class ExternalCmdConverterNode : public rclcpp::Node @@ -48,7 +47,7 @@ class ExternalCmdConverterNode : public rclcpp::Node private: // Publisher - rclcpp::Publisher::SharedPtr pub_cmd_; + rclcpp::Publisher::SharedPtr pub_cmd_; rclcpp::Publisher::SharedPtr pub_current_cmd_; diff --git a/vehicle/external_cmd_converter/package.xml b/vehicle/external_cmd_converter/package.xml index d9301e23e05fe..513d73d2d39ff 100644 --- a/vehicle/external_cmd_converter/package.xml +++ b/vehicle/external_cmd_converter/package.xml @@ -12,8 +12,8 @@ ament_cmake_auto autoware_cmake - autoware_auto_control_msgs - autoware_auto_vehicle_msgs + autoware_control_msgs + autoware_vehicle_msgs diagnostic_updater geometry_msgs nav_msgs diff --git a/vehicle/external_cmd_converter/src/node.cpp b/vehicle/external_cmd_converter/src/node.cpp index 32592c02c3347..21945bb9078b8 100644 --- a/vehicle/external_cmd_converter/src/node.cpp +++ b/vehicle/external_cmd_converter/src/node.cpp @@ -26,7 +26,7 @@ ExternalCmdConverterNode::ExternalCmdConverterNode(const rclcpp::NodeOptions & n { using std::placeholders::_1; - pub_cmd_ = create_publisher("out/control_cmd", rclcpp::QoS{1}); + pub_cmd_ = create_publisher("out/control_cmd", rclcpp::QoS{1}); pub_current_cmd_ = create_publisher("out/latest_external_control_cmd", rclcpp::QoS{1}); sub_velocity_ = create_subscription( @@ -142,11 +142,11 @@ void ExternalCmdConverterNode::onExternalCmd(const ExternalControlCommand::Const } // Publish ControlCommand - autoware_auto_control_msgs::msg::AckermannControlCommand output; + autoware_control_msgs::msg::Control output; output.stamp = cmd_ptr->stamp; output.lateral.steering_tire_angle = cmd_ptr->control.steering_angle; output.lateral.steering_tire_rotation_rate = cmd_ptr->control.steering_angle_velocity; - output.longitudinal.speed = ref_velocity; + output.longitudinal.velocity = ref_velocity; output.longitudinal.acceleration = ref_acceleration; pub_cmd_->publish(output); diff --git a/vehicle/raw_vehicle_cmd_converter/README.md b/vehicle/raw_vehicle_cmd_converter/README.md index 5767c4fbf672b..6ac1ee4666cae 100644 --- a/vehicle/raw_vehicle_cmd_converter/README.md +++ b/vehicle/raw_vehicle_cmd_converter/README.md @@ -26,11 +26,11 @@ For ease of calibration and adjustments to the lookup table, an auto-calibration ## Input topics -| Name | Type | Description | -| --------------------- | -------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------ | -| `~/input/control_cmd` | autoware_auto_control_msgs::msg::AckermannControlCommand | target `velocity/acceleration/steering_angle/steering_angle_velocity` is necessary to calculate actuation command. | -| `~/input/steering"` | autoware_auto_vehicle_msgs::SteeringReport | current status of steering used for steering feed back control | -| `~/input/twist` | navigation_msgs::Odometry | twist topic in odometry is used. | +| Name | Type | Description | +| --------------------- | ------------------------------------- | ------------------------------------------------------------------------------------------------------------------ | +| `~/input/control_cmd` | autoware_control_msgs::msg::Control | target `velocity/acceleration/steering_angle/steering_angle_velocity` is necessary to calculate actuation command. | +| `~/input/steering"` | autoware_vehicle_msgs::SteeringReport | current status of steering used for steering feed back control | +| `~/input/twist` | navigation_msgs::Odometry | twist topic in odometry is used. | ## Output topics diff --git a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/node.hpp b/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/node.hpp index 98693337b5c28..d71ff96abade0 100644 --- a/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/node.hpp +++ b/vehicle/raw_vehicle_cmd_converter/include/raw_vehicle_cmd_converter/node.hpp @@ -23,8 +23,8 @@ #include -#include -#include +#include +#include #include #include #include @@ -36,12 +36,12 @@ namespace raw_vehicle_cmd_converter { -using AckermannControlCommand = autoware_auto_control_msgs::msg::AckermannControlCommand; +using Control = autoware_control_msgs::msg::Control; using tier4_debug_msgs::msg::Float32MultiArrayStamped; using tier4_vehicle_msgs::msg::ActuationCommandStamped; using TwistStamped = geometry_msgs::msg::TwistStamped; using Odometry = nav_msgs::msg::Odometry; -using Steering = autoware_auto_vehicle_msgs::msg::SteeringReport; +using Steering = autoware_vehicle_msgs::msg::SteeringReport; class DebugValues { @@ -77,7 +77,7 @@ class RawVehicleCommandConverterNode : public rclcpp::Node //!< @brief subscriber for current velocity rclcpp::Subscription::SharedPtr sub_velocity_; //!< @brief subscriber for vehicle command - rclcpp::Subscription::SharedPtr sub_control_cmd_; + rclcpp::Subscription::SharedPtr sub_control_cmd_; //!< @brief subscriber for steering rclcpp::Subscription::SharedPtr sub_steering_; @@ -85,7 +85,7 @@ class RawVehicleCommandConverterNode : public rclcpp::Node std::unique_ptr current_twist_ptr_; // [m/s] std::unique_ptr current_steer_ptr_; - AckermannControlCommand::ConstSharedPtr control_cmd_ptr_; + Control::ConstSharedPtr control_cmd_ptr_; AccelMap accel_map_; BrakeMap brake_map_; SteerMap steer_map_; @@ -110,7 +110,7 @@ class RawVehicleCommandConverterNode : public rclcpp::Node double calculateBrakeMap(const double current_velocity, const double desired_acc); double calculateSteer(const double vel, const double steering, const double steer_rate); void onSteering(const Steering::ConstSharedPtr msg); - void onControlCmd(const AckermannControlCommand::ConstSharedPtr msg); + void onControlCmd(const Control::ConstSharedPtr msg); void onVelocity(const Odometry::ConstSharedPtr msg); void publishActuationCmd(); // for debugging diff --git a/vehicle/raw_vehicle_cmd_converter/package.xml b/vehicle/raw_vehicle_cmd_converter/package.xml index d68f4601aab67..376a5c74f1cb6 100644 --- a/vehicle/raw_vehicle_cmd_converter/package.xml +++ b/vehicle/raw_vehicle_cmd_converter/package.xml @@ -17,8 +17,8 @@ ament_cmake_auto autoware_cmake - autoware_auto_control_msgs - autoware_auto_vehicle_msgs + autoware_control_msgs + autoware_vehicle_msgs geometry_msgs interpolation nav_msgs diff --git a/vehicle/raw_vehicle_cmd_converter/src/node.cpp b/vehicle/raw_vehicle_cmd_converter/src/node.cpp index 2506fb1f70b76..91c668f63dfbd 100644 --- a/vehicle/raw_vehicle_cmd_converter/src/node.cpp +++ b/vehicle/raw_vehicle_cmd_converter/src/node.cpp @@ -76,7 +76,7 @@ RawVehicleCommandConverterNode::RawVehicleCommandConverterNode( steer_pid_.setInitialized(); } pub_actuation_cmd_ = create_publisher("~/output/actuation_cmd", 1); - sub_control_cmd_ = create_subscription( + sub_control_cmd_ = create_subscription( "~/input/control_cmd", 1, std::bind(&RawVehicleCommandConverterNode::onControlCmd, this, _1)); sub_velocity_ = create_subscription( "~/input/odometry", 1, std::bind(&RawVehicleCommandConverterNode::onVelocity, this, _1)); @@ -216,7 +216,7 @@ void RawVehicleCommandConverterNode::onVelocity(const Odometry::ConstSharedPtr m current_twist_ptr_->twist = msg->twist.twist; } -void RawVehicleCommandConverterNode::onControlCmd(const AckermannControlCommand::ConstSharedPtr msg) +void RawVehicleCommandConverterNode::onControlCmd(const Control::ConstSharedPtr msg) { control_cmd_ptr_ = msg; publishActuationCmd(); diff --git a/vehicle/steer_offset_estimator/Readme.md b/vehicle/steer_offset_estimator/Readme.md index 3b455a97e4925..164d411e31050 100644 --- a/vehicle/steer_offset_estimator/Readme.md +++ b/vehicle/steer_offset_estimator/Readme.md @@ -17,10 +17,10 @@ Calculate yaw rate error and then calculate steering error recursively by least ### Input -| Name | Type | Description | -| --------------- | ------------------------------------------------- | ------------- | -| `~/input/twist` | `geometry_msgs::msg::TwistStamped` | vehicle twist | -| `~/input/steer` | `autoware_auto_vehicle_msgs::msg::SteeringReport` | steering | +| Name | Type | Description | +| --------------- | -------------------------------------------- | ------------- | +| `~/input/twist` | `geometry_msgs::msg::TwistStamped` | vehicle twist | +| `~/input/steer` | `autoware_vehicle_msgs::msg::SteeringReport` | steering | ### Output diff --git a/vehicle/steer_offset_estimator/include/steer_offset_estimator/steer_offset_estimator_node.hpp b/vehicle/steer_offset_estimator/include/steer_offset_estimator/steer_offset_estimator_node.hpp index 64d6694d7ce3e..afd1d0520e951 100644 --- a/vehicle/steer_offset_estimator/include/steer_offset_estimator/steer_offset_estimator_node.hpp +++ b/vehicle/steer_offset_estimator/include/steer_offset_estimator/steer_offset_estimator_node.hpp @@ -18,7 +18,7 @@ #include "diagnostic_updater/diagnostic_updater.hpp" #include "rclcpp/rclcpp.hpp" -#include "autoware_auto_vehicle_msgs/msg/steering_report.hpp" +#include "autoware_vehicle_msgs/msg/steering_report.hpp" #include "geometry_msgs/msg/twist_stamped.hpp" #include "tier4_debug_msgs/msg/float32_stamped.hpp" @@ -28,7 +28,7 @@ namespace steer_offset_estimator { using geometry_msgs::msg::TwistStamped; using tier4_debug_msgs::msg::Float32Stamped; -using Steering = autoware_auto_vehicle_msgs::msg::SteeringReport; +using Steering = autoware_vehicle_msgs::msg::SteeringReport; using diagnostic_updater::DiagnosticStatusWrapper; using diagnostic_updater::Updater; diff --git a/vehicle/steer_offset_estimator/package.xml b/vehicle/steer_offset_estimator/package.xml index 242ec5f2f148a..636d901d71ef5 100644 --- a/vehicle/steer_offset_estimator/package.xml +++ b/vehicle/steer_offset_estimator/package.xml @@ -9,7 +9,7 @@ ament_cmake_auto autoware_cmake - autoware_auto_vehicle_msgs + autoware_vehicle_msgs diagnostic_updater geometry_msgs rclcpp