This abstract class defines common interfaces and types for a generic Kalman filter.
More...
#include <kalman_filter.h>
|
struct | statecov_t |
| Helper struct for passing around the state and its covariance in one variable. More...
|
|
|
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 .
|
|
|
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.
|
|
◆ correct()
template<int n_states, int n_inputs, int n_measurements>
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
-
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.
◆ predict()
template<int n_states, int n_inputs, int n_measurements>
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
-
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 | The 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: