WPILibC++ 2024.3.2
|
A Kalman filter combines predictions from a model and measurements to give an estimate of the true system state. More...
#include <frc/estimator/ExtendedKalmanFilter.h>
Public Types | |
using | StateVector = Vectord< States > |
using | InputVector = Vectord< Inputs > |
using | OutputVector = Vectord< Outputs > |
using | StateArray = wpi::array< double, States > |
using | OutputArray = wpi::array< double, Outputs > |
using | StateMatrix = Matrixd< States, States > |
Public Member Functions | |
ExtendedKalmanFilter (std::function< StateVector(const StateVector &, const InputVector &)> f, std::function< OutputVector(const StateVector &, const InputVector &)> h, const StateArray &stateStdDevs, const OutputArray &measurementStdDevs, units::second_t dt) | |
Constructs an extended Kalman filter. More... | |
ExtendedKalmanFilter (std::function< StateVector(const StateVector &, const InputVector &)> f, std::function< OutputVector(const StateVector &, const InputVector &)> h, const StateArray &stateStdDevs, const OutputArray &measurementStdDevs, std::function< OutputVector(const OutputVector &, const OutputVector &)> residualFuncY, std::function< StateVector(const StateVector &, const StateVector &)> addFuncX, units::second_t dt) | |
Constructs an extended Kalman filter. More... | |
const StateMatrix & | P () const |
Returns the error covariance matrix P. More... | |
double | P (int i, int j) const |
Returns an element of the error covariance matrix P. More... | |
void | SetP (const StateMatrix &P) |
Set the current error covariance matrix P. More... | |
const StateVector & | Xhat () const |
Returns the state estimate x-hat. More... | |
double | Xhat (int i) const |
Returns an element of the state estimate x-hat. More... | |
void | SetXhat (const StateVector &xHat) |
Set initial state estimate x-hat. More... | |
void | SetXhat (int i, double value) |
Set an element of the initial state estimate x-hat. More... | |
void | Reset () |
Resets the observer. More... | |
void | Predict (const InputVector &u, units::second_t dt) |
Project the model into the future with a new control input u. More... | |
void | Correct (const InputVector &u, const OutputVector &y) |
Correct the state estimate x-hat using the measurements in y. More... | |
void | Correct (const InputVector &u, const OutputVector &y, const Matrixd< Outputs, Outputs > &R) |
Correct the state estimate x-hat using the measurements in y. More... | |
template<int Rows> | |
void | Correct (const InputVector &u, const Vectord< Rows > &y, std::function< Vectord< Rows >(const StateVector &, const InputVector &)> h, const Matrixd< Rows, Rows > &R) |
Correct the state estimate x-hat using the measurements in y. More... | |
template<int Rows> | |
void | Correct (const InputVector &u, const Vectord< Rows > &y, std::function< Vectord< Rows >(const StateVector &, const InputVector &)> h, const Matrixd< Rows, Rows > &R, std::function< Vectord< Rows >(const Vectord< Rows > &, const Vectord< Rows > &)> residualFuncY, std::function< StateVector(const StateVector &, const StateVector &)> addFuncX) |
Correct the state estimate x-hat using the measurements in y. More... | |
A Kalman filter combines predictions from a model and measurements to give an estimate of the true system state.
This is useful because many states cannot be measured directly as a result of sensor noise, or because the state is "hidden".
Kalman filters use a K gain matrix to determine whether to trust the model or measurements more. Kalman filter theory uses statistics to compute an optimal K gain which minimizes the sum of squares error in the state estimate. This K gain is used to correct the state estimate by some amount of the difference between the actual measurements and the measurements predicted by the model.
An extended Kalman filter supports nonlinear state and measurement models. It propagates the error covariance by linearizing the models around the state estimate, then applying the linear Kalman filter equations.
For more on the underlying math, read https://file.tavsys.net/control/controls-engineering-in-frc.pdf chapter 9 "Stochastic control theory".
States | Number of states. |
Inputs | Number of inputs. |
Outputs | Number of outputs. |
using frc::ExtendedKalmanFilter< States, Inputs, Outputs >::InputVector = Vectord<Inputs> |
using frc::ExtendedKalmanFilter< States, Inputs, Outputs >::OutputArray = wpi::array<double, Outputs> |
using frc::ExtendedKalmanFilter< States, Inputs, Outputs >::OutputVector = Vectord<Outputs> |
using frc::ExtendedKalmanFilter< States, Inputs, Outputs >::StateArray = wpi::array<double, States> |
using frc::ExtendedKalmanFilter< States, Inputs, Outputs >::StateMatrix = Matrixd<States, States> |
using frc::ExtendedKalmanFilter< States, Inputs, Outputs >::StateVector = Vectord<States> |
frc::ExtendedKalmanFilter< States, Inputs, Outputs >::ExtendedKalmanFilter | ( | std::function< StateVector(const StateVector &, const InputVector &)> | f, |
std::function< OutputVector(const StateVector &, const InputVector &)> | h, | ||
const StateArray & | stateStdDevs, | ||
const OutputArray & | measurementStdDevs, | ||
units::second_t | dt | ||
) |
Constructs an extended Kalman filter.
See https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices for how to select the standard deviations.
f | A vector-valued function of x and u that returns the derivative of the state vector. |
h | A vector-valued function of x and u that returns the measurement vector. |
stateStdDevs | Standard deviations of model states. |
measurementStdDevs | Standard deviations of measurements. |
dt | Nominal discretization timestep. |
frc::ExtendedKalmanFilter< States, Inputs, Outputs >::ExtendedKalmanFilter | ( | std::function< StateVector(const StateVector &, const InputVector &)> | f, |
std::function< OutputVector(const StateVector &, const InputVector &)> | h, | ||
const StateArray & | stateStdDevs, | ||
const OutputArray & | measurementStdDevs, | ||
std::function< OutputVector(const OutputVector &, const OutputVector &)> | residualFuncY, | ||
std::function< StateVector(const StateVector &, const StateVector &)> | addFuncX, | ||
units::second_t | dt | ||
) |
Constructs an extended Kalman filter.
See https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices for how to select the standard deviations.
f | A vector-valued function of x and u that returns the derivative of the state vector. |
h | A vector-valued function of x and u that returns the measurement vector. |
stateStdDevs | Standard deviations of model states. |
measurementStdDevs | Standard deviations of measurements. |
residualFuncY | A function that computes the residual of two measurement vectors (i.e. it subtracts them.) |
addFuncX | A function that adds two state vectors. |
dt | Nominal discretization timestep. |
|
inline |
Correct the state estimate x-hat using the measurements in y.
u | Same control input used in the predict step. |
y | Measurement vector. |
|
inline |
Correct the state estimate x-hat using the measurements in y.
This is useful for when the measurement noise covariances vary.
u | Same control input used in the predict step. |
y | Measurement vector. |
R | Continuous measurement noise covariance matrix. |
void frc::ExtendedKalmanFilter< States, Inputs, Outputs >::Correct | ( | const InputVector & | u, |
const Vectord< Rows > & | y, | ||
std::function< Vectord< Rows >(const StateVector &, const InputVector &)> | h, | ||
const Matrixd< Rows, Rows > & | R | ||
) |
Correct the state estimate x-hat using the measurements in y.
This is useful for when the measurements available during a timestep's Correct() call vary. The h(x, u) passed to the constructor is used if one is not provided (the two-argument version of this function).
u | Same control input used in the predict step. |
y | Measurement vector. |
h | A vector-valued function of x and u that returns the measurement vector. |
R | Continuous measurement noise covariance matrix. |
void frc::ExtendedKalmanFilter< States, Inputs, Outputs >::Correct | ( | const InputVector & | u, |
const Vectord< Rows > & | y, | ||
std::function< Vectord< Rows >(const StateVector &, const InputVector &)> | h, | ||
const Matrixd< Rows, Rows > & | R, | ||
std::function< Vectord< Rows >(const Vectord< Rows > &, const Vectord< Rows > &)> | residualFuncY, | ||
std::function< StateVector(const StateVector &, const StateVector &)> | addFuncX | ||
) |
Correct the state estimate x-hat using the measurements in y.
This is useful for when the measurements available during a timestep's Correct() call vary. The h(x, u) passed to the constructor is used if one is not provided (the two-argument version of this function).
u | Same control input used in the predict step. |
y | Measurement vector. |
h | A vector-valued function of x and u that returns the measurement vector. |
R | Continuous measurement noise covariance matrix. |
residualFuncY | A function that computes the residual of two measurement vectors (i.e. it subtracts them.) |
addFuncX | A function that adds two state vectors. |
|
inline |
Returns the error covariance matrix P.
|
inline |
Returns an element of the error covariance matrix P.
i | Row of P. |
j | Column of P. |
void frc::ExtendedKalmanFilter< States, Inputs, Outputs >::Predict | ( | const InputVector & | u, |
units::second_t | dt | ||
) |
Project the model into the future with a new control input u.
u | New control input from controller. |
dt | Timestep for prediction. |
|
inline |
Resets the observer.
|
inline |
Set the current error covariance matrix P.
P | The error covariance matrix P. |
|
inline |
Set initial state estimate x-hat.
xHat | The state estimate x-hat. |
|
inline |
Set an element of the initial state estimate x-hat.
i | Row of x-hat. |
value | Value for element of x-hat. |
|
inline |
Returns the state estimate x-hat.
|
inline |
Returns an element of the state estimate x-hat.
i | Row of x-hat. |