Skip to content

roi_cluster_fusion#

Purpose#

The roi_cluster_fusion is a package for filtering clusters that are less likely to be objects and overwriting labels of clusters with that of Region Of Interests (ROIs) by a 2D object detector.

Inner-workings / Algorithms#

The clusters are projected onto image planes, and then if the ROIs of clusters and ROIs by a detector are overlapped, the labels of clusters are overwritten with that of ROIs by detector. Intersection over Union (IoU) is used to determine if there are overlaps between them.

roi_cluster_fusion_image

Inputs / Outputs#

Input#

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/rois[0-7] tier4_perception_msgs::msg::DetectedObjectsWithFeature ROIs 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#

The following figure is an inner pipeline overview of RoI cluster fusion node. Please refer to it for your parameter settings.

roi_cluster_fusion_pipeline

Core 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.0
strict_iou_fusion_distance float If the detected object's distance is less than its value, IoU method specified in strict_iou_match_mode is used, otherwise rough_iou_match_mode is used. 100.0 ≥0.0
strict_iou_match_mode string Name of IoU method applied to the objects in range of [0.0, trust_distance]. iou ['iou', 'iou_x', 'iou_y']
rough_iou_match_mode string Name of IoU method applied to the objects in range of [trust_distance, fusion_distance], if trust_distance < fusion_distance. iou_x ['iou', 'iou_x', 'iou_y']
use_cluster_semantic_type boolean If this parameter is false, label of cluster objects will be reset to UNKNOWN. False N/A
only_allow_inside_cluster boolean If this parameter is true, only clusters in which all their points are inside the RoI can be assigned to the RoI. True N/A
roi_scale_factor float A scale factor for resizing RoI while checking if cluster points are inside the RoI. 1.1 ≥1.0
≤2.0
iou_threshold.UNKNOWN float IoU threshold for UNKNOWN objects. 0.1 ≥0.0
≤1.0
iou_threshold.CAR float IoU threshold for CAR objects. 0.65 ≥0.0
≤1.0
iou_threshold.TRUCK float IoU threshold for TRUCK objects. 0.65 ≥0.0
≤1.0
iou_threshold.BUS float IoU threshold for BUS objects. 0.65 ≥0.0
≤1.0
iou_threshold.TRAILER float IoU threshold for TRAILER objects. 0.65 ≥0.0
≤1.0
iou_threshold.MOTORCYCLE float IoU threshold for MOTORCYCLE objects. 0.65 ≥0.0
≤1.0
iou_threshold.BICYCLE float IoU threshold for BICYCLE objects. 0.65 ≥0.0
≤1.0
iou_threshold.PEDESTRIAN float IoU threshold for PEDESTRIAN objects. 0.65 ≥0.0
≤1.0
remove_unknown boolean If this parameter is true, all of objects labeled UNKNOWN will be removed in post-process. False N/A

Example Configuration#

The iou_threshold parameter should be configured as an object with thresholds for each object class:

iou_threshold:
  UNKNOWN: 0.1
  CAR: 0.65
  TRUCK: 0.65
  BUS: 0.65
  TRAILER: 0.65
  MOTORCYCLE: 0.65
  BICYCLE: 0.65
  PEDESTRIAN: 0.65

The threshold values determine the minimum IoU score required to overwrite a cluster's label with the corresponding ROI label. Different thresholds can be set for each object class to account for varying detection characteristics.

Assumptions / Known limits#

(Optional) Error detection and handling#

(Optional) Performance characterization#

(Optional) Future extensions / Unimplemented parts#