Public Member Functions | Private Attributes | List of all members
tuw::KalmanFilterLinOrd1< NumType, XDim, UDim, ParamType > Class Template Reference

Partial implementation of KalmanFilterPredictInterface for 1st order multivariate (linear) integrator systems. The state variables are expected to be ordered in a 2 * XDim vector where the first XDim variables are the order 0 states and the 2nd XDim variables are their corresponding derivatives. More...

#include <kalman_filter_linear_ord1.hpp>

Inheritance diagram for tuw::KalmanFilterLinOrd1< NumType, XDim, UDim, ParamType >:
Inheritance graph
[legend]

Public Member Functions

void computef (const Eigen::Matrix< NumType, UDim, 1 > &_u) override
 Interface for computation of the state transition function vector f_. More...
 
void computePhi () override
 Interface for computation of the state transition matrix Phi_. More...
 
void computeQ () override
 Interface for computation of the state process noise matrix Q_. More...
 
virtual void computeSigmaInit () override
 Interface for initialization of the state covariance matrix Sigma_. More...
 
 KalmanFilterLinOrd1 (ParamType &_params)
 
virtual void precompute (const double &_Ta) override
 Interface for precomputation function called at the beginning of the prediction step. More...
 
void setNN (const size_t &_i, const double &_val)
 Sets a noise variance parameter. More...
 
- Public Member Functions inherited from tuw::KalmanFilterPredictInterface< NumType, 2 *XDim, UDim, ParamType >
void init (const Eigen::Matrix< NumType, XDim, 1 > &_x0)
 Initializes the state vector and triggers initialization of Sigma_. More...
 
 KalmanFilterPredictInterface (ParamType &_params)
 
 KalmanFilterPredictInterface (const KalmanFilterPredictInterface &)=default
 
 KalmanFilterPredictInterface (KalmanFilterPredictInterface &&)=default
 
KalmanFilterPredictInterfaceoperator= (const KalmanFilterPredictInterface &)=default
 
KalmanFilterPredictInterfaceoperator= (KalmanFilterPredictInterface &&)=default
 
const ParamType & param () const
 Parameters const acces. More...
 
void predict (const Eigen::Matrix< NumType, UDim, 1 > &_u, const double &_Ta)
 Performs the prediction step. More...
 
void predict (const Eigen::Matrix< NumType, UDim, 1 > &_u, const double &_Ta)
 Performs the prediction step with resizing. More...
 
void predict (const double &_Ta)
 
virtual ~KalmanFilterPredictInterface ()=default
 
- Public Member Functions inherited from tuw::KalmanFilter< NumType, XDim >
void init (const Eigen::Matrix< NumType, XDim, 1 > &_x0, const Eigen::Matrix< NumType, XDim, XDim > &_Sigma0)
 Initializes state and covariance of filter. More...
 
 KalmanFilter ()=default
 
 KalmanFilter (const KalmanFilter &)=default
 
 KalmanFilter (KalmanFilter &&)=default
 
KalmanFilteroperator= (const KalmanFilter &)=default
 
KalmanFilteroperator= (KalmanFilter &&)=default
 
void predict (const Eigen::Matrix< NumType, XDim, 1 > &_f, const Eigen::Matrix< NumType, XDim, XDim > &_Phi, const Eigen::Matrix< NumType, XDim, XDim > &_Q)
 Preforms Kalman prediction step. More...
 
const Eigen::Matrix< NumType, XDim, XDim > & Sigma () const
 State covariance matrix const access. More...
 
template<int UpdateDim>
void update (const Eigen::Matrix< NumType, UpdateDim, 1 > &_deltah, const Eigen::Matrix< NumType, UpdateDim, XDim > &_C, const Eigen::Matrix< NumType, UpdateDim, UpdateDim > &_R)
 Preforms Kalman update step. More...
 
const Eigen::Matrix< NumType, XDim, 1 > & x () const
 State vector const access. More...
 
virtual ~KalmanFilter ()=default
 

Private Attributes

Eigen::Matrix< NumType, XDim, 1 > nn_
 container storing state noise variance values. More...
 
bool recalculate_
 
bool recalculateQ_
 
double Ta_
 
double TaCub_
 
double TaSqr_
 

Additional Inherited Members

- Public Types inherited from tuw::KalmanFilterPredictInterface< NumType, 2 *XDim, UDim, ParamType >
using ParamsType = ParamType
 Parameter type. More...
 
- Public Types inherited from tuw::KalmanFilter< NumType, XDim >
using NumericalType = NumType
 Numerical type. More...
 
- Static Public Attributes inherited from tuw::KalmanFilter< NumType, XDim >
static constexpr const int xDim = XDim
 State vector size More...
 
- Protected Attributes inherited from tuw::KalmanFilterPredictInterface< NumType, 2 *XDim, UDim, ParamType >
Eigen::Matrix< NumType, XDim, 1 > f_
 State transition function vector More...
 
ParamType & params_
 Filter parameters. More...
 
Eigen::Matrix< NumType, XDim, XDim > Phi_
 
Eigen::Matrix< NumType, XDim, XDim > Q_
 to the state variables More...
 
- Protected Attributes inherited from tuw::KalmanFilter< NumType, XDim >
Eigen::Matrix< NumType, XDim, XDim > Sigma_
 State covariance matrix More...
 
