Autoware.Auto
autoware::perception::tracking::GenericClassificationTracker< ClassificationStateT > Class Template Reference

A class for tracking classification information that works on any set of variables. More...

#include <classification_tracker.hpp>

Public Member Functions

 GenericClassificationTracker ()=default
 Default constructor. More...
 
 GenericClassificationTracker (const autoware::common::types::float32_t default_observation_covariance, const autoware::common::types::float32_t initial_state_covariance)
 Allow specifying a custom observation covariance. More...
 
void update (const autoware_auto_perception_msgs::msg::DetectedObject::_classification_type &classification_vector)
 Update the class probabilities given a classification update. More...
 
void update (const autoware_auto_perception_msgs::msg::DetectedObject::_classification_type &classification_vector, const common::types::float32_t observation_covariance)
 Update the class probabilities given a classification update. More...
 
std::uint8_t most_likely_class () const
 Gets the most likely class from the current state vector. More...
 
autoware_auto_perception_msgs::msg::DetectedObject::_classification_type object_classification_vector () const
 Gets the object classification vector to be set directly into the DetectedObject message. More...
 
const ClassificationStateT & state () const noexcept
 Expose the underlying state for utility purposes. More...
 
autoware::common::types::float32_t default_observation_covariance () const noexcept
 Expose the observation covariance. More...
 

Detailed Description

template<typename ClassificationStateT>
class autoware::perception::tracking::GenericClassificationTracker< ClassificationStateT >

A class for tracking classification information that works on any set of variables.

Under the hood, this class uses the autoware::common::state_estimation::KalmanFilter class with a special state vector containing all the relevant classes that we aim to track. The state vector directly holds the probabilities in its values. If the observation covariance for any particular observation is the same for all observed classes, then the underlying vector is guaranteed to represent probabilities that always sum up to 1.

Template Parameters
ClassificationStateTA state that defines all classes that can be tracked.

Constructor & Destructor Documentation

◆ GenericClassificationTracker() [1/2]

template<typename ClassificationStateT >
autoware::perception::tracking::GenericClassificationTracker< ClassificationStateT >::GenericClassificationTracker ( )
default

Default constructor.

◆ GenericClassificationTracker() [2/2]

template<typename ClassificationStateT >
autoware::perception::tracking::GenericClassificationTracker< ClassificationStateT >::GenericClassificationTracker ( const autoware::common::types::float32_t  default_observation_covariance,
const autoware::common::types::float32_t  initial_state_covariance 
)
inlineexplicit

Allow specifying a custom observation covariance.

Member Function Documentation

◆ default_observation_covariance()

template<typename ClassificationStateT >
autoware::common::types::float32_t autoware::perception::tracking::GenericClassificationTracker< ClassificationStateT >::default_observation_covariance ( ) const
inlinenoexcept

Expose the observation covariance.

◆ most_likely_class()

template<typename ClassificationStateT >
std::uint8_t autoware::perception::tracking::GenericClassificationTracker< ClassificationStateT >::most_likely_class ( ) const
inline

Gets the most likely class from the current state vector.

Returns
The most likely classification value.

◆ object_classification_vector()

template<typename ClassificationStateT >
autoware_auto_perception_msgs::msg::DetectedObject::_classification_type autoware::perception::tracking::GenericClassificationTracker< ClassificationStateT >::object_classification_vector ( ) const
inline

Gets the object classification vector to be set directly into the DetectedObject message.

Returns
The object classification vector.

◆ state()

template<typename ClassificationStateT >
const ClassificationStateT& autoware::perception::tracking::GenericClassificationTracker< ClassificationStateT >::state ( ) const
inlinenoexcept

Expose the underlying state for utility purposes.

◆ update() [1/2]

template<typename ClassificationStateT >
void autoware::perception::tracking::GenericClassificationTracker< ClassificationStateT >::update ( const autoware_auto_perception_msgs::msg::DetectedObject::_classification_type &  classification_vector)
inline

Update the class probabilities given a classification update.

Note
If the probabilities in the classification vector add up to a number less than 1, all the "missing" probability mass will be assigned to the UNKNOWN state. If the sum is above 1 an exception std::domain_error will be thrown instead.
Parameters
[in]classification_vectorA vector of classifications with their probabilities.

◆ update() [2/2]

template<typename ClassificationStateT >
void autoware::perception::tracking::GenericClassificationTracker< ClassificationStateT >::update ( const autoware_auto_perception_msgs::msg::DetectedObject::_classification_type &  classification_vector,
const common::types::float32_t  observation_covariance 
)
inline

Update the class probabilities given a classification update.

Note
If the probabilities in the classification vector add up to a number less than 1, all the "missing" probability mass will be assigned to the UNKNOWN state. If the sum is above 1 an exception std::domain_error will be thrown instead.
Parameters
[in]classification_vectorA vector of classifications with their probabilities.
[in]observation_covarianceA custom observation covariance.

The documentation for this class was generated from the following file: