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

This class implements the norm-constrained linear Kalman filter [5]. More...

#include <nckf.h>

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

Public Types

using Base_class = LKF< n, m, p >
 Base class of this class.
 
using x_t = typename Base_class::x_t
 State vector type $n \times 1$.
 
using u_t = typename Base_class::u_t
 Input vector type $m \times 1$.
 
using z_t = typename Base_class::z_t
 Measurement vector type $p \times 1$.
 
using P_t = typename Base_class::P_t
 State uncertainty covariance matrix type $n \times n$.
 
using R_t = typename Base_class::R_t
 Measurement noise covariance matrix type $p \times p$.
 
using Q_t = typename Base_class::Q_t
 Process noise covariance matrix type $n \times n$.
 
using statecov_t = typename Base_class::statecov_t
 Helper struct for passing around the state and its covariance in one variable.
 
using A_t = typename Base_class::A_t
 System transition matrix type $n \times n$.
 
using B_t = typename Base_class::B_t
 Input to state mapping matrix type $n \times m$.
 
using H_t = typename Base_class::H_t
 State to measurement mapping matrix type $p \times n$.
 
using K_t = typename Base_class::K_t
 Kalman gain matrix type $n \times p$.
 
- Public Types inherited from mrs_lib::LKF< n_states, n_inputs, n_measurements >
using Base_class = KalmanFilter< n, m, p >
 Base class of this class.
 
using x_t = typename Base_class::x_t
 State vector type $n \times 1$.
 
using u_t = typename Base_class::u_t
 Input vector type $m \times 1$.
 
using z_t = typename Base_class::z_t
 Measurement vector type $p \times 1$.
 
using P_t = typename Base_class::P_t
 State uncertainty covariance matrix type $n \times n$.
 
using R_t = typename Base_class::R_t
 Measurement noise covariance matrix type $p \times p$.
 
using Q_t = typename Base_class::Q_t
 Process noise covariance matrix type $n \times n$.
 
using statecov_t = typename Base_class::statecov_t
 Helper struct for passing around the state and its covariance in one variable.
 
typedef Eigen::Matrix< double, n, nA_t
 System transition matrix type $n \times n$.
 
typedef Eigen::Matrix< double, n, mB_t
 Input to state mapping matrix type $n \times m$.
 
typedef Eigen::Matrix< double, p, nH_t
 State to measurement mapping matrix type $p \times n$.
 
typedef Eigen::Matrix< double, n, pK_t
 Kalman gain matrix type $n \times p$.
 
- Public Types inherited from mrs_lib::KalmanFilter< n_states, n_inputs, n_measurements >
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

 NCLKF ()
 Convenience default constructor. More...
 
 NCLKF (const A_t &A, const B_t &B, const H_t &H, const double l)
 The main constructor. More...
 
- Public Member Functions inherited from mrs_lib::LKF< n_states, n_inputs, n_measurements >
 LKF ()
 Convenience default constructor. More...
 
 LKF (const A_t &A, const B_t &B, const H_t &H)
 The main constructor. More...
 
virtual statecov_t correct (const statecov_t &sc, const z_t &z, const R_t &R) const override
 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, [[maybe_unused]] double dt) const override
 Applies the prediction (time) step of the Kalman filter. More...
 
- Public Member Functions inherited from mrs_lib::KalmanFilter< n_states, n_inputs, n_measurements >
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.
 
- Static Public Attributes inherited from mrs_lib::LKF< n_states, n_inputs, n_measurements >
static constexpr int n = n_states
 Length of the state vector of the system.
 
static constexpr int m = n_inputs
 Length of the input vector of the system.
 
static constexpr int p = n_measurements
 Length of the measurement vector of the system.
 
- Static Public Attributes inherited from mrs_lib::KalmanFilter< n_states, n_inputs, n_measurements >
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.
 

Protected Member Functions

virtual K_t computeKalmanGain (const statecov_t &sc, const z_t &z, const R_t &R, const H_t &H) const override
 
- Protected Member Functions inherited from mrs_lib::LKF< n_states, n_inputs, n_measurements >
virtual K_t computeKalmanGain (const statecov_t &sc, [[maybe_unused]] const z_t &z, const R_t &R, const H_t &H) const
 
statecov_t ::type correction_impl (const statecov_t &sc, const z_t &z, const R_t &R, const H_t &H) const
 

Protected Attributes

double l
 

Additional Inherited Members

- Public Attributes inherited from mrs_lib::LKF< n_states, n_inputs, n_measurements >
A_t A
 The system transition matrix $n \times n$.
 
B_t B
 The input to state mapping matrix $n \times m$.
 
H_t H
 The state to measurement mapping matrix $p \times n$.
 
- Static Protected Member Functions inherited from mrs_lib::LKF< n_states, n_inputs, n_measurements >
static P_t covariance_predict (const A_t &A, const P_t &P, const Q_t &Q, const double dt)
 
template<int check = n_inputs>
static std::enable_if< check==0, x_t >::type state_predict (const A_t &A, const x_t &x, [[maybe_unused]] const B_t &B, [[maybe_unused]] const u_t &u)
 
template<int check = n_inputs>
static std::enable_if< check !=0, x_t >::type state_predict (const A_t &A, const x_t &x, const B_t &B, const u_t &u)
 
static R_t invert_W (R_t W)
 

Detailed Description

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

This class implements the norm-constrained linear Kalman filter [5].

Note that the class is templated. The template parameters specify the number of states, number of inputs and number of measurements of the system. The last template parameter specifies the number of states which are norm-constrained.

The norm constraint is specified in the constructor and applied to the whole state vector of the system.

Constructor & Destructor Documentation

◆ NCLKF() [1/2]

template<int n_states, int n_inputs, int n_measurements>
mrs_lib::NCLKF< n_states, n_inputs, n_measurements >::NCLKF ( )
inline

Convenience default constructor.

This constructor should not be used if applicable. If used, the main constructor has to be called afterwards, before using this class, otherwise the object is invalid (not initialized).

◆ NCLKF() [2/2]

template<int n_states, int n_inputs, int n_measurements>
mrs_lib::NCLKF< n_states, n_inputs, n_measurements >::NCLKF ( const A_t A,
const B_t B,
const H_t H,
const double  l 
)
inline

The main constructor.

Parameters
AState transition matrix of the system (n x n).
BInput to state mapping matrix of the system (n x m).
HState to measurement mapping matrix of the system (p x n).
lThe norm constraint, applied to the specified states.

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