Public Member Functions | Private Attributes | List of all members
tuw::KalmanFilterInterface< KFPredType, KFUpdateType > Class Template Reference

Interface for simplified manipulation of specialized (Extended) Kalman Filter implementations. More...

#include <kalman_filter.hpp>

Inheritance diagram for tuw::KalmanFilterInterface< KFPredType, KFUpdateType >:
Inheritance graph
[legend]

Public Member Functions

 KalmanFilterInterface (typename KFPredType::ParamsType &_params)
 
 KalmanFilterInterface (const KalmanFilterInterface &)=default
 
 KalmanFilterInterface (KalmanFilterInterface &&)=default
 
KalmanFilterInterfaceoperator= (const KalmanFilterInterface &)=default
 
KalmanFilterInterfaceoperator= (KalmanFilterInterface &&)=default
 
template<typename KFUpdateTypeI = typename std::tuple_element<0, std::tuple<KFUpdateType...>>::type, int i = KFUpdateTypeI::hDim, typename std::enable_if<(i > = 0>
void update (const Eigen::Matrix< typename KFPredType::NumericalType, KFUpdateTypeI::hDim, 1 > &_zObs)
 Performs the update step defined by the template argument KFUpdateTypeI (defaults to first updater class). More...
 
template<typename KFUpdateTypeI = typename std::tuple_element<0, std::tuple<KFUpdateType...>>::type, int i = KFUpdateTypeI::hDim, typename std::enable_if<(i==-1)>::type * = nullptr>
void update (const Eigen::Matrix< typename KFPredType::NumericalType, KFUpdateTypeI::hDim, 1 > &_zObs)
 Performs the update step by the template argument KFUpdateTypeI (defaults to first updater class) with resizing. More...
 
virtual ~KalmanFilterInterface ()=default
 

Private Attributes

std::tuple< KFUpdateType... > updaters_
 Container. More...
 

Detailed Description

template<typename KFPredType, typename... KFUpdateType>
class tuw::KalmanFilterInterface< KFPredType, KFUpdateType >

Interface for simplified manipulation of specialized (Extended) Kalman Filter implementations.

Template Parameters
KFPredTypeKalman prediction class (extended from KalmanFilterPredictInterface)
KFUpdateTypeParameter pack of implemented KalmanFilterUpdateInterface classes that are used to update the filter As building blocks, a KalmanFilterPredictInterface and multilple KalmanFilterUpdateInterface have to be defined.

Definition at line 366 of file kalman_filter.hpp.

Constructor & Destructor Documentation

template<typename KFPredType , typename... KFUpdateType>
tuw::KalmanFilterInterface< KFPredType, KFUpdateType >::KalmanFilterInterface ( typename KFPredType::ParamsType &  _params)
inline

Definition at line 370 of file kalman_filter.hpp.

template<typename KFPredType , typename... KFUpdateType>
virtual tuw::KalmanFilterInterface< KFPredType, KFUpdateType >::~KalmanFilterInterface ( )
virtualdefault
template<typename KFPredType , typename... KFUpdateType>
tuw::KalmanFilterInterface< KFPredType, KFUpdateType >::KalmanFilterInterface ( const KalmanFilterInterface< KFPredType, KFUpdateType > &  )
default
template<typename KFPredType , typename... KFUpdateType>
tuw::KalmanFilterInterface< KFPredType, KFUpdateType >::KalmanFilterInterface ( KalmanFilterInterface< KFPredType, KFUpdateType > &&  )
default

Member Function Documentation

template<typename KFPredType , typename... KFUpdateType>
KalmanFilterInterface& tuw::KalmanFilterInterface< KFPredType, KFUpdateType >::operator= ( const KalmanFilterInterface< KFPredType, KFUpdateType > &  )
default
template<typename KFPredType , typename... KFUpdateType>
KalmanFilterInterface& tuw::KalmanFilterInterface< KFPredType, KFUpdateType >::operator= ( KalmanFilterInterface< KFPredType, KFUpdateType > &&  )
default
template<typename KFPredType , typename... KFUpdateType>
template<typename KFUpdateTypeI = typename std::tuple_element<0, std::tuple<KFUpdateType...>>::type, int i = KFUpdateTypeI::hDim, typename std::enable_if<(i > = 0>
void tuw::KalmanFilterInterface< KFPredType, KFUpdateType >::update ( const Eigen::Matrix< typename KFPredType::NumericalType, KFUpdateTypeI::hDim, 1 > &  _zObs)
inline

Performs the update step defined by the template argument KFUpdateTypeI (defaults to first updater class).

This function performs no resizing on the internal filter variables and is thus intended for external use only for compile-time constant filter state size.

The order in which the implementation-specific functions are called is: KalmanFilterUpdateInterface::precompute, KalmanFilterUpdateInterface::computeH, KalmanFilterUpdateInterface::computeh, KalmanFilterUpdateInterface::computeR. Note that computeH is called before KalmanFilterUpdateInterface::computeh and thus KalmanFilterUpdateInterface::H_ can be used in KalmanFilterUpdateInterface::computeh (for linear prediction models).

Parameters
_uInputs vector.
_TaTime duration since last prediction step.
See also
KalmanFilterUpdateInterface::precompute, KalmanFilterUpdateInterface::computeH, KalmanFilterUpdateInterface::computeh, KalmanFilterUpdateInterface::computeR

Definition at line 411 of file kalman_filter.hpp.

template<typename KFPredType , typename... KFUpdateType>
template<typename KFUpdateTypeI = typename std::tuple_element<0, std::tuple<KFUpdateType...>>::type, int i = KFUpdateTypeI::hDim, typename std::enable_if<(i==-1)>::type * = nullptr>
void tuw::KalmanFilterInterface< KFPredType, KFUpdateType >::update ( const Eigen::Matrix< typename KFPredType::NumericalType, KFUpdateTypeI::hDim, 1 > &  _zObs)
inline

Performs the update step by the template argument KFUpdateTypeI (defaults to first updater class) with resizing.

This function performs resizing on the internal filter variables and later calls its its static counterpart. It is intended for external use for dynamic filter measurement vector size.

For dynamic measurement vector size, KalmanFilterUpdateInterface::h_, KalmanFilterUpdateInterface::H_ and KalmanFilterUpdateInterface::R_ are being properly resized but their content is not initialized.

See also
update for constant measurement vector size

Definition at line 435 of file kalman_filter.hpp.

Member Data Documentation

template<typename KFPredType , typename... KFUpdateType>
std::tuple<KFUpdateType...> tuw::KalmanFilterInterface< KFPredType, KFUpdateType >::updaters_
private

Container.

Definition at line 445 of file kalman_filter.hpp.


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


tuw_control
Author(s): George Todoran
autogenerated on Mon Jun 10 2019 15:27:23