From 48cf1d7b61d0bb826797ae7b28e55499e79b1cb2 Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome Date: Tue, 4 Jun 2024 00:21:26 +0900 Subject: [PATCH] feat!: replace autoware_auto_msgs with autoware_msgs for tools Signed-off-by: Ryohsuke Mitsudome Co-authored-by: Cynthia Liu Co-authored-by: NorahXiong Co-authored-by: beginningfan --- tools/reaction_analyzer/README.md | 22 +++++------ .../include/reaction_analyzer_node.hpp | 4 +- .../reaction_analyzer/include/subscriber.hpp | 33 +++++++--------- .../include/topic_publisher.hpp | 36 ++++++++--------- tools/reaction_analyzer/include/utils.hpp | 30 +++++++------- tools/reaction_analyzer/package.xml | 10 ++--- .../param/reaction_analyzer.param.yaml | 28 ++++++------- tools/reaction_analyzer/src/subscriber.cpp | 39 +++++++++---------- .../reaction_analyzer/src/topic_publisher.cpp | 12 +++--- tools/reaction_analyzer/src/utils.cpp | 32 +++++++-------- 10 files changed, 120 insertions(+), 126 deletions(-) diff --git a/tools/reaction_analyzer/README.md b/tools/reaction_analyzer/README.md index f5a22aaf20176..ba77cc4c8f5bb 100644 --- a/tools/reaction_analyzer/README.md +++ b/tools/reaction_analyzer/README.md @@ -201,21 +201,21 @@ for each of the nodes. - `sensor_msgs/msg/Image` - `geometry_msgs/msg/PoseWithCovarianceStamped` - `sensor_msgs/msg/Imu` - - `autoware_auto_vehicle_msgs/msg/ControlModeReport` - - `autoware_auto_vehicle_msgs/msg/GearReport` - - `autoware_auto_vehicle_msgs/msg/HazardLightsReport` - - `autoware_auto_vehicle_msgs/msg/SteeringReport` - - `autoware_auto_vehicle_msgs/msg/TurnIndicatorsReport` - - `autoware_auto_vehicle_msgs/msg/VelocityReport` + - `autoware_vehicle_msgs/msg/ControlModeReport` + - `autoware_vehicle_msgs/msg/GearReport` + - `autoware_vehicle_msgs/msg/HazardLightsReport` + - `autoware_vehicle_msgs/msg/SteeringReport` + - `autoware_vehicle_msgs/msg/TurnIndicatorsReport` + - `autoware_vehicle_msgs/msg/VelocityReport` - **Subscriber Message Types:** - `sensor_msgs/msg/PointCloud2` - - `autoware_auto_perception_msgs/msg/DetectedObjects` - - `autoware_auto_perception_msgs/msg/TrackedObjects` - - `autoware_auto_msgs/msg/PredictedObject` - - `autoware_auto_planning_msgs/msg/Trajectory` - - `autoware_auto_control_msgs/msg/AckermannControlCommand` + - `autoware_perception_msgs/msg/DetectedObjects` + - `autoware_perception_msgs/msg/TrackedObjects` + - `autoware_perception_msgs/msg/PredictedObject` + - `autoware_planning_msgs/msg/Trajectory` + - `autoware_control_msgs/msg/Control` - **Reaction Types:** - `FIRST_BRAKE` diff --git a/tools/reaction_analyzer/include/reaction_analyzer_node.hpp b/tools/reaction_analyzer/include/reaction_analyzer_node.hpp index 6dc3dd896dc92..c5a8f6a2e663a 100644 --- a/tools/reaction_analyzer/include/reaction_analyzer_node.hpp +++ b/tools/reaction_analyzer/include/reaction_analyzer_node.hpp @@ -42,9 +42,9 @@ using autoware_adapi_v1_msgs::msg::LocalizationInitializationState; using autoware_adapi_v1_msgs::msg::OperationModeState; using autoware_adapi_v1_msgs::msg::RouteState; using autoware_adapi_v1_msgs::srv::ChangeOperationMode; -using autoware_auto_perception_msgs::msg::PredictedObject; -using autoware_auto_perception_msgs::msg::PredictedObjects; using autoware_internal_msgs::msg::PublishedTime; +using autoware_perception_msgs::msg::PredictedObject; +using autoware_perception_msgs::msg::PredictedObjects; using geometry_msgs::msg::Pose; using geometry_msgs::msg::PoseStamped; using nav_msgs::msg::Odometry; diff --git a/tools/reaction_analyzer/include/subscriber.hpp b/tools/reaction_analyzer/include/subscriber.hpp index d14d41da545f7..21d370a68b556 100644 --- a/tools/reaction_analyzer/include/subscriber.hpp +++ b/tools/reaction_analyzer/include/subscriber.hpp @@ -39,23 +39,23 @@ namespace reaction_analyzer::subscriber { -using autoware_auto_control_msgs::msg::AckermannControlCommand; -using autoware_auto_perception_msgs::msg::DetectedObject; -using autoware_auto_perception_msgs::msg::DetectedObjects; -using autoware_auto_perception_msgs::msg::PredictedObject; -using autoware_auto_perception_msgs::msg::PredictedObjects; -using autoware_auto_perception_msgs::msg::TrackedObject; -using autoware_auto_perception_msgs::msg::TrackedObjects; -using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_control_msgs::msg::Control; using autoware_internal_msgs::msg::PublishedTime; +using autoware_perception_msgs::msg::DetectedObject; +using autoware_perception_msgs::msg::DetectedObjects; +using autoware_perception_msgs::msg::PredictedObject; +using autoware_perception_msgs::msg::PredictedObjects; +using autoware_perception_msgs::msg::TrackedObject; +using autoware_perception_msgs::msg::TrackedObjects; +using autoware_planning_msgs::msg::Trajectory; using geometry_msgs::msg::Pose; using nav_msgs::msg::Odometry; using sensor_msgs::msg::PointCloud2; // Buffers to be used to store subscribed messages' data, pipeline Header, and PublishedTime using MessageBuffer = std::optional; -// We need to store the past AckermannControlCommands to analyze the first brake -using ControlCommandBuffer = std::pair, MessageBuffer>; +// We need to store the past Control to analyze the first brake +using ControlCommandBuffer = std::pair, MessageBuffer>; // Variant to store different types of buffers using MessageBufferVariant = std::variant; @@ -67,7 +67,7 @@ struct SubscriberVariables std::unique_ptr> sub1_; std::unique_ptr> sub2_; std::unique_ptr> synchronizer_; - // tmp: only for the messages who don't have header e.g. AckermannControlCommand + // tmp: only for the messages who don't have header e.g. Control std::unique_ptr> cache_; }; @@ -75,7 +75,7 @@ struct SubscriberVariables using SubscriberVariablesVariant = std::variant< SubscriberVariables, SubscriberVariables, SubscriberVariables, SubscriberVariables, - SubscriberVariables, SubscriberVariables>; + SubscriberVariables, SubscriberVariables>; // The configuration of the topic to be subscribed which are defined in reaction_chain struct TopicConfig @@ -153,14 +153,11 @@ class SubscriberBase bool init_subscribers(); std::optional get_subscriber_variable( const TopicConfig & topic_config); - std::optional find_first_brake_idx( - const std::vector & cmd_array); - void set_control_command_to_buffer( - std::vector & buffer, const AckermannControlCommand & cmd) const; + std::optional find_first_brake_idx(const std::vector & cmd_array); + void set_control_command_to_buffer(std::vector & buffer, const Control & cmd) const; // Callbacks for modules are subscribed - void on_control_command( - const std::string & node_name, const AckermannControlCommand::ConstSharedPtr & msg_ptr); + void on_control_command(const std::string & node_name, const Control::ConstSharedPtr & msg_ptr); void on_trajectory(const std::string & node_name, const Trajectory::ConstSharedPtr & msg_ptr); void on_trajectory( const std::string & node_name, const Trajectory::ConstSharedPtr & msg_ptr, diff --git a/tools/reaction_analyzer/include/topic_publisher.hpp b/tools/reaction_analyzer/include/topic_publisher.hpp index c6d3a90650884..0c01561fec508 100644 --- a/tools/reaction_analyzer/include/topic_publisher.hpp +++ b/tools/reaction_analyzer/include/topic_publisher.hpp @@ -20,12 +20,12 @@ #include #include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include #include #include #include @@ -45,12 +45,12 @@ namespace reaction_analyzer::topic_publisher { -using autoware_auto_control_msgs::msg::AckermannControlCommand; -using autoware_auto_perception_msgs::msg::DetectedObject; -using autoware_auto_perception_msgs::msg::DetectedObjects; -using autoware_auto_perception_msgs::msg::PredictedObject; -using autoware_auto_perception_msgs::msg::PredictedObjects; -using autoware_auto_planning_msgs::msg::Trajectory; +using autoware_control_msgs::msg::Control; +using autoware_perception_msgs::msg::DetectedObject; +using autoware_perception_msgs::msg::DetectedObjects; +using autoware_perception_msgs::msg::PredictedObject; +using autoware_perception_msgs::msg::PredictedObjects; +using autoware_planning_msgs::msg::Trajectory; using geometry_msgs::msg::Pose; using nav_msgs::msg::Odometry; using sensor_msgs::msg::PointCloud2; @@ -164,12 +164,12 @@ using PublisherVariablesVariant = std::variant< PublisherVariables, PublisherVariables, PublisherVariables, PublisherVariables, - PublisherVariables, - PublisherVariables, - PublisherVariables, - PublisherVariables, - PublisherVariables, - PublisherVariables>; + PublisherVariables, + PublisherVariables, + PublisherVariables, + PublisherVariables, + PublisherVariables, + PublisherVariables>; using LidarOutputPair = std::pair< std::shared_ptr>, diff --git a/tools/reaction_analyzer/include/utils.hpp b/tools/reaction_analyzer/include/utils.hpp index da1defc03f34c..4a31da363deff 100644 --- a/tools/reaction_analyzer/include/utils.hpp +++ b/tools/reaction_analyzer/include/utils.hpp @@ -22,12 +22,12 @@ #include #include -#include -#include -#include -#include -#include +#include #include +#include +#include +#include +#include #include #include #include @@ -52,16 +52,16 @@ // The reaction_analyzer namespace contains utility functions for the Reaction Analyzer tool. namespace reaction_analyzer { -using autoware_auto_control_msgs::msg::AckermannControlCommand; -using autoware_auto_perception_msgs::msg::DetectedObject; -using autoware_auto_perception_msgs::msg::DetectedObjects; -using autoware_auto_perception_msgs::msg::PredictedObject; -using autoware_auto_perception_msgs::msg::PredictedObjects; -using autoware_auto_perception_msgs::msg::TrackedObject; -using autoware_auto_perception_msgs::msg::TrackedObjects; -using autoware_auto_planning_msgs::msg::Trajectory; -using autoware_auto_planning_msgs::msg::TrajectoryPoint; +using autoware_control_msgs::msg::Control; using autoware_internal_msgs::msg::PublishedTime; +using autoware_perception_msgs::msg::DetectedObject; +using autoware_perception_msgs::msg::DetectedObjects; +using autoware_perception_msgs::msg::PredictedObject; +using autoware_perception_msgs::msg::PredictedObjects; +using autoware_perception_msgs::msg::TrackedObject; +using autoware_perception_msgs::msg::TrackedObjects; +using autoware_planning_msgs::msg::Trajectory; +using autoware_planning_msgs::msg::TrajectoryPoint; using sensor_msgs::msg::PointCloud2; /** @@ -111,7 +111,7 @@ enum class PublisherMessageType { */ enum class SubscriberMessageType { UNKNOWN = 0, - ACKERMANN_CONTROL_COMMAND = 1, + CONTROL = 1, TRAJECTORY = 2, POINTCLOUD2 = 3, DETECTED_OBJECTS = 4, diff --git a/tools/reaction_analyzer/package.xml b/tools/reaction_analyzer/package.xml index 05081eac01751..a5199aa78c9f8 100644 --- a/tools/reaction_analyzer/package.xml +++ b/tools/reaction_analyzer/package.xml @@ -15,12 +15,12 @@ autoware_cmake autoware_adapi_v1_msgs - autoware_auto_control_msgs - autoware_auto_perception_msgs - autoware_auto_planning_msgs - autoware_auto_system_msgs - autoware_auto_vehicle_msgs + autoware_control_msgs autoware_internal_msgs + autoware_perception_msgs + autoware_planning_msgs + autoware_system_msgs + autoware_vehicle_msgs eigen libpcl-all-dev message_filters diff --git a/tools/reaction_analyzer/param/reaction_analyzer.param.yaml b/tools/reaction_analyzer/param/reaction_analyzer.param.yaml index 62c1191bd345a..b40a67ecc333c 100644 --- a/tools/reaction_analyzer/param/reaction_analyzer.param.yaml +++ b/tools/reaction_analyzer/param/reaction_analyzer.param.yaml @@ -54,27 +54,27 @@ obstacle_cruise_planner: topic_name: /planning/scenario_planning/lane_driving/trajectory time_debug_topic_name: /planning/scenario_planning/lane_driving/trajectory/debug/published_time - message_type: autoware_auto_planning_msgs/msg/Trajectory + message_type: autoware_planning_msgs/msg/Trajectory scenario_selector: topic_name: /planning/scenario_planning/scenario_selector/trajectory time_debug_topic_name: /planning/scenario_planning/scenario_selector/trajectory/debug/published_time - message_type: autoware_auto_planning_msgs/msg/Trajectory + message_type: autoware_planning_msgs/msg/Trajectory motion_velocity_smoother: topic_name: /planning/scenario_planning/motion_velocity_smoother/trajectory time_debug_topic_name: /planning/scenario_planning/motion_velocity_smoother/trajectory/debug/published_time - message_type: autoware_auto_planning_msgs/msg/Trajectory + message_type: autoware_planning_msgs/msg/Trajectory planning_validator: topic_name: /planning/scenario_planning/trajectory time_debug_topic_name: /planning/scenario_planning/trajectory/debug/published_time - message_type: autoware_auto_planning_msgs/msg/Trajectory + message_type: autoware_planning_msgs/msg/Trajectory trajectory_follower: topic_name: /control/trajectory_follower/control_cmd time_debug_topic_name: /control/trajectory_follower/control_cmd/debug/published_time - message_type: autoware_auto_control_msgs/msg/AckermannControlCommand + message_type: autoware_control_msgs/msg/Control vehicle_cmd_gate: topic_name: /control/command/control_cmd time_debug_topic_name: /control/command/control_cmd/debug/published_time - message_type: autoware_auto_control_msgs/msg/AckermannControlCommand + message_type: autoware_control_msgs/msg/Control common_ground_filter: topic_name: /perception/obstacle_segmentation/single_frame/pointcloud time_debug_topic_name: /perception/obstacle_segmentation/single_frame/pointcloud/debug/published_time @@ -86,32 +86,32 @@ multi_object_tracker: topic_name: /perception/object_recognition/tracking/near_objects time_debug_topic_name: /perception/object_recognition/tracking/near_objects/debug/published_time - message_type: autoware_auto_perception_msgs/msg/TrackedObjects + message_type: autoware_perception_msgs/msg/TrackedObjects lidar_centerpoint: topic_name: /perception/object_recognition/detection/centerpoint/objects time_debug_topic_name: /perception/object_recognition/detection/centerpoint/objects/debug/published_time - message_type: autoware_auto_perception_msgs/msg/DetectedObjects + message_type: autoware_perception_msgs/msg/DetectedObjects obstacle_pointcloud_based_validator: topic_name: /perception/object_recognition/detection/centerpoint/validation/objects time_debug_topic_name: /perception/object_recognition/detection/centerpoint/validation/objects/debug/published_time - message_type: autoware_auto_perception_msgs/msg/DetectedObjects + message_type: autoware_perception_msgs/msg/DetectedObjects decorative_tracker_merger: topic_name: /perception/object_recognition/tracking/objects time_debug_topic_name: /perception/object_recognition/tracking/objects/debug/published_time - message_type: autoware_auto_perception_msgs/msg/TrackedObjects + message_type: autoware_perception_msgs/msg/TrackedObjects detected_object_feature_remover: topic_name: /perception/object_recognition/detection/clustering/objects time_debug_topic_name: /perception/object_recognition/detection/clustering/objects/debug/published_time - message_type: autoware_auto_perception_msgs/msg/DetectedObjects + message_type: autoware_perception_msgs/msg/DetectedObjects detection_by_tracker: topic_name: /perception/object_recognition/detection/detection_by_tracker/objects time_debug_topic_name: /perception/object_recognition/detection/detection_by_tracker/objects/debug/published_time - message_type: autoware_auto_perception_msgs/msg/DetectedObjects + message_type: autoware_perception_msgs/msg/DetectedObjects object_lanelet_filter: topic_name: /perception/object_recognition/detection/objects time_debug_topic_name: /perception/object_recognition/detection/objects/debug/published_time - message_type: autoware_auto_perception_msgs/msg/DetectedObjects + message_type: autoware_perception_msgs/msg/DetectedObjects map_based_prediction: topic_name: /perception/object_recognition/objects time_debug_topic_name: /perception/object_recognition/objects/debug/published_time - message_type: autoware_auto_perception_msgs/msg/PredictedObjects + message_type: autoware_perception_msgs/msg/PredictedObjects diff --git a/tools/reaction_analyzer/src/subscriber.cpp b/tools/reaction_analyzer/src/subscriber.cpp index 8c735c42b9cd5..9064f42377d10 100644 --- a/tools/reaction_analyzer/src/subscriber.cpp +++ b/tools/reaction_analyzer/src/subscriber.cpp @@ -189,12 +189,12 @@ void SubscriberBase::reset() // Callbacks void SubscriberBase::on_control_command( - const std::string & node_name, const AckermannControlCommand::ConstSharedPtr & msg_ptr) + const std::string & node_name, const Control::ConstSharedPtr & msg_ptr) { std::lock_guard lock(mutex_); auto & variant = message_buffers_[node_name]; if (!std::holds_alternative(variant)) { - ControlCommandBuffer buffer(std::vector{*msg_ptr}, std::nullopt); + ControlCommandBuffer buffer(std::vector{*msg_ptr}, std::nullopt); variant = buffer; } auto & cmd_buffer = std::get(variant); @@ -212,7 +212,7 @@ void SubscriberBase::on_control_command( // TODO(brkay54): update here if message_filters package add support for the messages which // does not have header const auto & subscriber_variant = - std::get>(subscriber_variables_map_[node_name]); + std::get>(subscriber_variables_map_[node_name]); // check if the cache was initialized or not, if there is, use it to set the published time if (subscriber_variant.cache_) { @@ -636,24 +636,23 @@ std::optional SubscriberBase::get_subscriber_variabl const TopicConfig & topic_config) { switch (topic_config.message_type) { - case SubscriberMessageType::ACKERMANN_CONTROL_COMMAND: { - SubscriberVariables subscriber_variable; + case SubscriberMessageType::CONTROL: { + SubscriberVariables subscriber_variable; if (!topic_config.time_debug_topic_address.empty()) { // If not empty, user should define a time debug topic // NOTE: Because message_filters package does not support the messages without headers, we // can not use the synchronizer. After we reacted, we are going to use the cache - // of the both PublishedTime and AckermannControlCommand subscribers to find the messages + // of the both PublishedTime and Control subscribers to find the messages // which have same header time. - std::function callback = - [this, topic_config](const AckermannControlCommand::ConstSharedPtr & ptr) { + std::function callback = + [this, topic_config](const Control::ConstSharedPtr & ptr) { this->on_control_command(topic_config.node_name, ptr); }; - subscriber_variable.sub1_ = - std::make_unique>( - node_, topic_config.topic_address, rclcpp::QoS(1).get_rmw_qos_profile(), - create_subscription_options(node_)); + subscriber_variable.sub1_ = std::make_unique>( + node_, topic_config.topic_address, rclcpp::QoS(1).get_rmw_qos_profile(), + create_subscription_options(node_)); subscriber_variable.sub1_->registerCallback(std::bind(callback, std::placeholders::_1)); @@ -665,15 +664,14 @@ std::optional SubscriberBase::get_subscriber_variabl *subscriber_variable.sub2_, cache_size); } else { - std::function callback = - [this, topic_config](const AckermannControlCommand::ConstSharedPtr & ptr) { + std::function callback = + [this, topic_config](const Control::ConstSharedPtr & ptr) { this->on_control_command(topic_config.node_name, ptr); }; - subscriber_variable.sub1_ = - std::make_unique>( - node_, topic_config.topic_address, rclcpp::QoS(1).get_rmw_qos_profile(), - create_subscription_options(node_)); + subscriber_variable.sub1_ = std::make_unique>( + node_, topic_config.topic_address, rclcpp::QoS(1).get_rmw_qos_profile(), + create_subscription_options(node_)); subscriber_variable.sub1_->registerCallback(std::bind(callback, std::placeholders::_1)); RCLCPP_WARN( @@ -915,8 +913,7 @@ std::optional SubscriberBase::get_subscriber_variabl } } -std::optional SubscriberBase::find_first_brake_idx( - const std::vector & cmd_array) +std::optional SubscriberBase::find_first_brake_idx(const std::vector & cmd_array) { if ( cmd_array.size() < @@ -975,7 +972,7 @@ std::optional SubscriberBase::find_first_brake_idx( } void SubscriberBase::set_control_command_to_buffer( - std::vector & buffer, const AckermannControlCommand & cmd) const + std::vector & buffer, const Control & cmd) const { const auto last_cmd_time = cmd.stamp; if (!buffer.empty()) { diff --git a/tools/reaction_analyzer/src/topic_publisher.cpp b/tools/reaction_analyzer/src/topic_publisher.cpp index 8a66bf9e33911..f720786d422bc 100644 --- a/tools/reaction_analyzer/src/topic_publisher.cpp +++ b/tools/reaction_analyzer/src/topic_publisher.cpp @@ -512,22 +512,22 @@ void TopicPublisher::init_rosbag_publisher_buffer( } else if (message_type == PublisherMessageType::IMU) { set_message(current_topic, *bag_message, is_empty_area_message); } else if (message_type == PublisherMessageType::CONTROL_MODE_REPORT) { - set_message( + set_message( current_topic, *bag_message, is_empty_area_message); } else if (message_type == PublisherMessageType::GEAR_REPORT) { - set_message( + set_message( current_topic, *bag_message, is_empty_area_message); } else if (message_type == PublisherMessageType::HAZARD_LIGHTS_REPORT) { - set_message( + set_message( current_topic, *bag_message, is_empty_area_message); } else if (message_type == PublisherMessageType::STEERING_REPORT) { - set_message( + set_message( current_topic, *bag_message, is_empty_area_message); } else if (message_type == PublisherMessageType::TURN_INDICATORS_REPORT) { - set_message( + set_message( current_topic, *bag_message, is_empty_area_message); } else if (message_type == PublisherMessageType::VELOCITY_REPORT) { - set_message( + set_message( current_topic, *bag_message, is_empty_area_message); } } diff --git a/tools/reaction_analyzer/src/utils.cpp b/tools/reaction_analyzer/src/utils.cpp index 4a6110322440e..9f9198af7dc48 100644 --- a/tools/reaction_analyzer/src/utils.cpp +++ b/tools/reaction_analyzer/src/utils.cpp @@ -18,22 +18,22 @@ namespace reaction_analyzer { SubscriberMessageType get_subscriber_message_type(const std::string & message_type) { - if (message_type == "autoware_auto_control_msgs/msg/AckermannControlCommand") { - return SubscriberMessageType::ACKERMANN_CONTROL_COMMAND; + if (message_type == "autoware_control_msgs/msg/Control") { + return SubscriberMessageType::CONTROL; } - if (message_type == "autoware_auto_planning_msgs/msg/Trajectory") { + if (message_type == "autoware_planning_msgs/msg/Trajectory") { return SubscriberMessageType::TRAJECTORY; } if (message_type == "sensor_msgs/msg/PointCloud2") { return SubscriberMessageType::POINTCLOUD2; } - if (message_type == "autoware_auto_perception_msgs/msg/PredictedObjects") { + if (message_type == "autoware_perception_msgs/msg/PredictedObjects") { return SubscriberMessageType::PREDICTED_OBJECTS; } - if (message_type == "autoware_auto_perception_msgs/msg/DetectedObjects") { + if (message_type == "autoware_perception_msgs/msg/DetectedObjects") { return SubscriberMessageType::DETECTED_OBJECTS; } - if (message_type == "autoware_auto_perception_msgs/msg/TrackedObjects") { + if (message_type == "autoware_perception_msgs/msg/TrackedObjects") { return SubscriberMessageType::TRACKED_OBJECTS; } return SubscriberMessageType::UNKNOWN; @@ -62,22 +62,22 @@ PublisherMessageType get_publisher_message_type(const std::string & message_type if (message_type == "sensor_msgs/msg/Imu") { return PublisherMessageType::IMU; } - if (message_type == "autoware_auto_vehicle_msgs/msg/ControlModeReport") { + if (message_type == "autoware_vehicle_msgs/msg/ControlModeReport") { return PublisherMessageType::CONTROL_MODE_REPORT; } - if (message_type == "autoware_auto_vehicle_msgs/msg/GearReport") { + if (message_type == "autoware_vehicle_msgs/msg/GearReport") { return PublisherMessageType::GEAR_REPORT; } - if (message_type == "autoware_auto_vehicle_msgs/msg/HazardLightsReport") { + if (message_type == "autoware_vehicle_msgs/msg/HazardLightsReport") { return PublisherMessageType::HAZARD_LIGHTS_REPORT; } - if (message_type == "autoware_auto_vehicle_msgs/msg/SteeringReport") { + if (message_type == "autoware_vehicle_msgs/msg/SteeringReport") { return PublisherMessageType::STEERING_REPORT; } - if (message_type == "autoware_auto_vehicle_msgs/msg/TurnIndicatorsReport") { + if (message_type == "autoware_vehicle_msgs/msg/TurnIndicatorsReport") { return PublisherMessageType::TURN_INDICATORS_REPORT; } - if (message_type == "autoware_auto_vehicle_msgs/msg/VelocityReport") { + if (message_type == "autoware_vehicle_msgs/msg/VelocityReport") { return PublisherMessageType::VELOCITY_REPORT; } return PublisherMessageType::UNKNOWN; @@ -360,17 +360,17 @@ PredictedObjects::SharedPtr create_entity_predicted_objects_ptr(const EntityPara dimension.set__z(entity_params.z_l); obj.shape.set__dimensions(dimension); - obj.shape.type = autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX; + obj.shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX; obj.existence_probability = 1.0; obj.kinematics.initial_pose_with_covariance.pose = entity_pose; - autoware_auto_perception_msgs::msg::PredictedPath path; + autoware_perception_msgs::msg::PredictedPath path; path.confidence = 1.0; path.path.emplace_back(entity_pose); obj.kinematics.predicted_paths.emplace_back(path); - autoware_auto_perception_msgs::msg::ObjectClassification classification; - classification.label = autoware_auto_perception_msgs::msg::ObjectClassification::CAR; + autoware_perception_msgs::msg::ObjectClassification classification; + classification.label = autoware_perception_msgs::msg::ObjectClassification::CAR; classification.probability = 1.0; obj.classification.emplace_back(classification); obj.set__object_id(generate_uuid_msg("test_obstacle"));