Go to the documentation of this file.
17 #ifndef TRACKING__TRACKER_TYPES_HPP_
18 #define TRACKING__TRACKER_TYPES_HPP_
23 #include <unordered_set>
42 static constexpr std::size_t UNASSIGNED = std::numeric_limits<std::size_t>::max();
67 #endif // TRACKING__TRACKER_TYPES_HPP_
constexpr uint16_t MAX_NUM_TRACKS
Maximum number of tracks possible in every timestep.
Definition: tracker_types.hpp:34
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
Struct to store results after the assignment is done.
Definition: tracker_types.hpp:40
constexpr uint16_t NUM_OBJ_POSE_DIM
Number of dimensions needed to represent object position for tracking (x and y)
Definition: tracker_types.hpp:37
bool had_errors
Indicates if there were errors in the data during association.
Definition: tracker_types.hpp:52
std::vector< std::size_t > track_assignments
This vector stores the detection index associated with each track idx. So, it should have Associator:...
Definition: tracker_types.hpp:46
std::unordered_set< std::size_t > unassigned_track_indices
Indices of tracks that are not associated to any detections.
Definition: tracker_types.hpp:50
@ LidarClusterIfVision
Create tracks from unassociated lidar clusters only if they have associated vision detections.
TrackCreationPolicy
Definition: tracker_types.hpp:55
@ LidarClusterOnly
Create tracks from every unassociated lidar cluster.
std::unordered_set< std::size_t > unassigned_detection_indices
Indices of detections that are not associated to any tracks.
Definition: tracker_types.hpp:48