diff --git a/control/vehicle_cmd_analyzer/include/vehicle_cmd_analyzer/vehicle_cmd_analyzer.hpp b/control/vehicle_cmd_analyzer/include/vehicle_cmd_analyzer/vehicle_cmd_analyzer.hpp index f3f77e62..7e68da3e 100644 --- a/control/vehicle_cmd_analyzer/include/vehicle_cmd_analyzer/vehicle_cmd_analyzer.hpp +++ b/control/vehicle_cmd_analyzer/include/vehicle_cmd_analyzer/vehicle_cmd_analyzer.hpp @@ -20,7 +20,7 @@ #include -#include "autoware_auto_control_msgs/msg/ackermann_control_command.hpp" +#include "autoware_control_msgs/msg/control.hpp" #include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp" #include @@ -32,13 +32,11 @@ class VehicleCmdAnalyzer : public rclcpp::Node { private: - rclcpp::Subscription::SharedPtr - sub_vehicle_cmd_; + rclcpp::Subscription::SharedPtr sub_vehicle_cmd_; rclcpp::Publisher::SharedPtr pub_debug_; rclcpp::TimerBase::SharedPtr timer_control_; - std::shared_ptr vehicle_cmd_ptr_{ - nullptr}; + std::shared_ptr vehicle_cmd_ptr_{nullptr}; // timer callback double control_rate_; @@ -54,8 +52,7 @@ class VehicleCmdAnalyzer : public rclcpp::Node // debug values DebugValues debug_values_; - void callbackVehicleCommand( - const autoware_auto_control_msgs::msg::AckermannControlCommand::SharedPtr msg); + void callbackVehicleCommand(const autoware_control_msgs::msg::Control::SharedPtr msg); void callbackTimerControl(); diff --git a/control/vehicle_cmd_analyzer/package.xml b/control/vehicle_cmd_analyzer/package.xml index 345cf595..9e190656 100644 --- a/control/vehicle_cmd_analyzer/package.xml +++ b/control/vehicle_cmd_analyzer/package.xml @@ -11,7 +11,7 @@ autoware_cmake - autoware_auto_control_msgs + autoware_control_msgs rclcpp rclcpp_components tier4_debug_msgs diff --git a/control/vehicle_cmd_analyzer/src/vehicle_cmd_analyzer.cpp b/control/vehicle_cmd_analyzer/src/vehicle_cmd_analyzer.cpp index bf5063dc..ceab6298 100644 --- a/control/vehicle_cmd_analyzer/src/vehicle_cmd_analyzer.cpp +++ b/control/vehicle_cmd_analyzer/src/vehicle_cmd_analyzer.cpp @@ -30,10 +30,9 @@ VehicleCmdAnalyzer::VehicleCmdAnalyzer(const rclcpp::NodeOptions & options) const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); wheelbase_ = vehicle_info.wheel_base_m; - sub_vehicle_cmd_ = - this->create_subscription( - "/control/command/control_cmd", rclcpp::QoS(10), - std::bind(&VehicleCmdAnalyzer::callbackVehicleCommand, this, std::placeholders::_1)); + sub_vehicle_cmd_ = this->create_subscription( + "/control/command/control_cmd", rclcpp::QoS(10), + std::bind(&VehicleCmdAnalyzer::callbackVehicleCommand, this, std::placeholders::_1)); pub_debug_ = create_publisher( "~/debug_values", rclcpp::QoS{1}); @@ -50,10 +49,9 @@ VehicleCmdAnalyzer::VehicleCmdAnalyzer(const rclcpp::NodeOptions & options) } void VehicleCmdAnalyzer::callbackVehicleCommand( - const autoware_auto_control_msgs::msg::AckermannControlCommand::SharedPtr msg) + const autoware_control_msgs::msg::Control::SharedPtr msg) { - vehicle_cmd_ptr_ = - std::make_shared(*msg); + vehicle_cmd_ptr_ = std::make_shared(*msg); } void VehicleCmdAnalyzer::callbackTimerControl() @@ -76,7 +74,7 @@ void VehicleCmdAnalyzer::publishDebugData() // set debug values debug_values_.setValues(DebugValues::TYPE::DT, dt); debug_values_.setValues( - DebugValues::TYPE::CURRENT_TARGET_VEL, vehicle_cmd_ptr_->longitudinal.speed); + DebugValues::TYPE::CURRENT_TARGET_VEL, vehicle_cmd_ptr_->longitudinal.velocity); debug_values_.setValues(DebugValues::TYPE::CURRENT_TARGET_D_VEL, d_vel); debug_values_.setValues(DebugValues::TYPE::CURRENT_TARGET_DD_VEL, dd_vel); debug_values_.setValues( @@ -111,13 +109,13 @@ double VehicleCmdAnalyzer::getDt() std::pair VehicleCmdAnalyzer::differentiateVelocity(const double dt) { if (!prev_target_vel_) { - prev_target_vel_ = vehicle_cmd_ptr_->longitudinal.speed; + prev_target_vel_ = vehicle_cmd_ptr_->longitudinal.velocity; prev_target_d_vel_.at(2) = 0.0; return {0.0, 0.0}; } - const double d_vel = (vehicle_cmd_ptr_->longitudinal.speed - prev_target_vel_) / dt; + const double d_vel = (vehicle_cmd_ptr_->longitudinal.velocity - prev_target_vel_) / dt; const double dd_vel = (d_vel - prev_target_d_vel_.at(0)) / 2 / dt; - prev_target_vel_ = vehicle_cmd_ptr_->longitudinal.speed; + prev_target_vel_ = vehicle_cmd_ptr_->longitudinal.velocity; for (int i = 0; i < 2; i++) { prev_target_d_vel_.at(i) = prev_target_d_vel_.at(i + 1); } @@ -139,7 +137,7 @@ double VehicleCmdAnalyzer::differentiateAcceleration(const double dt) double VehicleCmdAnalyzer::calcLateralAcceleration() const { const double delta = vehicle_cmd_ptr_->lateral.steering_tire_angle; - const double vel = vehicle_cmd_ptr_->longitudinal.speed; + const double vel = vehicle_cmd_ptr_->longitudinal.velocity; const double a_lat = vel * vel * std::sin(delta) / wheelbase_; return a_lat; } diff --git a/localization/deviation_estimation_tools/ReadMe.md b/localization/deviation_estimation_tools/ReadMe.md index 8bc5819d..df26f2e2 100644 --- a/localization/deviation_estimation_tools/ReadMe.md +++ b/localization/deviation_estimation_tools/ReadMe.md @@ -60,7 +60,7 @@ Topic information: Topic: /localization/pose_estimator/pose_with_covariance | Ty Topic: /clock | Type: rosgraph_msgs/msg/Clock | Count: 57309 | Serialization Format: cdr Topic: /tf_static | Type: tf2_msgs/msg/TFMessage | Count: 2 | Serialization Format: cdr Topic: /sensing/imu/tamagawa/imu_raw | Type: sensor_msgs/msg/Imu | Count: 8076 | Serialization Format: cdr - Topic: /vehicle/status/velocity_status | Type: autoware_auto_vehicle_msgs/msg/VelocityReport | Count: 8275 | Serialization Format: cdr + Topic: /vehicle/status/velocity_status | Type: autoware_vehicle_msgs/msg/VelocityReport | Count: 8275 | Serialization Format: cdr ``` @@ -183,11 +183,11 @@ The parameters and input topic names can be seen in the `deviation_estimator.lau #### Input -| Name | Type | Description | -| ------------------------ | ------------------------------------------------- | -------------------- | -| `in_pose_with_covariance | `geometry_msgs::msg::PoseWithCovarianceStamped` | Input pose | -| `in_imu` | `sensor_msgs::msg::Imu` | Input IMU data | -| `in_wheel_odometry` | `autoware_auto_vehicle_msgs::msg::VelocityReport` | Input wheel odometry | +| Name | Type | Description | +| ------------------------ | ----------------------------------------------- | -------------------- | +| `in_pose_with_covariance | `geometry_msgs::msg::PoseWithCovarianceStamped` | Input pose | +| `in_imu` | `sensor_msgs::msg::Imu` | Input IMU data | +| `in_wheel_odometry` | `autoware_vehicle_msgs::msg::VelocityReport` | Input wheel odometry | #### Output diff --git a/localization/deviation_estimation_tools/deviation_estimator/include/deviation_estimator/deviation_estimator.hpp b/localization/deviation_estimation_tools/deviation_estimator/include/deviation_estimator/deviation_estimator.hpp index 94f30509..bf773638 100644 --- a/localization/deviation_estimation_tools/deviation_estimator/include/deviation_estimator/deviation_estimator.hpp +++ b/localization/deviation_estimation_tools/deviation_estimator/include/deviation_estimator/deviation_estimator.hpp @@ -24,7 +24,7 @@ #include "tf2/utils.h" #include "tier4_autoware_utils/ros/transform_listener.hpp" -#include "autoware_auto_vehicle_msgs/msg/velocity_report.hpp" +#include "autoware_vehicle_msgs/msg/velocity_report.hpp" #include "geometry_msgs/msg/pose_with_covariance_stamped.hpp" #include "geometry_msgs/msg/transform_stamped.hpp" #include "geometry_msgs/msg/twist_with_covariance_stamped.hpp" @@ -58,8 +58,7 @@ class DeviationEstimator : public rclcpp::Node private: rclcpp::Subscription::SharedPtr sub_pose_with_cov_; - rclcpp::Subscription::SharedPtr - sub_wheel_odometry_; + rclcpp::Subscription::SharedPtr sub_wheel_odometry_; rclcpp::Subscription::SharedPtr sub_imu_; rclcpp::Publisher::SharedPtr pub_coef_vx_; rclcpp::Publisher::SharedPtr pub_bias_angvel_; @@ -109,7 +108,7 @@ class DeviationEstimator : public rclcpp::Node void callback_pose_with_covariance(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg); void callback_wheel_odometry( - const autoware_auto_vehicle_msgs::msg::VelocityReport::ConstSharedPtr wheel_odometry_msg_ptr); + const autoware_vehicle_msgs::msg::VelocityReport::ConstSharedPtr wheel_odometry_msg_ptr); void callback_imu(const sensor_msgs::msg::Imu::ConstSharedPtr imu_msg_ptr); diff --git a/localization/deviation_estimation_tools/deviation_estimator/package.xml b/localization/deviation_estimation_tools/deviation_estimator/package.xml index d15a6a00..21cc5504 100644 --- a/localization/deviation_estimation_tools/deviation_estimator/package.xml +++ b/localization/deviation_estimation_tools/deviation_estimator/package.xml @@ -10,7 +10,7 @@ ament_cmake_auto autoware_cmake - autoware_auto_vehicle_msgs + autoware_vehicle_msgs geometry_msgs nav_msgs rclcpp diff --git a/localization/deviation_estimation_tools/deviation_estimator/src/deviation_estimator.cpp b/localization/deviation_estimation_tools/deviation_estimator/src/deviation_estimator.cpp index ebf0974a..cc3f255c 100644 --- a/localization/deviation_estimation_tools/deviation_estimator/src/deviation_estimator.cpp +++ b/localization/deviation_estimation_tools/deviation_estimator/src/deviation_estimator.cpp @@ -167,7 +167,7 @@ DeviationEstimator::DeviationEstimator( sub_imu_ = create_subscription( "in_imu", 1, std::bind(&DeviationEstimator::callback_imu, this, _1)); - sub_wheel_odometry_ = create_subscription( + sub_wheel_odometry_ = create_subscription( "in_wheel_odometry", 1, std::bind(&DeviationEstimator::callback_wheel_odometry, this, _1)); results_logger_.log_estimated_result_section( 0.2, 0.0, geometry_msgs::msg::Vector3{}, geometry_msgs::msg::Vector3{}); @@ -200,7 +200,7 @@ void DeviationEstimator::callback_pose_with_covariance( * @brief receive velocity data and store it in a buffer */ void DeviationEstimator::callback_wheel_odometry( - const autoware_auto_vehicle_msgs::msg::VelocityReport::ConstSharedPtr wheel_odometry_msg_ptr) + const autoware_vehicle_msgs::msg::VelocityReport::ConstSharedPtr wheel_odometry_msg_ptr) { tier4_debug_msgs::msg::Float64Stamped vx; vx.stamp = wheel_odometry_msg_ptr->header.stamp; diff --git a/localization/deviation_estimation_tools/deviation_estimator/src/deviation_estimator_main.cpp b/localization/deviation_estimation_tools/deviation_estimator/src/deviation_estimator_main.cpp index 578c0def..6346e8e0 100644 --- a/localization/deviation_estimation_tools/deviation_estimator/src/deviation_estimator_main.cpp +++ b/localization/deviation_estimation_tools/deviation_estimator/src/deviation_estimator_main.cpp @@ -58,8 +58,7 @@ int main(int argc, char ** argv) reader.open(storage_options, converter_options); // Prepare serialization - rclcpp::Serialization - serialization_velocity_status; + rclcpp::Serialization serialization_velocity_status; rclcpp::Serialization serialization_tf; rclcpp::Serialization serialization_imu; rclcpp::Serialization serialization_pose; @@ -83,8 +82,8 @@ int main(int argc, char ** argv) const rclcpp::SerializedMessage msg(*serialized_message->serialized_data); if (topic_name == "/vehicle/status/velocity_status") { - autoware_auto_vehicle_msgs::msg::VelocityReport::SharedPtr velocity_status_msg = - std::make_shared(); + autoware_vehicle_msgs::msg::VelocityReport::SharedPtr velocity_status_msg = + std::make_shared(); serialization_velocity_status.deserialize_message(&msg, velocity_status_msg.get()); const rclcpp::Time curr_stamp = velocity_status_msg->header.stamp; first_stamp = std::min(first_stamp, curr_stamp); diff --git a/planning/planning_debug_tools/scripts/closest_velocity_checker.py b/planning/planning_debug_tools/scripts/closest_velocity_checker.py index a8a553a3..cf00a2ad 100755 --- a/planning/planning_debug_tools/scripts/closest_velocity_checker.py +++ b/planning/planning_debug_tools/scripts/closest_velocity_checker.py @@ -104,13 +104,13 @@ def __init__(self): # control commands self.sub6 = self.create_subscription( - AckermannControlCommand, + Control, "/control/trajectory_follower/control_cmd", self.CallBackControlCmd, 1, ) self.sub7 = self.create_subscription( - AckermannControlCommand, "/control/command/control_cmd", self.CallBackVehicleCmd, 1 + Control, "/control/command/control_cmd", self.CallBackVehicleCmd, 1 ) # others related to velocity diff --git a/vehicle/calibration_adapter/include/calibration_adapter/calibration_adapter_node.hpp b/vehicle/calibration_adapter/include/calibration_adapter/calibration_adapter_node.hpp index 62c50bca..32befa12 100644 --- a/vehicle/calibration_adapter/include/calibration_adapter/calibration_adapter_node.hpp +++ b/vehicle/calibration_adapter/include/calibration_adapter/calibration_adapter_node.hpp @@ -21,8 +21,8 @@ #include "estimator_utils/math_utils.hpp" #include "rclcpp/rclcpp.hpp" -#include "autoware_auto_control_msgs/msg/ackermann_control_command.hpp" -#include "autoware_auto_vehicle_msgs/msg/velocity_report.hpp" +#include "autoware_control_msgs/msg/control.hpp" +#include "autoware_vehicle_msgs/msg/velocity_report.hpp" #include "geometry_msgs/msg/twist_stamped.hpp" #include "tier4_calibration_msgs/msg/float32_stamped.hpp" @@ -30,8 +30,8 @@ class CalibrationAdapterNode : public CalibrationAdapterNodeBase { - using Velocity = autoware_auto_vehicle_msgs::msg::VelocityReport; - using ControlCommandStamped = autoware_auto_control_msgs::msg::AckermannControlCommand; + using Velocity = autoware_vehicle_msgs::msg::VelocityReport; + using ControlCommandStamped = autoware_control_msgs::msg::Control; using TwistStamped = geometry_msgs::msg::TwistStamped; public: diff --git a/vehicle/calibration_adapter/include/calibration_adapter/calibration_adapter_node_base.hpp b/vehicle/calibration_adapter/include/calibration_adapter/calibration_adapter_node_base.hpp index 39a25534..53d34c1a 100644 --- a/vehicle/calibration_adapter/include/calibration_adapter/calibration_adapter_node_base.hpp +++ b/vehicle/calibration_adapter/include/calibration_adapter/calibration_adapter_node_base.hpp @@ -19,8 +19,8 @@ #include "rclcpp/rclcpp.hpp" -#include "autoware_auto_vehicle_msgs/msg/engage.hpp" -#include "autoware_auto_vehicle_msgs/msg/steering_report.hpp" +#include "autoware_vehicle_msgs/msg/engage.hpp" +#include "autoware_vehicle_msgs/msg/steering_report.hpp" #include "tier4_calibration_msgs/msg/bool_stamped.hpp" #include "tier4_calibration_msgs/msg/float32_stamped.hpp" #include "tier4_vehicle_msgs/msg/actuation_command_stamped.hpp" @@ -33,8 +33,8 @@ class CalibrationAdapterNodeBase : public rclcpp::Node using ActuationStatusStamped = tier4_vehicle_msgs::msg::ActuationStatusStamped; using Float32Stamped = tier4_calibration_msgs::msg::Float32Stamped; using BoolStamped = tier4_calibration_msgs::msg::BoolStamped; - using EngageStatus = autoware_auto_vehicle_msgs::msg::Engage; - using SteeringAngleStatus = autoware_auto_vehicle_msgs::msg::SteeringReport; + using EngageStatus = autoware_vehicle_msgs::msg::Engage; + using SteeringAngleStatus = autoware_vehicle_msgs::msg::SteeringReport; CalibrationAdapterNodeBase(); private: diff --git a/vehicle/calibration_adapter/package.xml b/vehicle/calibration_adapter/package.xml index 5382a278..3f1b91db 100644 --- a/vehicle/calibration_adapter/package.xml +++ b/vehicle/calibration_adapter/package.xml @@ -11,8 +11,8 @@ autoware_cmake - autoware_auto_control_msgs - autoware_auto_vehicle_msgs + autoware_control_msgs + autoware_vehicle_msgs estimator_utils rclcpp tf2 diff --git a/vehicle/calibration_adapter/src/calibration_adapter_node_base.cpp b/vehicle/calibration_adapter/src/calibration_adapter_node_base.cpp index 7a3fe0c4..15673d36 100644 --- a/vehicle/calibration_adapter/src/calibration_adapter_node_base.cpp +++ b/vehicle/calibration_adapter/src/calibration_adapter_node_base.cpp @@ -52,7 +52,7 @@ CalibrationAdapterNodeBase::CalibrationAdapterNodeBase() : Node("calibration_ada pub_is_engage_ = create_publisher("~/output/is_engage", durable_qos); - sub_engage_status_ = create_subscription( + sub_engage_status_ = create_subscription( "~/input/is_engage", queue_size, std::bind(&CalibrationAdapterNodeBase::onEngageStatus, this, _1)); sub_actuation_status_ = create_subscription( diff --git a/vehicle/parameter_estimator/include/parameter_estimator/parameter_estimator_node.hpp b/vehicle/parameter_estimator/include/parameter_estimator/parameter_estimator_node.hpp index 62bae678..e4eae654 100644 --- a/vehicle/parameter_estimator/include/parameter_estimator/parameter_estimator_node.hpp +++ b/vehicle/parameter_estimator/include/parameter_estimator/parameter_estimator_node.hpp @@ -25,7 +25,7 @@ #include "rclcpp/rclcpp.hpp" #include "vehicle_info_util/vehicle_info_util.hpp" -#include "autoware_auto_vehicle_msgs/msg/control_mode_report.hpp" +#include "autoware_vehicle_msgs/msg/control_mode_report.hpp" #include "geometry_msgs/msg/twist_stamped.hpp" #include "sensor_msgs/msg/imu.hpp" #include "tier4_calibration_msgs/msg/float32_stamped.hpp" @@ -38,7 +38,7 @@ class ParameterEstimatorNode : public rclcpp::Node rclcpp::Subscription::SharedPtr sub_vehicle_twist_; rclcpp::Subscription::SharedPtr sub_steer_; rclcpp::Subscription::SharedPtr sub_steer_wheel_; - rclcpp::Subscription::SharedPtr + rclcpp::Subscription::SharedPtr sub_control_mode_report_; rclcpp::Subscription::SharedPtr sub_imu_; @@ -50,7 +50,7 @@ class ParameterEstimatorNode : public rclcpp::Node sensor_msgs::msg::Imu::ConstSharedPtr imu_ptr_; tier4_calibration_msgs::msg::Float32Stamped::ConstSharedPtr steer_ptr_; tier4_calibration_msgs::msg::Float32Stamped::ConstSharedPtr steer_wheel_ptr_; - autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr control_mode_ptr_; + autoware_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr control_mode_ptr_; /** * ros parameters @@ -77,7 +77,7 @@ class ParameterEstimatorNode : public rclcpp::Node void callbackSteer(const tier4_calibration_msgs::msg::Float32Stamped::ConstSharedPtr msg); void callbackSteerWheel(const tier4_calibration_msgs::msg::Float32Stamped::ConstSharedPtr msg); void callbackControlModeReport( - const autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg); + const autoware_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg); void timerCallback(); bool updateGearRatio(); diff --git a/vehicle/parameter_estimator/package.xml b/vehicle/parameter_estimator/package.xml index e656bafc..66a996bf 100644 --- a/vehicle/parameter_estimator/package.xml +++ b/vehicle/parameter_estimator/package.xml @@ -10,7 +10,7 @@ ament_cmake_auto - autoware_auto_vehicle_msgs + autoware_vehicle_msgs estimator_utils geometry_msgs rclcpp diff --git a/vehicle/parameter_estimator/src/parameter_estimator_node.cpp b/vehicle/parameter_estimator/src/parameter_estimator_node.cpp index 9bb19934..08303cbe 100644 --- a/vehicle/parameter_estimator/src/parameter_estimator_node.cpp +++ b/vehicle/parameter_estimator/src/parameter_estimator_node.cpp @@ -73,10 +73,9 @@ ParameterEstimatorNode::ParameterEstimatorNode(const rclcpp::NodeOptions & node_ sub_steer_ = create_subscription( "input/steer", queue_size, std::bind(&ParameterEstimatorNode::callbackSteer, this, _1)); } - sub_control_mode_report_ = - create_subscription( - "input/control_mode", queue_size, - std::bind(&ParameterEstimatorNode::callbackControlModeReport, this, _1)); + sub_control_mode_report_ = create_subscription( + "input/control_mode", queue_size, + std::bind(&ParameterEstimatorNode::callbackControlModeReport, this, _1)); initTimer(1.0 / update_hz_); } @@ -173,11 +172,11 @@ void ParameterEstimatorNode::callbackSteerWheel( } void ParameterEstimatorNode::callbackControlModeReport( - const autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg) + const autoware_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg) { auto & clk = *this->get_clock(); control_mode_ptr_ = msg; - if (control_mode_ptr_->mode == autoware_auto_vehicle_msgs::msg::ControlModeReport::AUTONOMOUS) { + if (control_mode_ptr_->mode == autoware_vehicle_msgs::msg::ControlModeReport::AUTONOMOUS) { auto_mode_duration_ = (this->now().seconds() - last_manual_time_); RCLCPP_DEBUG_STREAM_THROTTLE( rclcpp::get_logger("parameter_estimator"), clk, 5000, diff --git a/vehicle/time_delay_estimator/include/time_delay_estimator/general_time_delay_estimator_node.hpp b/vehicle/time_delay_estimator/include/time_delay_estimator/general_time_delay_estimator_node.hpp index b1fe8ca3..54f0bd6d 100644 --- a/vehicle/time_delay_estimator/include/time_delay_estimator/general_time_delay_estimator_node.hpp +++ b/vehicle/time_delay_estimator/include/time_delay_estimator/general_time_delay_estimator_node.hpp @@ -23,7 +23,7 @@ #include "time_delay_estimator/parameters.hpp" #include "time_delay_estimator/time_delay_estimator.hpp" -#include "autoware_auto_vehicle_msgs/msg/control_mode_report.hpp" +#include "autoware_vehicle_msgs/msg/control_mode_report.hpp" #include "std_msgs/msg/bool.hpp" #include "std_msgs/msg/float32.hpp" #include "std_msgs/msg/float32_multi_array.hpp" @@ -44,7 +44,7 @@ class TimeDelayEstimatorNode : public rclcpp::Node { using Float32Stamped = tier4_calibration_msgs::msg::Float32Stamped; - using ControlModeReport = autoware_auto_vehicle_msgs::msg::ControlModeReport; + using ControlModeReport = autoware_vehicle_msgs::msg::ControlModeReport; using IsEngaged = tier4_calibration_msgs::msg::BoolStamped; using BoolStamped = tier4_calibration_msgs::msg::BoolStamped; using TimeDelay = tier4_calibration_msgs::msg::TimeDelay; @@ -54,7 +54,7 @@ class TimeDelayEstimatorNode : public rclcpp::Node rclcpp::Publisher::SharedPtr pub_time_delay_; // input subscription - rclcpp::Subscription::SharedPtr + rclcpp::Subscription::SharedPtr sub_control_mode_report_; // response subscription diff --git a/vehicle/time_delay_estimator/include/time_delay_estimator/time_delay_estimator_node.hpp b/vehicle/time_delay_estimator/include/time_delay_estimator/time_delay_estimator_node.hpp index d31cf5e6..84742362 100644 --- a/vehicle/time_delay_estimator/include/time_delay_estimator/time_delay_estimator_node.hpp +++ b/vehicle/time_delay_estimator/include/time_delay_estimator/time_delay_estimator_node.hpp @@ -23,7 +23,7 @@ #include "time_delay_estimator/parameters.hpp" #include "time_delay_estimator/time_delay_estimator.hpp" -#include "autoware_auto_vehicle_msgs/msg/control_mode_report.hpp" +#include "autoware_vehicle_msgs/msg/control_mode_report.hpp" #include "std_msgs/msg/bool.hpp" #include "std_msgs/msg/float32.hpp" #include "std_msgs/msg/float32_multi_array.hpp" @@ -44,7 +44,7 @@ class TimeDelayEstimatorNode : public rclcpp::Node { using Float32Stamped = tier4_calibration_msgs::msg::Float32Stamped; - using ControlModeReport = autoware_auto_vehicle_msgs::msg::ControlModeReport; + using ControlModeReport = autoware_vehicle_msgs::msg::ControlModeReport; using IsEngaged = tier4_calibration_msgs::msg::BoolStamped; using BoolStamped = tier4_calibration_msgs::msg::BoolStamped; using TimeDelay = tier4_calibration_msgs::msg::TimeDelay; @@ -57,8 +57,7 @@ class TimeDelayEstimatorNode : public rclcpp::Node rclcpp::Publisher::SharedPtr pub_time_delay_steer_; // input subscription - rclcpp::Subscription::SharedPtr - sub_control_mode_; + rclcpp::Subscription::SharedPtr sub_control_mode_; // response subscription rclcpp::Subscription::SharedPtr sub_accel_cmd_; diff --git a/vehicle/time_delay_estimator/package.xml b/vehicle/time_delay_estimator/package.xml index fb6ecaea..83b4cc11 100644 --- a/vehicle/time_delay_estimator/package.xml +++ b/vehicle/time_delay_estimator/package.xml @@ -10,7 +10,7 @@ ament_cmake_auto - autoware_auto_vehicle_msgs + autoware_vehicle_msgs calibration_adapter eigen estimator_utils diff --git a/vehicle/time_delay_estimator/src/general_time_delay_estimator_node.cpp b/vehicle/time_delay_estimator/src/general_time_delay_estimator_node.cpp index c835c76f..242b8376 100644 --- a/vehicle/time_delay_estimator/src/general_time_delay_estimator_node.cpp +++ b/vehicle/time_delay_estimator/src/general_time_delay_estimator_node.cpp @@ -80,10 +80,9 @@ TimeDelayEstimatorNode::TimeDelayEstimatorNode(const rclcpp::NodeOptions & node_ last_manual_time_ = this->now().seconds(); // input - sub_control_mode_report_ = - create_subscription( - "~/input/control_mode", queue_size, - std::bind(&TimeDelayEstimatorNode::callbackControlModeReport, this, _1)); + sub_control_mode_report_ = create_subscription( + "~/input/control_mode", queue_size, + std::bind(&TimeDelayEstimatorNode::callbackControlModeReport, this, _1)); // response sub_input_cmd_ = create_subscription( @@ -189,7 +188,7 @@ void TimeDelayEstimatorNode::callbackControlModeReport(const ControlModeReport:: { auto & clk = *this->get_clock(); control_mode_ptr_ = msg; - if (control_mode_ptr_->mode == autoware_auto_vehicle_msgs::msg::ControlModeReport::AUTONOMOUS) { + if (control_mode_ptr_->mode == autoware_vehicle_msgs::msg::ControlModeReport::AUTONOMOUS) { auto_mode_duration_ = (this->now().seconds() - last_manual_time_); RCLCPP_DEBUG_STREAM_THROTTLE( rclcpp::get_logger("time_delay_estimator"), clk, 5000, diff --git a/vehicle/time_delay_estimator/src/time_delay_estimator_node.cpp b/vehicle/time_delay_estimator/src/time_delay_estimator_node.cpp index 8f982c5f..9fffa917 100644 --- a/vehicle/time_delay_estimator/src/time_delay_estimator_node.cpp +++ b/vehicle/time_delay_estimator/src/time_delay_estimator_node.cpp @@ -86,7 +86,7 @@ TimeDelayEstimatorNode::TimeDelayEstimatorNode(const rclcpp::NodeOptions & node_ last_manual_time_ = this->now().seconds(); // input - sub_control_mode_ = create_subscription( + sub_control_mode_ = create_subscription( "~/input/control_mode", queue_size, std::bind(&TimeDelayEstimatorNode::callbackControlModeReport, this, _1)); @@ -296,7 +296,7 @@ void TimeDelayEstimatorNode::callbackControlModeReport(const ControlModeReport:: { auto & clk = *this->get_clock(); control_mode_ptr_ = msg; - if (control_mode_ptr_->mode == autoware_auto_vehicle_msgs::msg::ControlModeReport::AUTONOMOUS) { + if (control_mode_ptr_->mode == autoware_vehicle_msgs::msg::ControlModeReport::AUTONOMOUS) { auto_mode_duration_ = (this->now().seconds() - last_manual_time_); RCLCPP_DEBUG_STREAM_THROTTLE( rclcpp::get_logger("time_delay_estimator"), clk, 5000,