|
| ExtendedKalmanFilter (const statefunc_t &stateFunc, const outputfunc_t &outputFunc, const statespace::NoiseCovMat< stateDim, processNoiseDim, inputDim > &processNoise, const statespace::NoiseCovMat< stateDim, outputNoiseDim, outputDim > &outputNoise, double dt) |
| Create a new discrete-time EKF.
|
|
void | predict (const Eigen::Matrix< double, inputDim, 1 > &input) override |
| Use the model to predict the next system state, given the current inputs.
|
|
void | correct (const Eigen::Matrix< double, outputDim, 1 > &measurement) |
| Correct the state estimate with measurement data.
|
|
void | reset () |
| Reset the filter.
|
|
void | reset (const Eigen::Matrix< double, stateDim, 1 > &state) |
| Reset the filter.
|
|
void | reset (const Eigen::Matrix< double, stateDim, 1 > &state, const Eigen::Matrix< double, stateDim, 1 > &stdDevs) |
| Reset the filter.
|
|
void | reset (const Eigen::Matrix< double, stateDim, 1 > &state, const Eigen::Matrix< double, stateDim, stateDim > &estCovMat) |
| Reset the filter.
|
|
Eigen::Matrix< double, stateDim, 1 > | getState () const |
| Gets the current state estimate.
|
|
Eigen::Matrix< double, stateDim, stateDim > | getEstimateCovarianceMat () const |
| Get the current estimate covariance matrix.
|
|
|
std::function< Eigen::Matrix< double, stateDim, stateDim >(const state_t &, const input_t &, const processnoise_t &)> | stateFuncJacobianX |
| Set this to provide an analytic solution to df/dx.
|
|
std::function< Eigen::Matrix< double, stateDim, processNoiseDim >(const state_t &, const input_t &, const processnoise_t &)> | stateFuncJacobianW |
| Set this to provide an analytic solution to df/dw.
|
|
std::function< Eigen::Matrix< double, outputDim, stateDim >(const state_t &, const outputnoise_t &)> | outputFuncJacobianX |
| Set this to provide an analytic solution to dh/dx.
|
|
std::function< Eigen::Matrix< double, outputDim, outputNoiseDim >(const state_t &, const outputnoise_t &)> | outputFuncJacobianV |
| Set this to provide an analytic solution to dh/dv.
|
|
template<int stateDim, int inputDim, int outputDim, int processNoiseDim, int outputNoiseDim>
class filters::ExtendedKalmanFilter< stateDim, inputDim, outputDim, processNoiseDim, outputNoiseDim >
Implements a discrete-time EKF.
This implements the more general system form described here: https://en.wikipedia.org/wiki/Extended_Kalman_filter#Non-additive_noise_formulation_and_equations
- Template Parameters
-
stateDim | The dimension of the state space for this system. This is the number of elements in the state vector. |
inputDim | The dimension of the input space for this system. This is the number of elements in the input vector. |
outputDim | The dimension of the output space for this system. This is the number of elements in the output (measurement) vector. |
processNoiseDim | The dimension of the process noise matrix. In systems with additive process noise, this is the same as stateDim. |
outputNoiseDim | The dimension of the output noise matrix. In systems with additive output noise, this is the same as outputDim. |