Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes | Friends | List of all members
tuw::KalmanFilterUpdateInterface< KFPredType, HDim > Class Template Referenceabstract

Interface for simplified manipulation of specialized (Extended) Kalman Filter updates. To be used with KalmanFilterPredictInterface. More...

#include <kalman_filter.hpp>

Public Member Functions

const Eigen::Matrix< typename KFPredType::NumericalType, HDim, 1 > & deltah () const
 Const access of measurement function error vector h_. More...
 
const Eigen::Matrix< typename KFPredType::NumericalType, HDim, KFPredType::xDim > & H () const
 Const access of predicted measurement matrix H_. More...
 
 KalmanFilterUpdateInterface ()=default
 
 KalmanFilterUpdateInterface (const KalmanFilterUpdateInterface &)=default
 
 KalmanFilterUpdateInterface (KalmanFilterUpdateInterface &&)=default
 
KalmanFilterUpdateInterfaceoperator= (const KalmanFilterUpdateInterface &)=default
 
KalmanFilterUpdateInterfaceoperator= (KalmanFilterUpdateInterface &&)=default
 
const Eigen::Matrix< typename KFPredType::NumericalType, HDim, HDim > & R () const
 Const access of measurement noise matrix R_. More...
 
virtual ~KalmanFilterUpdateInterface ()=default
 

Static Public Attributes

static constexpr const int hDim = HDim
 Measurement vector size. More...
 

Protected Member Functions

virtual void computeDeltah (const KFPredType *_kf, const Eigen::Matrix< typename KFPredType::NumericalType, hDim, 1 > &_zObs)=0
 Interface for computation of the measurement function error vector deltah_. More...
 
virtual void computeH (const KFPredType *_kf)=0
 Interface for computation of the predicted measurement matrix H_. More...
 
virtual void computeR (const KFPredType *_kf)=0
 Interface for computation of the measurement noise matrix R_. More...
 
virtual void precompute (const KFPredType *_kf)=0
 measurement-space) More...
 

Protected Attributes

Eigen::Matrix< typename KFPredType::NumericalType, HDim, 1 > deltah_
 Measurement function error vector. More...
 
Eigen::Matrix< typename KFPredType::NumericalType, HDim, KFPredType::xDim > H_
 
Eigen::Matrix< typename KFPredType::NumericalType, HDim, HDim > R_
 

Friends

template<typename KFPredTypeI , typename... KFUpdateType>
class KalmanFilterInterface
 

Detailed Description

template<typename KFPredType, int HDim>
class tuw::KalmanFilterUpdateInterface< KFPredType, HDim >

Interface for simplified manipulation of specialized (Extended) Kalman Filter updates. To be used with KalmanFilterPredictInterface.

Template Parameters
KFPredTypeKalman prediction class (extended from KalmanFilterPredictInterface)
HDimDimension of the measurement vector. Value -1 relates to dynamic size measurement vector

Definition at line 287 of file kalman_filter.hpp.

Constructor & Destructor Documentation

template<typename KFPredType , int HDim>
tuw::KalmanFilterUpdateInterface< KFPredType, HDim >::KalmanFilterUpdateInterface ( )
default
template<typename KFPredType , int HDim>
virtual tuw::KalmanFilterUpdateInterface< KFPredType, HDim >::~KalmanFilterUpdateInterface ( )
virtualdefault
template<typename KFPredType , int HDim>
tuw::KalmanFilterUpdateInterface< KFPredType, HDim >::KalmanFilterUpdateInterface ( const KalmanFilterUpdateInterface< KFPredType, HDim > &  )
default
template<typename KFPredType , int HDim>
tuw::KalmanFilterUpdateInterface< KFPredType, HDim >::KalmanFilterUpdateInterface ( KalmanFilterUpdateInterface< KFPredType, HDim > &&  )
default

Member Function Documentation

