diff --git a/perception/radar_fusion_to_detected_object/README.md b/perception/radar_fusion_to_detected_object/README.md index 78db70f8f9c36..b22938cbf0e5a 100644 --- a/perception/radar_fusion_to_detected_object/README.md +++ b/perception/radar_fusion_to_detected_object/README.md @@ -56,10 +56,10 @@ ros2 launch radar_fusion_to_detected_object radar_object_to_detected_object.laun ### Input -| Name | Type | Description | -| ----------------------- | ---------------------------------------------------- | ---------------------------------------------------------------------- | -| `~/input/objects` | autoware_auto_perception_msgs/msg/DetectedObject.msg | 3D detected objects. | -| `~/input/radar_objects` | autoware_auto_perception_msgs/msg/TrackedObjects.msg | Radar objects. Note that frame_id need to be same as `~/input/objects` | +| Name | Type | Description | +| ----------------------- | ----------------------------------------------------- | ---------------------------------------------------------------------- | +| `~/input/objects` | autoware_auto_perception_msgs/msg/DetectedObject.msg | 3D detected objects. | +| `~/input/radar_objects` | autoware_auto_perception_msgs/msg/DetectedObjects.msg | Radar objects. Note that frame_id need to be same as `~/input/objects` | ### Output diff --git a/perception/radar_fusion_to_detected_object/include/radar_object_fusion_to_detected_object/radar_object_fusion_to_detected_object_node.hpp b/perception/radar_fusion_to_detected_object/include/radar_object_fusion_to_detected_object/radar_object_fusion_to_detected_object_node.hpp index aab580d34fe09..1a90e9f6bd046 100644 --- a/perception/radar_fusion_to_detected_object/include/radar_object_fusion_to_detected_object/radar_object_fusion_to_detected_object_node.hpp +++ b/perception/radar_fusion_to_detected_object/include/radar_object_fusion_to_detected_object/radar_object_fusion_to_detected_object_node.hpp @@ -23,7 +23,6 @@ #include "rclcpp/rclcpp.hpp" #include "autoware_auto_perception_msgs/msg/detected_objects.hpp" -#include "autoware_auto_perception_msgs/msg/tracked_objects.hpp" #include #include @@ -34,8 +33,6 @@ namespace radar_fusion_to_detected_object { using autoware_auto_perception_msgs::msg::DetectedObject; using autoware_auto_perception_msgs::msg::DetectedObjects; -using autoware_auto_perception_msgs::msg::TrackedObject; -using autoware_auto_perception_msgs::msg::TrackedObjects; class RadarObjectFusionToDetectedObjectNode : public rclcpp::Node { @@ -50,22 +47,22 @@ class RadarObjectFusionToDetectedObjectNode : public rclcpp::Node private: // Subscriber message_filters::Subscriber sub_object_{}; - message_filters::Subscriber sub_radar_{}; + message_filters::Subscriber sub_radar_{}; using SyncPolicy = - message_filters::sync_policies::ApproximateTime; + message_filters::sync_policies::ApproximateTime; using Sync = message_filters::Synchronizer; typename std::shared_ptr sync_ptr_; // Callback void onData( const DetectedObjects::ConstSharedPtr object_msg, - const TrackedObjects::ConstSharedPtr radar_msg); + const DetectedObjects::ConstSharedPtr radar_msg); bool isDataReady(); // Data Buffer DetectedObjects::ConstSharedPtr detected_objects_{}; - TrackedObjects::ConstSharedPtr radar_objects_{}; + DetectedObjects::ConstSharedPtr radar_objects_{}; // Publisher rclcpp::Publisher::SharedPtr pub_objects_{}; @@ -87,7 +84,7 @@ class RadarObjectFusionToDetectedObjectNode : public rclcpp::Node // Lapper RadarFusionToDetectedObject::RadarInput setRadarInput( - const TrackedObject & radar_object, const std_msgs::msg::Header & header_); + const DetectedObject & radar_object, const std_msgs::msg::Header & header_); }; } // namespace radar_fusion_to_detected_object diff --git a/perception/radar_fusion_to_detected_object/src/radar_object_fusion_to_detected_object_node/radar_object_fusion_to_detected_object_node.cpp b/perception/radar_fusion_to_detected_object/src/radar_object_fusion_to_detected_object_node/radar_object_fusion_to_detected_object_node.cpp index c113527cb5424..8e909e4fc08c8 100644 --- a/perception/radar_fusion_to_detected_object/src/radar_object_fusion_to_detected_object_node/radar_object_fusion_to_detected_object_node.cpp +++ b/perception/radar_fusion_to_detected_object/src/radar_object_fusion_to_detected_object_node/radar_object_fusion_to_detected_object_node.cpp @@ -51,7 +51,6 @@ namespace radar_fusion_to_detected_object { using autoware_auto_perception_msgs::msg::DetectedObject; using autoware_auto_perception_msgs::msg::DetectedObjects; -using autoware_auto_perception_msgs::msg::TrackedObjects; RadarObjectFusionToDetectedObjectNode::RadarObjectFusionToDetectedObjectNode( const rclcpp::NodeOptions & node_options) @@ -181,7 +180,7 @@ bool RadarObjectFusionToDetectedObjectNode::isDataReady() } void RadarObjectFusionToDetectedObjectNode::onData( - const DetectedObjects::ConstSharedPtr object_msg, const TrackedObjects::ConstSharedPtr radar_msg) + const DetectedObjects::ConstSharedPtr object_msg, const DetectedObjects::ConstSharedPtr radar_msg) { detected_objects_ = object_msg; radar_objects_ = radar_msg; @@ -211,7 +210,7 @@ void RadarObjectFusionToDetectedObjectNode::onData( } RadarFusionToDetectedObject::RadarInput RadarObjectFusionToDetectedObjectNode::setRadarInput( - const TrackedObject & radar_object, const std_msgs::msg::Header & header_) + const DetectedObject & radar_object, const std_msgs::msg::Header & header_) { RadarFusionToDetectedObject::RadarInput output{}; output.pose_with_covariance = radar_object.kinematics.pose_with_covariance;