Eigen::Matrix< NumType, XDim, 1 > x_
 State vector More...
 

Detailed Description

template<typename NumType, size_t XDim, size_t UDim, typename ParamType>
class tuw::KalmanFilterLinOrd1< NumType, XDim, UDim, ParamType >

Partial implementation of KalmanFilterPredictInterface for 1st order multivariate (linear) integrator systems. The state variables are expected to be ordered in a 2 * XDim vector where the first XDim variables are the order 0 states and the 2nd XDim variables are their corresponding derivatives.

Definition at line 46 of file kalman_filter_linear_ord1.hpp.

Constructor & Destructor Documentation

template<typename NumType , size_t XDim, size_t UDim, typename ParamType >
tuw::KalmanFilterLinOrd1< NumType, XDim, UDim, ParamType >::KalmanFilterLinOrd1 ( ParamType &  _params)
inline

Definition at line 49 of file kalman_filter_linear_ord1.hpp.

Member Function Documentation

template<typename NumType , size_t XDim, size_t UDim, typename ParamType >
void tuw::KalmanFilterLinOrd1< NumType, XDim, UDim, ParamType >::computef ( const Eigen::Matrix< NumType, UDim, 1 > &  _u)
inlineoverridevirtual

Interface for computation of the state transition function vector f_.

Implements tuw::KalmanFilterPredictInterface< NumType, 2 *XDim, UDim, ParamType >.

Definition at line 101 of file kalman_filter_linear_ord1.hpp.

template<typename NumType , size_t XDim, size_t UDim, typename ParamType >
void tuw::KalmanFilterLinOrd1< NumType, XDim, UDim, ParamType >::computePhi ( )
inlineoverridevirtual

Interface for computation of the state transition matrix Phi_.

Implements tuw::KalmanFilterPredictInterface< NumType, 2 *XDim, UDim, ParamType >.

Definition at line 89 of file kalman_filter_linear_ord1.hpp.

template<typename NumType , size_t XDim, size_t UDim, typename ParamType >
void tuw::KalmanFilterLinOrd1< NumType, XDim, UDim, ParamType >::computeQ ( )
inlineoverridevirtual

Interface for computation of the state process noise matrix Q_.

Implements tuw::KalmanFilterPredictInterface< NumType, 2 *XDim, UDim, ParamType >.

Definition at line 111 of file kalman_filter_linear_ord1.hpp.

template<typename NumType , size_t XDim, size_t UDim, typename ParamType >
virtual void tuw::KalmanFilterLinOrd1< NumType, XDim, UDim, ParamType >::computeSigmaInit ( )
inlineoverridevirtual

Interface for initialization of the state covariance matrix Sigma_.

Implements tuw::KalmanFilterPredictInterface< NumType, 2 *XDim, UDim, ParamType >.

Definition at line 64 of file kalman_filter_linear_ord1.hpp.

template<typename NumType , size_t XDim, size_t UDim, typename ParamType >
virtual void tuw::KalmanFilterLinOrd1< NumType, XDim, UDim, ParamType >::precompute ( const double &  _Ta)
inlineoverridevirtual

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

Implements tuw::KalmanFilterPredictInterface< NumType, 2 *XDim, UDim, ParamType >.

Definition at line 73 of file kalman_filter_linear_ord1.hpp.

template<typename NumType , size_t XDim, size_t UDim, typename ParamType >
void tuw::KalmanFilterLinOrd1< NumType, XDim, UDim, ParamType >::setNN ( const size_t &  _i,
const double &  _val 
)
inline

Sets a noise variance parameter.

Parameters
_iIndex of the state correspoing variance
_valVariance value

Definition at line 129 of file kalman_filter_linear_ord1.hpp.

Member Data Documentation

template<typename NumType , size_t XDim, size_t UDim, typename ParamType >
Eigen::Matrix<NumType, XDim, 1> tuw::KalmanFilterLinOrd1< NumType, XDim, UDim, ParamType >::nn_
private

container storing state noise variance values.

Definition at line 136 of file kalman_filter_linear_ord1.hpp.

template<typename NumType , size_t XDim, size_t UDim, typename ParamType >
bool tuw::KalmanFilterLinOrd1< NumType, XDim, UDim, ParamType >::recalculate_
private

Definition at line 141 of file kalman_filter_linear_ord1.hpp.

template<typename NumType , size_t XDim, size_t UDim, typename ParamType >
bool tuw::KalmanFilterLinOrd1< NumType, XDim, UDim, ParamType >::recalculateQ_
private

Definition at line 144 of file kalman_filter_linear_ord1.hpp.

template<typename NumType , size_t XDim, size_t UDim, typename ParamType >
double tuw::KalmanFilterLinOrd1< NumType, XDim, UDim, ParamType >::Ta_
private

Definition at line 138 of file kalman_filter_linear_ord1.hpp.

template<typename NumType , size_t XDim, size_t UDim, typename ParamType >
double tuw::KalmanFilterLinOrd1< NumType, XDim, UDim, ParamType >::TaCub_
private

Definition at line 138 of file kalman_filter_linear_ord1.hpp.

template<typename NumType , size_t XDim, size_t UDim, typename ParamType >
double tuw::KalmanFilterLinOrd1< NumType, XDim, UDim, ParamType >::TaSqr_
private

Definition at line 138 of file kalman_filter_linear_ord1.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