template<typename KFPredType , int HDim>
virtual void tuw::KalmanFilterUpdateInterface< KFPredType, HDim >::computeDeltah ( const KFPredType *  _kf,
const Eigen::Matrix< typename KFPredType::NumericalType, hDim, 1 > &  _zObs 
)
protectedpure virtual

Interface for computation of the measurement function error vector deltah_.

template<typename KFPredType , int HDim>
virtual void tuw::KalmanFilterUpdateInterface< KFPredType, HDim >::computeH ( const KFPredType *  _kf)
protectedpure virtual

Interface for computation of the predicted measurement matrix H_.

template<typename KFPredType , int HDim>
virtual void tuw::KalmanFilterUpdateInterface< KFPredType, HDim >::computeR ( const KFPredType *  _kf)
protectedpure virtual

Interface for computation of the measurement noise matrix R_.

template<typename KFPredType , int HDim>
const Eigen::Matrix<typename KFPredType::NumericalType, HDim, 1>& tuw::KalmanFilterUpdateInterface< KFPredType, HDim >::deltah ( ) const
inline

Const access of measurement function error vector h_.

Definition at line 312 of file kalman_filter.hpp.

template<typename KFPredType , int HDim>
const Eigen::Matrix<typename KFPredType::NumericalType, HDim, KFPredType::xDim>& tuw::KalmanFilterUpdateInterface< KFPredType, HDim >::H ( ) const
inline

Const access of predicted measurement matrix H_.

Definition at line 317 of file kalman_filter.hpp.

template<typename KFPredType , int HDim>
KalmanFilterUpdateInterface& tuw::KalmanFilterUpdateInterface< KFPredType, HDim >::operator= ( const KalmanFilterUpdateInterface< KFPredType, HDim > &  )
default
template<typename KFPredType , int HDim>
KalmanFilterUpdateInterface& tuw::KalmanFilterUpdateInterface< KFPredType, HDim >::operator= ( KalmanFilterUpdateInterface< KFPredType, HDim > &&  )
default
template<typename KFPredType , int HDim>
virtual void tuw::KalmanFilterUpdateInterface< KFPredType, HDim >::precompute ( const KFPredType *  _kf)
protectedpure virtual

measurement-space)

Interface for precomputation function called at the beginning of the update step.

template<typename KFPredType , int HDim>
const Eigen::Matrix<typename KFPredType::NumericalType, HDim, HDim>& tuw::KalmanFilterUpdateInterface< KFPredType, HDim >::R ( ) const
inline

Const access of measurement noise matrix R_.

Definition at line 322 of file kalman_filter.hpp.

Friends And Related Function Documentation

template<typename KFPredType , int HDim>
template<typename KFPredTypeI , typename... KFUpdateType>
friend class KalmanFilterInterface
friend

Definition at line 352 of file kalman_filter.hpp.

Member Data Documentation

template<typename KFPredType , int HDim>
Eigen::Matrix<typename KFPredType::NumericalType, HDim, 1> tuw::KalmanFilterUpdateInterface< KFPredType, HDim >::deltah_
protected

Measurement function error vector.

Definition at line 328 of file kalman_filter.hpp.

template<typename KFPredType , int HDim>
Eigen::Matrix<typename KFPredType::NumericalType, HDim, KFPredType::xDim> tuw::KalmanFilterUpdateInterface< KFPredType, HDim >::H_
protected

Predicted measurement partial

Definition at line 330 of file kalman_filter.hpp.

template<typename KFPredType , int HDim>
constexpr const int tuw::KalmanFilterUpdateInterface< KFPredType, HDim >::hDim = HDim
static

Measurement vector size.

Definition at line 309 of file kalman_filter.hpp.

template<typename KFPredType , int HDim>
Eigen::Matrix<typename KFPredType::NumericalType, HDim, HDim> tuw::KalmanFilterUpdateInterface< KFPredType, HDim >::R_
protected

derivative (Jacobian) with respect to the state vector Measurement noise matrix (mapped in

Definition at line 334 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