object_merger#
Purpose#
object_merger is a package for merging detected objects from two methods by data association.
Inner-workings / Algorithms#
The successive shortest path algorithm is used to solve the data association problem (the minimum-cost flow problem). The cost is calculated by the distance between two objects and gate functions are applied to reset cost, s.t. the maximum distance, the maximum area and the minimum area.
Inputs / Outputs#
Input#
Name | Type | Description |
---|---|---|
input/object0 |
autoware_perception_msgs::msg::DetectedObjects |
detection objects |
input/object1 |
autoware_perception_msgs::msg::DetectedObjects |
detection objects |
Output#
Name | Type | Description |
---|---|---|
output/object |
autoware_perception_msgs::msg::DetectedObjects |
modified Objects |
Parameters#
- object association merger
Name | Type | Description | Default | Range |
---|---|---|---|---|
sync_queue_size | integer | The size of the synchronization queue. | 20 | N/A |
precision_threshold_to_judge_overlapped | float | The precision threshold to judge if objects are overlapped. | 0.4 | N/A |
recall_threshold_to_judge_overlapped | float | The recall threshold to judge if objects are overlapped. | 0.5 | N/A |
remove_overlapped_unknown_objects | boolean | Flag to remove overlapped unknown objects. | True | N/A |
base_link_frame_id | string | The frame ID of the association frame. | base_link | N/A |
priority_mode | integer | Index for the priority_mode. | 3 | [0, 1, 2, 3] |
- data association matrix
Name | Type | Description | Default | Range |
---|---|---|---|---|
can_assign_matrix | array | Assignment table for data association. | [0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 0, 0, 0, 0, 0, 1, 1, 1, 0, 0, 0, 0, 0, 1, 1, 1] | N/A |
max_dist_matrix | array | Maximum distance table for data association. | [4.0, 4.0, 5.0, 5.0, 5.0, 2.0, 2.0, 2.0, 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, 5.0, 5.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, 5.0, 5.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, 5.0, 5.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, 2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.0, 2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 3.0, 2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0] | N/A |
max_rad_matrix | array | Maximum angle table for data association. If value is greater than pi, it will be ignored. | [3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 1.047, 1.047, 1.047, 1.047, 3.15, 3.15, 3.15, 3.15, 1.047, 1.047, 1.047, 1.047, 3.15, 3.15, 3.15, 3.15, 1.047, 1.047, 1.047, 1.047, 3.15, 3.15, 3.15, 3.15, 1.047, 1.047, 1.047, 1.047, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15, 3.15] | N/A |
min_iou_matrix | array | Minimum IoU threshold matrix for data association. If value is negative, it will be ignored. | [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.3, 0.2, 0.2, 0.2, 0.1, 0.1, 0.1, 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] | N/A |
- overlapped judge
Name | Type | Description | Default | Range |
---|---|---|---|---|
distance_threshold_list | array | Distance threshold for each class used in judging overlap. | [9.0, 9.0, 9.0, 9.0, 9.0, 9.0, 9.0, 9.0] | N/A |
generalized_iou_threshold | array | Generalized IoU threshold for each class. | [-0.1, -0.1, -0.1, -0.6, -0.6, -0.1, -0.1, -0.1] | N/A |
Tips#
- False Positive Unknown object detected by clustering method sometimes raises the risk of sudden stop and interferes with Planning module. If ML based detector rarely misses objects, you can tune the parameter of object_merger and make Perception module ignore unknown objects.
- If you want to remove unknown object close to large vehicle,
- use HIGH
distance_threshold_list
- However, this causes high computational load
- use LOW
precision_threshold_to_judge_overlapped
- use LOW
generalized_iou_threshold
- However, these 2 params raise the risk of overlooking object close to known object.
- use HIGH
- If you want to remove unknown object close to large vehicle,
Assumptions / Known limits#
(Optional) Error detection and handling#
(Optional) Performance characterization#
(Optional) References/External links#
(Optional) Future extensions / Unimplemented parts#
Data association algorithm was the same as that of multi_object_tracker, but the algorithm of multi_object_tracker was already updated.