Skip to content

Commit

Permalink
refactor: msg type
Browse files Browse the repository at this point in the history
Signed-off-by: Barış Zeren <[email protected]>
  • Loading branch information
StepTurtle committed Dec 12, 2024
1 parent 6b1833c commit e36df2d
Show file tree
Hide file tree
Showing 4 changed files with 14 additions and 13 deletions.
17 changes: 9 additions & 8 deletions perception/autoware_tensorrt_rtmdet/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,17 +12,17 @@ bicycles, etc. in a scene. This package provides a ROS 2 interface for RTMDet us
### Input

| Name | Type | Description |
| ---------- | ------------------- | --------------- |
|------------|---------------------|-----------------|
| `in/image` | `sensor_msgs/Image` | The input image |

### Output

| Name | Type | Description |
| ----------------- | -------------------------------------------------- | ------------------------------------------------------------------- |
| `out/objects` | `tier4_perception_msgs/DetectedObjectsWithFeature` | The detected objects with 2D bounding boxes and scores |
| `out/mask` | `autoware_perception_msgs/SegmentationMask` | The instance segmentation mask |
| `out/color_mask` | `sensor_msgs/Image` | The colorized image of instance segmentation mask for visualization |
| `out/debug_image` | `sensor_msgs/Image` | The image with 2D bounding boxes for visualization |
| Name | Type | Description |
|-------------------|------------------------------------------------------|---------------------------------------------------------------------|
| `out/objects` | `tier4_perception_msgs/DetectedObjectsWithFeature` | The detected objects with 2D bounding boxes and scores |
| `out/mask` | `autoware_internal_perception_msgs/SegmentationMask` | The instance segmentation mask |
| `out/color_mask` | `sensor_msgs/Image` | The colorized image of instance segmentation mask for visualization |
| `out/debug_image` | `sensor_msgs/Image` | The image with 2D bounding boxes for visualization |

## Parameters

Expand All @@ -36,7 +36,8 @@ A sample model is provided in `autoware_data` folder by ansible script on env pr
model, you follow instructions from the
[link](https://github.com/autowarefoundation/autoware/tree/main/ansible/roles/artifacts) to download the model.

The shared model was trained by open-mmlab using the COCO dataset. For more details, see [link](https://github.com/open-mmlab/mmdetection/tree/3.x/configs/rtmdet#instance-segmentation).
The shared model was trained by open-mmlab using the COCO dataset. For more details,
see [link](https://github.com/open-mmlab/mmdetection/tree/3.x/configs/rtmdet#instance-segmentation).

### Package acceptable model generation

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
#include <image_transport/image_transport.hpp>
#include <rclcpp/rclcpp.hpp>

#include "autoware_perception_msgs/msg/segmentation_mask.hpp"
#include "autoware_internal_perception_msgs/msg/segmentation_mask.hpp"
#include "tier4_perception_msgs/msg/detected_objects_with_feature.hpp"

#include <cv_bridge/cv_bridge.h>
Expand Down Expand Up @@ -108,7 +108,7 @@ class TrtRTMDetNode : public rclcpp::Node
rclcpp::TimerBase::SharedPtr timer_;

rclcpp::Publisher<tier4_perception_msgs::msg::DetectedObjectsWithFeature>::SharedPtr objects_pub_;
rclcpp::Publisher<autoware_perception_msgs::msg::SegmentationMask>::SharedPtr mask_pub_;
rclcpp::Publisher<autoware_internal_perception_msgs::msg::SegmentationMask>::SharedPtr mask_pub_;

image_transport::Publisher color_mask_pub_;
image_transport::Publisher debug_image_pub_;
Expand Down
2 changes: 1 addition & 1 deletion perception/autoware_tensorrt_rtmdet/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
<buildtool_export_depend>tensorrt_cmake_module</buildtool_export_depend>

<depend>autoware_cuda_utils</depend>
<depend>autoware_internal_msgs</depend>
<depend>autoware_internal_perception_msgs</depend>
<depend>autoware_object_recognition_utils</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_tensorrt_common</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ TrtRTMDetNode::TrtRTMDetNode(const rclcpp::NodeOptions & node_options)
objects_pub_ = this->create_publisher<tier4_perception_msgs::msg::DetectedObjectsWithFeature>(
"~/out/objects", 1);
mask_pub_ =
this->create_publisher<autoware_perception_msgs::msg::SegmentationMask>("~/out/mask", 1);
this->create_publisher<autoware_internal_perception_msgs::msg::SegmentationMask>("~/out/mask", 1);

color_mask_pub_ = image_transport::create_publisher(this, "~/out/color_mask");
debug_image_pub_ = image_transport::create_publisher(this, "~/out/debug_image");
Expand Down Expand Up @@ -163,7 +163,7 @@ void TrtRTMDetNode::on_image(const sensor_msgs::msg::Image::ConstSharedPtr msg)
object_classification.probability = 1.0;
classification.push_back(object_classification);
}
autoware_perception_msgs::msg::SegmentationMask mask_msg;
autoware_internal_perception_msgs::msg::SegmentationMask mask_msg;
mask_msg.classification = classification;
mask_msg.image = *mask_image;
mask_msg.header = msg->header;
Expand Down

0 comments on commit e36df2d

Please sign in to comment.