mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
mrs_lib::JLKF< n_states, n_inputs, n_measurements, n_biases > Class Template Reference
+ Inheritance diagram for mrs_lib::JLKF< n_states, n_inputs, n_measurements, n_biases >:
+ Collaboration diagram for mrs_lib::JLKF< n_states, n_inputs, n_measurements, n_biases >:

Classes

struct  inverse_exception
 This exception is thrown when taking the inverse of a matrix fails. More...
 

Public Types

using Base_class = KalmanFilterAloamGarm< n, m, p >
 
using x_t = typename Base_class::x_t
 
using u_t = typename Base_class::u_t
 
using z_t = typename Base_class::z_t
 
using P_t = typename Base_class::P_t
 
using R_t = typename Base_class::R_t
 
using statecov_t = typename Base_class::statecov_t
 
using Q_t = typename Base_class::Q_t
 
typedef Eigen::Matrix< double, n, n > A_t
 System transition matrix type $n \times n$.
 
typedef Eigen::Matrix< double, n, m > B_t
 Input to state mapping matrix type $n \times m$.
 
typedef Eigen::Matrix< double, p, n > H_t
 State to measurement mapping matrix type $p \times n$.
 
typedef Eigen::Matrix< double, n, p > K_t
 Kalman gain matrix type $n \times p$.
 
typedef Eigen::Matrix< double, p, p > C_t
 correntropy gain $p \times p$
 
typedef Eigen::Matrix< double, n, n > D_t
 D $n \times n$.
 
using generateA_t = std::function< A_t(double)>
 
using generateB_t = std::function< B_t(double)>
 
- Public Types inherited from mrs_lib::KalmanFilterAloamGarm< 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

 JLKF (const generateA_t &generateA, const generateB_t &generateB, const H_t &H, const ros::NodeHandle &nh, const double &nis_thr, const double &nis_avg_thr)
 The main constructor. More...
 
virtual statecov_t predict (const statecov_t &sc, const u_t &u, const Q_t &Q, double dt) const override
 Applies the prediction (time) step of the Kalman filter. 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...
 
- Public Member Functions inherited from mrs_lib::KalmanFilterAloamGarm< 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
 
static const int m = n_inputs
 
static const int p = n_measurements
 
- Static Public Attributes inherited from mrs_lib::KalmanFilterAloamGarm< 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, [[maybe_unused]] const z_t &z, const R_t &R, const H_t &H, double &nis, H_t &H_out, const double &nis_thr, const double &nis_avg_thr) const
 
statecov_t ::type correction_impl (const statecov_t &sc, const z_t &z, const R_t &R, const H_t &H) const
 

Static Protected Member Functions

static R_t invert_W (R_t W)
 

Constructor & Destructor Documentation

◆ JLKF()

template<int n_states, int n_inputs, int n_measurements, int n_biases>
mrs_lib::JLKF< n_states, n_inputs, n_measurements, n_biases >::JLKF ( const generateA_t &  generateA,
const generateB_t &  generateB,
const H_t H,
const ros::NodeHandle &  nh,
const double &  nis_thr,
const double &  nis_avg_thr 
)
inline

The main constructor.

Parameters
generateAa function, which returns the state transition matrix A based on the time difference dt.
generateBa function, which returns the input to state mapping matrix B based on the time difference dt.
Hthe state to measurement mapping matrix.

Member Function Documentation

◆ correct()

template<int n_states, int n_inputs, int n_measurements, int n_biases>
virtual statecov_t mrs_lib::JLKF< n_states, n_inputs, n_measurements, n_biases >::correct ( const statecov_t &  sc,
const z_t &  z,
const R_t &  R 
) const
inlineoverridevirtual

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

This method applies the linear Kalman filter correction step to the state and covariance passed in sc using the measurement z and measurement noise R. 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, int n_biases>
virtual statecov_t mrs_lib::JLKF< n_states, n_inputs, n_measurements, n_biases >::predict ( const statecov_t &  sc,
const u_t &  u,
const Q_t &  Q,
double  dt 
) const
inlineoverridevirtual

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

This method applies the linear Kalman filter prediction step to the state and covariance passed in sc using the input u and process noise Q. The process noise covariance Q is scaled by the dt parameter. 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.
dtUsed to scale the process noise covariance Q and to generate the state transition and input to state mapping matrices A and \B using the functions, passed in the object's constructor.
Returns
The state and covariance after the prediction step.
Note
Note that the dt parameter is used to scale the process noise covariance Q and to generate the system matrices #A or #B using the functions, passed in the constructor!

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