Autoware.Auto
|
|
A class for multi-object tracking. More...
#include <multi_object_tracker.hpp>
Public Member Functions | |
MultiObjectTracker (MultiObjectTrackerOptions options, TrackCreatorT track_creator, const tf2::BufferCore &tf2_buffer) | |
Constructor. More... | |
DetectedObjectsUpdateResult | update (const DetectedObjectsMsg &detections, const nav_msgs::msg::Odometry &detection_frame_odometry) |
Update the tracks with the specified detections and return the tracks at the current timestamp. More... | |
DetectedObjectsUpdateResult | update (const ClustersMsg &incoming_clusters, const nav_msgs::msg::Odometry &detection_frame_odometry) |
Update the tracks from incoming clusters. More... | |
void | update (const ClassifiedRoiArrayMsg &rois) |
Update the tracks with the specified detections. More... | |
void TRACKING_PUBLIC | update (const ClassifiedRoiArrayMsg &) |
Related Functions | |
(Note that these are not member functions.) | |
template<class TrackCreatorT > | |
DetectedObjectsUpdateResult | update (const DetectedObjects &detections, const nav_msgs::msg::Odometry &detection_frame_odometry) |
A class for multi-object tracking.
|
explicit |
Constructor.
void TRACKING_PUBLIC autoware::perception::tracking::MultiObjectTracker< TrackCreator< LidarOnlyPolicy > >::update | ( | const ClassifiedRoiArrayMsg & | ) |
void autoware::perception::tracking::MultiObjectTracker< TrackCreatorT >::update | ( | const ClassifiedRoiArrayMsg & | rois | ) |
Update the tracks with the specified detections.
[in] | rois | An array of vision detections. |
DetectedObjectsUpdateResult autoware::perception::tracking::MultiObjectTracker< TrackCreatorT >::update | ( | const ClustersMsg & | incoming_clusters, |
const nav_msgs::msg::Odometry & | detection_frame_odometry | ||
) |
Update the tracks from incoming clusters.
[in] | incoming_clusters | The incoming clusters |
[in] | detection_frame_odometry | An odometry message for the clusters frame in the tracking frame, which is defined in MultiObjectTrackerOptions. |
DetectedObjectsUpdateResult autoware::perception::tracking::MultiObjectTracker< TrackCreatorT >::update | ( | const DetectedObjectsMsg & | detections, |
const nav_msgs::msg::Odometry & | detection_frame_odometry | ||
) |
Update the tracks with the specified detections and return the tracks at the current timestamp.
[in] | detections | An array of detections. |
[in] | detection_frame_odometry | An odometry message for the detection frame in the tracking frame, which is defined in MultiObjectTrackerOptions. |
|
related |