Autoware.Auto
autoware::prediction::Measurement< T, kMeasurementModalities > Class Template Reference

#include <measurement.hpp>

Public Member Functions

 Measurement (const MeasurementBasedTime &acquisition_time, const MeasurementVector &values, const VarianceVector &variances={})
 
const MeasurementVector & get_values () const noexcept
 
const VarianceVector & get_variances () const noexcept
 
const MeasurementBasedTimeget_acquisition_time () const noexcept
 
template<std::int32_t kFullStateSize>
Vector< T, kFullStateSize > get_values_in_full_state (const Vector< T, kFullStateSize > &donor_state=Vector< T, kFullStateSize >::Zero()) const
 

Static Public Member Functions

template<std::int32_t kNumOfStates>
static MapMatrix< T, kNumOfStates > get_observation_to_state_mapping ()
 

Detailed Description

template<typename T, std::uint32_t... kMeasurementModalities>
class autoware::prediction::Measurement< T, kMeasurementModalities >

A class that wraps a measurement.

It can be used to create a measurement and produce valid values for:

  • Full state of the system generated from this measurement.
  • Mapping matrix to map measurement to the state.
  • Variances of this measurement.
Template Parameters
TType of measurement underlying type, e.g. float32_t
kMeasurementModalitiesWhich modalities does this measurement represent.

Constructor & Destructor Documentation

◆ Measurement()

template<typename T , std::uint32_t... kMeasurementModalities>
autoware::prediction::Measurement< T, kMeasurementModalities >::Measurement ( const MeasurementBasedTime acquisition_time,
const MeasurementVector &  values,
const VarianceVector &  variances = {} 
)
inlineexplicit

Create a measurement from the measured values and their variances.

Parameters
[in]acquisition_timeThe acquisition time for this measurement.
[in]valuesThe measured values.
[in]variancesThe variances of the measured values.

Member Function Documentation

◆ get_acquisition_time()

template<typename T , std::uint32_t... kMeasurementModalities>
const MeasurementBasedTime& autoware::prediction::Measurement< T, kMeasurementModalities >::get_acquisition_time ( ) const
inlinenoexcept

Get the time at which this measurement was acquired.

Returns
The acquisition time of the measurement.

◆ get_observation_to_state_mapping()

template<typename T , std::uint32_t... kMeasurementModalities>
template<std::int32_t kNumOfStates>
static MapMatrix<T, kNumOfStates> autoware::prediction::Measurement< T, kMeasurementModalities >::get_observation_to_state_mapping ( )
inlinestatic

Get a matrix that maps the observation to state given the state dimensionality.

Note
We can optimize this by allocating memory just once in the class static context, but this is left for the future if needed.
Template Parameters
kNumOfStatesNumber of states of the state vector.
Returns
The observation to state mapping matrix H such that: state = H * measurement.

◆ get_values()

template<typename T , std::uint32_t... kMeasurementModalities>
const MeasurementVector& autoware::prediction::Measurement< T, kMeasurementModalities >::get_values ( ) const
inlinenoexcept

Get stored measured values.

Returns
The values measured.

◆ get_values_in_full_state()

template<typename T , std::uint32_t... kMeasurementModalities>
template<std::int32_t kFullStateSize>
Vector<T, kFullStateSize> autoware::prediction::Measurement< T, kMeasurementModalities >::get_values_in_full_state ( const Vector< T, kFullStateSize > &  donor_state = Vector<T, kFullStateSize>::Zero()) const
inline

Get a full state vector populated by the values from this measurement.

Note that the ordering of these values depends on two factors:

  • which order of kMeasurementModalities is provided
  • integer values for measurement modalities in the enum.

It is assumed that state is ordered exactly as values in kMeasurementModalities, i.e., a measurement modality 0 is the first one in the state and so on..

Parameters
[in]donor_stateThe state that will be reused to set values missing in this measurement.
Template Parameters
kFullStateSizeThe dimentionality of the state.
Returns
The values from a measurement represented as a vector state dimentionality.

◆ get_variances()

template<typename T , std::uint32_t... kMeasurementModalities>
const VarianceVector& autoware::prediction::Measurement< T, kMeasurementModalities >::get_variances ( ) const
inlinenoexcept

Get stored variances.

Returns
Variances of this measurement as a vector of elements on the diagonal of R.

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