Skip to content

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.

multi_object_tracker_overview

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
selected_input_channels std::vector<std::string> array of channel names
  • default value: selected_input_channels:="['detected_objects']", merged DetectedObject message
  • multi-input example: selected_input_channels:="['lidar_centerpoint','camera_lidar_fusion','detection_by_tracker','radar_far']"

Output#

Name Type Description
~/output autoware_perception_msgs::msg::TrackedObjects tracked objects

Parameters#

Input Channel parameters#

Name Type Description Default Range
topic string The ROS topic name for the input channel. /perception/object_recognition/detection/objects N/A
can_spawn_new_tracker boolean Indicates if the input channel can spawn new trackers. 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#

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
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
publish_processing_time boolean Enable to publish debug message of 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
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, 1.0, 2.5, 10000.0, 10000.0, 10000.0, 10000.0, 2.5, 2.5, 1.0, 2.0, 10000.0, 10000.0, 10000.0, 10000.0, 1.5, 1.5, 1.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

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.

(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%. mussp_evaluation1

Execution time for varying the sparsity with matrix size 100. mussp_evaluation2

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

(Optional) Future extensions / Unimplemented parts#