multi_object_tracker#
Purpose#
The results of the detection are processed by a time series. The main purpose is to give ID and estimate velocity.
Inner-workings / Algorithms#
This multi object tracker consists of data association and EKF.
Data association#
The data association performs maximum score matching, called min cost max flow problem. In this package, mussp[1] is used as solver. In addition, when associating observations to tracers, data association have gates such as the area of the object from the BEV, Mahalanobis distance, and maximum distance, depending on the class label.
EKF Tracker#
Models for pedestrians, bicycles (motorcycles), cars and unknown are available. The pedestrian or bicycle tracker is running at the same time as the respective EKF model in order to enable the transition between pedestrian and bicycle tracking. For big vehicles such as trucks and buses, we have separate models for passenger cars and large vehicles because they are difficult to distinguish from passenger cars and are not stable. Therefore, separate models are prepared for passenger cars and big vehicles, and these models are run at the same time as the respective EKF models to ensure stability.
Inputs / Outputs#
Input#
Multiple inputs are pre-defined in the input channel parameters (described below) and the inputs can be configured
Name | Type | Description |
---|---|---|
input/detection**/objects |
std::string |
input topic |
input/detection**/channel |
std::string |
input channel configuration |
rule of the channel configuration
- 'none' or empty : Indicates that this detection input channel is not used/disabled
- Any other string : Specifies a custom channel name to be used for the detection input, configured in
schema/input_channels.schema.json
Up to 12 detection inputs can be configured (detection01 through detection12). Each input consists of an objects topic and its corresponding channel configuration.
Example configurations:
- Single detection input:
input/detection01/objects: /perception/object_recognition/detection/objects
input/detection01/channel: detected_objects # general input channel type
input/detection02/objects: input/objects02
input/detection02/channel: none # Disabled
- Multiple detection inputs:
# lidar centerpoint
input/detection01/objects: /perception/object_recognition/detection/lidar_centerpoint/objects
input/detection01/channel: lidar_centerpoint
# lidar short_range centerpoint
input/detection02/channel: /perception/object_recognition/detection/centerpoint_short_range/objects
input/detection02/objects: lidar_centerpoint_short_range
# camera lidar fusion
input/detection03/objects: /perception/object_recognition/detection/clustering/camera_lidar_fusion/objects
input/detection03/channel: camera_lidar_fusion
# camera lidar fusion based irregular object detection
input/detection04/objects: /perception/object_recognition/detection/irregular_object/objects
input/detection04/channel: camera_lidar_fusion_irregular
# detection by tracker
input/detection05/objects: /perception/object_recognition/detection/detection_by_tracker/objects
input/detection05/channel: detection_by_tracker
# radar
input/detection06/objects: /perception/object_recognition/detection/radar/objects
input/detection06/channel: radar
# disable
input/detection07/objects: input/objects07
input/detection07/channel: none # Disabled
Up to 12 detection inputs can be configured (detection01 through detection12). Each input consists of an objects topic and its corresponding channel configuration.
Output#
Name | Type | Description |
---|---|---|
~/output |
autoware_perception_msgs::msg::TrackedObjects |
tracked objects |
Parameters#
Input Channel parameters#
Name | Type | Description | Default | Range |
---|---|---|---|---|
flags.can_spawn_new_tracker | boolean | Indicates if the input channel can spawn new trackers. | True | N/A |
flags.can_trust_existence_probability | boolean | Indicates if the input channel can trust the existence probability. | True | N/A |
flags.can_trust_extension | boolean | Indicates if the input channel can trust the object size(extension). | True | N/A |
flags.can_trust_classification | boolean | Indicates if the input channel can trust the object classification. | True | N/A |
flags.can_trust_orientation | boolean | Indicates if the input channel can trust the object orientation. | True | N/A |
optional.name | string | The name of the input channel. | detected_objects | N/A |
optional.short_name | string | The short name of the input channel. | all | N/A |
Core Parameters#
- Node
Name | Type | Description | Default | Range |
---|---|---|---|---|
car_tracker | string | Tracker model for car class. | multi_vehicle_tracker | N/A |
truck_tracker | string | Tracker model for truck class. | multi_vehicle_tracker | N/A |
bus_tracker | string | Tracker model for bus class. | multi_vehicle_tracker | N/A |
trailer_tracker | string | Tracker model for trailer class. | multi_vehicle_tracker | N/A |
pedestrian_tracker | string | Tracker model for pedestrian class. | pedestrian_and_bicycle_tracker | N/A |
bicycle_tracker | string | Tracker model for bicycle class. | pedestrian_and_bicycle_tracker | N/A |
motorcycle_tracker | string | Tracker model for motorcycle class. | pedestrian_and_bicycle_tracker | N/A |
publish_rate | float | Timer frequency to output with delay compensation. | 10.0 | N/A |
world_frame_id | string | Object kinematics definition frame. | map | N/A |
ego_frame_id | string | Vehicle's ego frame. | base_link | N/A |
enable_delay_compensation | boolean | If True, tracker use timers to schedule publishers and use prediction step to extrapolate object state at desired timestamp. | False | N/A |
consider_odometry_uncertainty | boolean | If True, consider odometry uncertainty in tracking. | False | N/A |
enable_unknown_object_velocity_estimation | boolean | If True, enable velocity estimation for unknown objects. | True | N/A |
enable_unknown_object_motion_output | boolean | If True, export unknown object velocity. | False | N/A |
tracker_lifetime | float | Lifetime of the tracker in seconds. | 1.0 | N/A |
min_known_object_removal_iou | float | Minimum IOU between associated objects with known label to remove younger tracker | 0.1 | N/A |
min_unknown_object_removal_iou | float | Minimum IOU between associated objects with unknown label to remove unknown tracker | 0.001 | N/A |
confident_count_threshold.UNKNOWN | float | Number of measurements to consider tracker as confident for unknown object classes. | 3 | N/A |
confident_count_threshold.CAR | float | Number of measurements to consider tracker as confident for car object classes. | 3 | N/A |
confident_count_threshold.TRUCK | float | Number of measurements to consider tracker as confident for truck object classes. | 3 | N/A |
confident_count_threshold.BUS | float | Number of measurements to consider tracker as confident for bus object classes. | 3 | N/A |
confident_count_threshold.TRAILER | float | Number of measurements to consider tracker as confident for trailer object classes. | 3 | N/A |
confident_count_threshold.MOTORBIKE | float | Number of measurements to consider tracker as confident for motorbike object classes. | 3 | N/A |
confident_count_threshold.BICYCLE | float | Number of measurements to consider tracker as confident for bicycle object classes. | 3 | N/A |
confident_count_threshold.PEDESTRIAN | float | Number of measurements to consider tracker as confident for pedestrian object classes. | 3 | N/A |
generalized_iou_thresholds | array | Generalized IoU threshold for each class. | [-0.3, -0.4, -0.6, -0.6, -0.6, -0.1, -0.1, -0.1] | N/A |
overlap_distance_thresholds | array | Overlap distance threshold for each class. | [9.0, 5.0, 9.0, 9.0, 9.0, 4.0, 3.0, 2.0] | N/A |
publish_processing_time | boolean | Enable to publish debug message of process time information. | False | N/A |
publish_processing_time_detail | boolean | Enable to publish debug message of detailed process time information. | False | N/A |
publish_tentative_objects | boolean | Enable to publish tentative tracked objects, which have lower confidence. | False | N/A |
publish_debug_markers | boolean | Enable to publish debug markers, which indicates association of multi-inputs, existence probability of each detection. | False | N/A |
diagnostics_warn_delay | float | Delay threshold for warning diagnostics in seconds. | 0.5 | N/A |
diagnostics_error_delay | float | Delay threshold for error diagnostics in seconds. | 1.0 | N/A |
diagnostics_warn_extrapolation | float | Delay extrapolation threshold for warning diagnostics in seconds. | 0.5 | N/A |
diagnostics_error_extrapolation | float | Delay extrapolation threshold for error diagnostics in seconds. | 1.0 | N/A |
- Association
Name | Type | Description | Default | Range |
---|---|---|---|---|
can_assign_matrix | array | Assignment table for data association. | [1, 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, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, 3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, 3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, 2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0] | N/A |
max_area_matrix | array | Maximum area table for data association. | [100.0, 100.0, 100.0, 100.0, 100.0, 100.0, 100.0, 100.0, 12.1, 12.1, 36.0, 60.0, 60.0, 10000.0, 10000.0, 10000.0, 36.0, 12.1, 36.0, 60.0, 60.0, 10000.0, 10000.0, 10000.0, 60.0, 12.1, 36.0, 60.0, 60.0, 10000.0, 10000.0, 10000.0, 60.0, 12.1, 36.0, 60.0, 60.0, 10000.0, 10000.0, 10000.0, 2.5, 10000.0, 10000.0, 10000.0, 10000.0, 2.5, 2.5, 2.5, 2.5, 10000.0, 10000.0, 10000.0, 10000.0, 2.5, 2.5, 2.5, 2.0, 10000.0, 10000.0, 10000.0, 10000.0, 2.0, 2.0, 2.0] | N/A |
min_area_matrix | array | Minimum area table for data association. | [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.6, 3.6, 6.0, 10.0, 10.0, 0.0, 0.0, 0.0, 6.0, 3.6, 6.0, 10.0, 10.0, 0.0, 0.0, 0.0, 10.0, 3.6, 6.0, 10.0, 10.0, 0.0, 0.0, 0.0, 10.0, 3.6, 6.0, 10.0, 10.0, 0.0, 0.0, 0.0, 0.001, 0.0, 0.0, 0.0, 0.0, 0.1, 0.1, 0.1, 0.001, 0.0, 0.0, 0.0, 0.0, 0.1, 0.1, 0.1, 0.001, 0.0, 0.0, 0.0, 0.0, 0.1, 0.1, 0.1] | N/A |
max_rad_matrix | array | Maximum angle table for data association. | [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 | A matrix that represents the minimum Intersection over Union (IoU) limit allowed for assignment. | [0.0001, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 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.0001] | N/A |
unknown_association_giou_threshold | float | GIoU threshold for unknown-unknown association. | -0.8 | N/A |
Simulation parameters#
Name | Type | Description | Default | Range |
---|---|---|---|---|
car_tracker | string | Tracker model for car class. | pass_through_tracker | N/A |
truck_tracker | string | Tracker model for truck class. | pass_through_tracker | N/A |
bus_tracker | string | Tracker model for bus class. | pass_through_tracker | N/A |
pedestrian_tracker | string | Tracker model for pedestrian class. | pass_through_tracker | N/A |
bicycle_tracker | string | Tracker model for bicycle class. | pass_through_tracker | N/A |
motorcycle_tracker | string | Tracker model for motorcycle class. | pass_through_tracker | N/A |
Assumptions / Known limits#
See the model explanations.
Performance Benchmark & Unit Testing#
Overview#
Unit tests and benchmarks are included to evaluate tracker performance under varying detection loads and object types.
How to Run Locally#
1. Build with Tests#
colcon build --packages-select autoware_multi_object_tracker \
--cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo
2. Run the Performance Benchmark#
source install/setup.bash
./build/autoware_multi_object_tracker/test_multi_object_tracker
This runs the default test (runPerformanceTest
) and outputs timing data.
3. Enable Optional Profiling Modes (Manual)#
To evaluate scalability with object count:
- Manually enable the following functions in the test source:
profilePerformanceVsCarCount()
profilePerformanceVsPedestrianCount()
These run additional profiling scenarios.
Rosbag Replay & Visualization#
Simulated Rosbag Output#
To record benchmark results for visualization in RViz:
- Enable
write_bag = true
inrunIterations()
- Run the test; the output
.db3
path is printed - Visualize:
ros2 bag play <output_file>.db3
rviz2 -d <your_rviz_config>.rviz
Real Rosbag Input#
- Set the path in
runPerformanceTestWithRosbag()
to a real.db3
file - Run the test
- Visualize the tracking result in RViz
(Optional) Error detection and handling#
(Optional) Performance characterization#
Evaluation of muSSP#
According to our evaluation, muSSP is faster than normal SSP when the matrix size is more than 100.
Execution time for varying matrix size at 95% sparsity. In real data, the sparsity was often around 95%.
Execution time for varying the sparsity with matrix size 100.
(Optional) References/External links#
This package makes use of external code.
Name | License | Original Repository |
---|---|---|
muSSP | Apache-2.0 | https://github.com/yu-lab-vt/muSSP |
[1] C. Wang, Y. Wang, Y. Wang, C.-t. Wu, and G. Yu, "muSSP: Efficient Min-cost Flow Algorithm for Multi-object Tracking," NeurIPS, 2019