Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(radar_fusion_to_detected_object): fix input from TrackedObjects to DetectedObjects #3459

Merged
merged 3 commits into from
May 10, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 4 additions & 4 deletions perception/radar_fusion_to_detected_object/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 <chrono>
#include <memory>
Expand All @@ -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
{
Expand All @@ -50,22 +47,22 @@ class RadarObjectFusionToDetectedObjectNode : public rclcpp::Node
private:
// Subscriber
message_filters::Subscriber<DetectedObjects> sub_object_{};
message_filters::Subscriber<TrackedObjects> sub_radar_{};
message_filters::Subscriber<DetectedObjects> sub_radar_{};

using SyncPolicy =
message_filters::sync_policies::ApproximateTime<DetectedObjects, TrackedObjects>;
message_filters::sync_policies::ApproximateTime<DetectedObjects, DetectedObjects>;
using Sync = message_filters::Synchronizer<SyncPolicy>;
typename std::shared_ptr<Sync> 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<DetectedObjects>::SharedPtr pub_objects_{};
Expand All @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down