Autoware.Auto
autoware::common::state_estimation::UniformNoise< StateT > Class Template Reference

This class contains the logic for a uniform noise model. More...

#include <uniform_noise.hpp>

Inheritance diagram for autoware::common::state_estimation::UniformNoise< StateT >:
Collaboration diagram for autoware::common::state_estimation::UniformNoise< StateT >:

Public Types

using State = StateT
 A convenience typedef for the state for which this noise model is to be used. More...
 

Public Member Functions

 UniformNoise (const Matrix &covariance) noexcept
 Create the noise model from an existing covariance matrix. More...
 
template<typename OtherScalarT >
 UniformNoise (const std::array< OtherScalarT, State::size()> &variances) noexcept
 Create the noise model from an array. More...
 
template<typename OtherScalarT >
 UniformNoise (const std::vector< OtherScalarT > &variances)
 Create the noise model from a vector. More...
 
template<typename ... VarianceTs>
 UniformNoise (const Scalar variance, const VarianceTs ... variances)
 Create noise model from variances directly. More...
 
- Public Member Functions inherited from autoware::common::state_estimation::NoiseInterface< Derived >
auto covariance (const std::chrono::nanoseconds &dt) const
 Get a covariance matrix for this noise model. More...
 

Protected Member Functions

Matrix crtp_covariance (const std::chrono::nanoseconds &dt) const noexcept
 A CRTP-called covariance getter. More...
 

Protected Attributes

friend NoiseInterface< UniformNoise< StateT > >
 

Detailed Description

template<typename StateT>
class autoware::common::state_estimation::UniformNoise< StateT >

This class contains the logic for a uniform noise model.

Template Parameters
StateTState vector type for which this noise model is created.

Member Typedef Documentation

◆ State

template<typename StateT >
using autoware::common::state_estimation::UniformNoise< StateT >::State = StateT

A convenience typedef for the state for which this noise model is to be used.

Constructor & Destructor Documentation

◆ UniformNoise() [1/4]

template<typename StateT >
autoware::common::state_estimation::UniformNoise< StateT >::UniformNoise ( const Matrix &  covariance)
inlineexplicitnoexcept

Create the noise model from an existing covariance matrix.

Parameters
[in]covarianceThe covariance

◆ UniformNoise() [2/4]

template<typename StateT >
template<typename OtherScalarT >
autoware::common::state_estimation::UniformNoise< StateT >::UniformNoise ( const std::array< OtherScalarT, State::size()> &  variances)
inlineexplicitnoexcept

Create the noise model from an array.

Parameters
[in]variancesThe values for variances, i.e., values for σ (not squared)
Template Parameters
OtherScalarTSome scalar type.

◆ UniformNoise() [3/4]

template<typename StateT >
template<typename OtherScalarT >
autoware::common::state_estimation::UniformNoise< StateT >::UniformNoise ( const std::vector< OtherScalarT > &  variances)
inlineexplicit

Create the noise model from a vector.

Parameters
[in]variancesThe values for variances, i.e., values for σ (not squared)
Exceptions
std::runtime_errorif the vector is of a wrong size.
Template Parameters
OtherScalarTSome scalar type.

◆ UniformNoise() [4/4]

template<typename StateT >
template<typename ... VarianceTs>
autoware::common::state_estimation::UniformNoise< StateT >::UniformNoise ( const Scalar  variance,
const VarianceTs ...  variances 
)
inlineexplicit

Create noise model from variances directly.

Parameters
[in]varianceThe first variance, i.e., value for σ (not squared)
[in]variancesThe variances for all the other variables
Template Parameters
VarianceTsTypes for other variances.

Member Function Documentation

◆ crtp_covariance()

template<typename StateT >
Matrix autoware::common::state_estimation::UniformNoise< StateT >::crtp_covariance ( const std::chrono::nanoseconds &  dt) const
inlineprotectednoexcept

A CRTP-called covariance getter.

Returns
A covariance of the noise process over a given time span.

Member Data Documentation

◆ NoiseInterface< UniformNoise< StateT > >

template<typename StateT >
friend autoware::common::state_estimation::UniformNoise< StateT >::NoiseInterface< UniformNoise< StateT > >
protected

Allow the interface to access the protected and private members to visually encapsulate the implementation.


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