mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
mrs_lib::KalmanFilter< n_states, n_inputs, n_measurements > Class Template Referenceabstract

This abstract class defines common interfaces and types for a generic Kalman filter. More...

#include <kalman_filter.h>

+ Inheritance diagram for mrs_lib::KalmanFilter< n_states, n_inputs, n_measurements >:

Classes

struct  statecov_t
 Helper struct for passing around the state and its covariance in one variable. More...
 

Public Types

typedef Eigen::Matrix< double, n, 1 > x_t
 State vector type $n \times 1$.
 
typedef Eigen::Matrix< double, m, 1 > u_t
 Input vector type $m \times 1$.
 
typedef Eigen::Matrix< double, p, 1 > z_t
 Measurement vector type $p \times 1$.
 
typedef Eigen::Matrix< double, n, nP_t
 State uncertainty covariance matrix type $n \times n$.
 
typedef Eigen::Matrix< double, p, pR_t
 Measurement noise covariance matrix type $p \times p$.
 
typedef Eigen::Matrix< double, n, nQ_t
 Process noise covariance matrix type $n \times n$.
 

Public Member Functions

virtual statecov_t correct (const statecov_t &sc, const z_t &z, const R_t &R) const =0
 Applies the correction (update, measurement, data) step of the Kalman filter. More...
 
virtual statecov_t predict (const statecov_t &sc, const u_t &u, const Q_t &Q, double dt) const =0
 Applies the prediction (time) step of the Kalman filter. More...
 

Static Public Attributes

static const int n = n_states
 Length of the state vector of the system.
 
static const int m = n_inputs
 Length of the input vector of the system.
 
static const int p = n_measurements
 Length of the measurement vector of the system.
 

Detailed Description

template<int n_states, int n_inputs, int n_measurements>
class mrs_lib::KalmanFilter< n_states, n_inputs, n_measurements >

This abstract class defines common interfaces and types for a generic Kalman filter.

Template Parameters
n_statesnumber of states of the system (length of the $ \mathbf{x} $ vector).
n_inputsnumber of inputs of the system (length of the $ \mathbf{u} $ vector).
n_measurementsnumber of measurements of the system (length of the $ \mathbf{z} $ vector).

Member Function Documentation

◆ correct()

template<int n_states, int n_inputs, int n_measurements>
virtual statecov_t mrs_lib::KalmanFilter< n_states, n_inputs, n_measurements >::correct ( const statecov_t sc,
const z_t z,
const R_t R 
) const
pure virtual

Applies the correction (update, measurement, data) step of the Kalman filter.

This method applies the correction step to the state and covariance passed in sc using the measurement z and measurement noise R. An optional parameter param may be used by some implementations, but it is usually ignored. The updated state and covariance after the correction step is returned.

Parameters
scThe state and covariance to which the correction step is to be applied.
zThe measurement vector to be used for correction.
RThe measurement noise covariance matrix to be used for correction.
Returns
The state and covariance after the correction update.

◆ predict()

template<int n_states, int n_inputs, int n_measurements>
virtual statecov_t mrs_lib::KalmanFilter< n_states, n_inputs, n_measurements >::predict ( const statecov_t sc,
const u_t u,
const Q_t Q,
double  dt 
) const
pure virtual

Applies the prediction (time) step of the Kalman filter.

This method applies the prediction step to the state and covariance passed in sc using the input u and process noise Q. The state and covariance are updated by dt into the future, if applicable to the implementation. An optional parameter param may be used by some implementations, but it is usually ignored. The updated state and covariance after the prediction step is returned.

Parameters
scThe state and covariance to which the prediction step is to be applied.
uThe input vector to be used for prediction.
QThe process noise covariance matrix to be used for prediction.
dtThe time step for the prediction update (the state and covariance will be predicted by dt into the future).
Returns
The state and covariance after the prediction step.

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