mask_cluster_fusion
Purpose
The mask_cluster_fusion
package aims to assign the label of the mask to the cluster by using the mask information from the 2D instance segmentation model.
Inner-workings / Algorithms
- The clusters are projected onto the image plane.
- Find the mask which intersects with the cluster with high IoU.
- Assign the label of the mask to the cluster.
- For all clusters with an assigned label, check if any cluster intersects with the same mask. Reassign the label of the mask to the cluster if its IoU is lower than the previously assigned cluster.
Name |
Type |
Description |
input |
tier4_perception_msgs::msg::DetectedObjectsWithFeature |
clustered pointcloud |
input/camera_info[0-7] |
sensor_msgs::msg::CameraInfo |
camera information to project 3d points onto image planes |
input/masks[0-7] |
autoware_internal_perception_msgs::msg::SegmentationMask |
masks from each image |
input/image_raw[0-7] |
sensor_msgs::msg::Image |
images for visualization |
Output
Name |
Type |
Description |
output |
tier4_perception_msgs::msg::DetectedObjectsWithFeature |
labeled cluster pointcloud |
~/debug/image_raw[0-7] |
sensor_msgs::msg::Image |
images for visualization |
Parameters
Name |
Type |
Description |
Default |
Range |
fusion_distance |
float |
If the detected object's distance is less than its value, the fusion will be processed. |
100 |
≥0.0 |
fusion_ratio |
float |
The ratio between the selected cluster points and the total points in the cluster. |
0.4 |
≥0.0 |
remove_unknown |
boolean |
If this parameter is true, all of objects labeled UNKNOWN will be removed in post-process. |
0 |
N/A |
Assumptions / Known limits