|
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 .
|
|
typedef Eigen::Matrix< double, n, m > | B_t |
| Input to state mapping matrix type .
|
|
typedef Eigen::Matrix< double, p, n > | H_t |
| State to measurement mapping matrix type .
|
|
typedef Eigen::Matrix< double, n, p > | K_t |
| Kalman gain matrix type .
|
|
typedef Eigen::Matrix< double, p, p > | C_t |
| correntropy gain
|
|
typedef Eigen::Matrix< double, n, n > | D_t |
| D .
|
|
using | generateA_t = std::function< A_t(double)> |
|
using | generateB_t = std::function< B_t(double)> |
|
typedef Eigen::Matrix< double, n, 1 > | x_t |
| State vector type .
|
|
typedef Eigen::Matrix< double, m, 1 > | u_t |
| Input vector type .
|
|
typedef Eigen::Matrix< double, p, 1 > | z_t |
| Measurement vector type .
|
|
typedef Eigen::Matrix< double, n, n > | P_t |
| State uncertainty covariance matrix type .
|
|
typedef Eigen::Matrix< double, p, p > | R_t |
| Measurement noise covariance matrix type .
|
|
typedef Eigen::Matrix< double, n, n > | Q_t |
| Process noise covariance matrix type .
|
|
|
| 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...
|
|
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...
|
|
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
-
sc | The state and covariance to which the correction step is to be applied. |
z | The measurement vector to be used for correction. |
R | The measurement noise covariance matrix to be used for correction. |
- Returns
- The state and covariance after the correction update.
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
-
sc | The state and covariance to which the prediction step is to be applied. |
u | The input vector to be used for prediction. |
Q | The process noise covariance matrix to be used for prediction. |
dt | Used 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!