Class to create configuration parameters for data association.
More...
#include <detected_object_associator.hpp>
Class to create configuration parameters for data association.
◆ DataAssociationConfig()
autoware::perception::tracking::DataAssociationConfig::DataAssociationConfig |
( |
const float32_t |
max_distance, |
|
|
const float32_t |
max_area_ratio, |
|
|
const bool |
consider_edge_for_big_detections |
|
) |
| |
Constructor.
- Parameters
-
max_distance | Max distance between a track and detection beyond which they wont be considered for association with each other |
max_area_ratio | Max ratio between a track and detection area beyond which they wont be considered for association with each other |
consider_edge_for_big_detections | When true, the shortest edge of the detection will be used as the max distance threshold if it is greater than the configured threshold |
◆ consider_edge_for_big_detections()
bool autoware::perception::tracking::DataAssociationConfig::consider_edge_for_big_detections |
( |
| ) |
const |
|
inline |
◆ get_max_area_ratio()
float32_t autoware::perception::tracking::DataAssociationConfig::get_max_area_ratio |
( |
| ) |
const |
|
inline |
◆ get_max_area_ratio_inv()
float32_t autoware::perception::tracking::DataAssociationConfig::get_max_area_ratio_inv |
( |
| ) |
const |
|
inline |
◆ get_max_distance()
float32_t autoware::perception::tracking::DataAssociationConfig::get_max_distance |
( |
| ) |
const |
|
inline |
◆ get_max_distance_squared()
float32_t autoware::perception::tracking::DataAssociationConfig::get_max_distance_squared |
( |
| ) |
const |
|
inline |
The documentation for this class was generated from the following files: