WPILibC++ 2024.3.2
ExtendedKalmanFilter.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <functional>
8
9#include <wpi/array.h>
10
11#include "frc/EigenCore.h"
12#include "units/time.h"
13
14namespace frc {
15
16/**
17 * A Kalman filter combines predictions from a model and measurements to give an
18 * estimate of the true system state. This is useful because many states cannot
19 * be measured directly as a result of sensor noise, or because the state is
20 * "hidden".
21 *
22 * Kalman filters use a K gain matrix to determine whether to trust the model or
23 * measurements more. Kalman filter theory uses statistics to compute an optimal
24 * K gain which minimizes the sum of squares error in the state estimate. This K
25 * gain is used to correct the state estimate by some amount of the difference
26 * between the actual measurements and the measurements predicted by the model.
27 *
28 * An extended Kalman filter supports nonlinear state and measurement models. It
29 * propagates the error covariance by linearizing the models around the state
30 * estimate, then applying the linear Kalman filter equations.
31 *
32 * For more on the underlying math, read
33 * https://file.tavsys.net/control/controls-engineering-in-frc.pdf chapter 9
34 * "Stochastic control theory".
35 *
36 * @tparam States Number of states.
37 * @tparam Inputs Number of inputs.
38 * @tparam Outputs Number of outputs.
39 */
40template <int States, int Inputs, int Outputs>
42 public:
46
49
51
52 /**
53 * Constructs an extended Kalman filter.
54 *
55 * See
56 * https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices
57 * for how to select the standard deviations.
58 *
59 * @param f A vector-valued function of x and u that returns
60 * the derivative of the state vector.
61 * @param h A vector-valued function of x and u that returns
62 * the measurement vector.
63 * @param stateStdDevs Standard deviations of model states.
64 * @param measurementStdDevs Standard deviations of measurements.
65 * @param dt Nominal discretization timestep.
66 */
68 std::function<StateVector(const StateVector&, const InputVector&)> f,
69 std::function<OutputVector(const StateVector&, const InputVector&)> h,
70 const StateArray& stateStdDevs, const OutputArray& measurementStdDevs,
71 units::second_t dt);
72
73 /**
74 * Constructs an extended Kalman filter.
75 *
76 * See
77 * https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices
78 * for how to select the standard deviations.
79 *
80 * @param f A vector-valued function of x and u that returns
81 * the derivative of the state vector.
82 * @param h A vector-valued function of x and u that returns
83 * the measurement vector.
84 * @param stateStdDevs Standard deviations of model states.
85 * @param measurementStdDevs Standard deviations of measurements.
86 * @param residualFuncY A function that computes the residual of two
87 * measurement vectors (i.e. it subtracts them.)
88 * @param addFuncX A function that adds two state vectors.
89 * @param dt Nominal discretization timestep.
90 */
92 std::function<StateVector(const StateVector&, const InputVector&)> f,
93 std::function<OutputVector(const StateVector&, const InputVector&)> h,
94 const StateArray& stateStdDevs, const OutputArray& measurementStdDevs,
95 std::function<OutputVector(const OutputVector&, const OutputVector&)>
96 residualFuncY,
97 std::function<StateVector(const StateVector&, const StateVector&)>
98 addFuncX,
99 units::second_t dt);
100
101 /**
102 * Returns the error covariance matrix P.
103 */
104 const StateMatrix& P() const { return m_P; }
105
106 /**
107 * Returns an element of the error covariance matrix P.
108 *
109 * @param i Row of P.
110 * @param j Column of P.
111 */
112 double P(int i, int j) const { return m_P(i, j); }
113
114 /**
115 * Set the current error covariance matrix P.
116 *
117 * @param P The error covariance matrix P.
118 */
119 void SetP(const StateMatrix& P) { m_P = P; }
120
121 /**
122 * Returns the state estimate x-hat.
123 */
124 const StateVector& Xhat() const { return m_xHat; }
125
126 /**
127 * Returns an element of the state estimate x-hat.
128 *
129 * @param i Row of x-hat.
130 */
131 double Xhat(int i) const { return m_xHat(i); }
132
133 /**
134 * Set initial state estimate x-hat.
135 *
136 * @param xHat The state estimate x-hat.
137 */
138 void SetXhat(const StateVector& xHat) { m_xHat = xHat; }
139
140 /**
141 * Set an element of the initial state estimate x-hat.
142 *
143 * @param i Row of x-hat.
144 * @param value Value for element of x-hat.
145 */
146 void SetXhat(int i, double value) { m_xHat(i) = value; }
147
148 /**
149 * Resets the observer.
150 */
151 void Reset() {
152 m_xHat.setZero();
153 m_P = m_initP;
154 }
155
156 /**
157 * Project the model into the future with a new control input u.
158 *
159 * @param u New control input from controller.
160 * @param dt Timestep for prediction.
161 */
162 void Predict(const InputVector& u, units::second_t dt);
163
164 /**
165 * Correct the state estimate x-hat using the measurements in y.
166 *
167 * @param u Same control input used in the predict step.
168 * @param y Measurement vector.
169 */
170 void Correct(const InputVector& u, const OutputVector& y) {
171 Correct<Outputs>(u, y, m_h, m_contR, m_residualFuncY, m_addFuncX);
172 }
173
174 /**
175 * Correct the state estimate x-hat using the measurements in y.
176 *
177 * This is useful for when the measurement noise covariances vary.
178 *
179 * @param u Same control input used in the predict step.
180 * @param y Measurement vector.
181 * @param R Continuous measurement noise covariance matrix.
182 */
183 void Correct(const InputVector& u, const OutputVector& y,
185 Correct<Outputs>(u, y, m_h, R, m_residualFuncY, m_addFuncX);
186 }
187
188 /**
189 * Correct the state estimate x-hat using the measurements in y.
190 *
191 * This is useful for when the measurements available during a timestep's
192 * Correct() call vary. The h(x, u) passed to the constructor is used if one
193 * is not provided (the two-argument version of this function).
194 *
195 * @param u Same control input used in the predict step.
196 * @param y Measurement vector.
197 * @param h A vector-valued function of x and u that returns the measurement
198 * vector.
199 * @param R Continuous measurement noise covariance matrix.
200 */
201 template <int Rows>
202 void Correct(
203 const InputVector& u, const Vectord<Rows>& y,
204 std::function<Vectord<Rows>(const StateVector&, const InputVector&)> h,
205 const Matrixd<Rows, Rows>& R);
206
207 /**
208 * Correct the state estimate x-hat using the measurements in y.
209 *
210 * This is useful for when the measurements available during a timestep's
211 * Correct() call vary. The h(x, u) passed to the constructor is used if one
212 * is not provided (the two-argument version of this function).
213 *
214 * @param u Same control input used in the predict step.
215 * @param y Measurement vector.
216 * @param h A vector-valued function of x and u that returns
217 * the measurement vector.
218 * @param R Continuous measurement noise covariance matrix.
219 * @param residualFuncY A function that computes the residual of two
220 * measurement vectors (i.e. it subtracts them.)
221 * @param addFuncX A function that adds two state vectors.
222 */
223 template <int Rows>
224 void Correct(
225 const InputVector& u, const Vectord<Rows>& y,
226 std::function<Vectord<Rows>(const StateVector&, const InputVector&)> h,
227 const Matrixd<Rows, Rows>& R,
228 std::function<Vectord<Rows>(const Vectord<Rows>&, const Vectord<Rows>&)>
229 residualFuncY,
230 std::function<StateVector(const StateVector&, const StateVector&)>
231 addFuncX);
232
233 private:
234 std::function<StateVector(const StateVector&, const InputVector&)> m_f;
235 std::function<OutputVector(const StateVector&, const InputVector&)> m_h;
236 std::function<OutputVector(const OutputVector&, const OutputVector&)>
237 m_residualFuncY;
238 std::function<StateVector(const StateVector&, const StateVector&)> m_addFuncX;
239 StateVector m_xHat;
240 StateMatrix m_P;
241 StateMatrix m_contQ;
243 units::second_t m_dt;
244
245 StateMatrix m_initP;
246};
247
248} // namespace frc
249
A Kalman filter combines predictions from a model and measurements to give an estimate of the true sy...
Definition: ExtendedKalmanFilter.h:41
void Correct(const InputVector &u, const OutputVector &y)
Correct the state estimate x-hat using the measurements in y.
Definition: ExtendedKalmanFilter.h:170
const StateMatrix & P() const
Returns the error covariance matrix P.
Definition: ExtendedKalmanFilter.h:104
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.
Definition: ExtendedKalmanFilter.inc:21
Vectord< Inputs > InputVector
Definition: ExtendedKalmanFilter.h:44
void Reset()
Resets the observer.
Definition: ExtendedKalmanFilter.h:151
void Predict(const InputVector &u, units::second_t dt)
Project the model into the future with a new control input u.
Definition: ExtendedKalmanFilter.inc:92
Matrixd< States, States > StateMatrix
Definition: ExtendedKalmanFilter.h:50
Vectord< Outputs > OutputVector
Definition: ExtendedKalmanFilter.h:45
void SetP(const StateMatrix &P)
Set the current error covariance matrix P.
Definition: ExtendedKalmanFilter.h:119
void SetXhat(int i, double value)
Set an element of the initial state estimate x-hat.
Definition: ExtendedKalmanFilter.h:146
const StateVector & Xhat() const
Returns the state estimate x-hat.
Definition: ExtendedKalmanFilter.h:124
Vectord< States > StateVector
Definition: ExtendedKalmanFilter.h:43
void SetXhat(const StateVector &xHat)
Set initial state estimate x-hat.
Definition: ExtendedKalmanFilter.h:138
double P(int i, int j) const
Returns an element of the error covariance matrix P.
Definition: ExtendedKalmanFilter.h:112
void Correct(const InputVector &u, const OutputVector &y, const Matrixd< Outputs, Outputs > &R)
Correct the state estimate x-hat using the measurements in y.
Definition: ExtendedKalmanFilter.h:183
double Xhat(int i) const
Returns an element of the state estimate x-hat.
Definition: ExtendedKalmanFilter.h:131
This class is a wrapper around std::array that does compile time size checking.
Definition: array.h:26
Definition: AprilTagPoseEstimator.h:15
Eigen::Matrix< double, Rows, Cols, Options, MaxRows, MaxCols > Matrixd
Definition: EigenCore.h:21
Eigen::Vector< double, Size > Vectord
Definition: EigenCore.h:12
static constexpr const unit_t< compound_unit< energy::joules, inverse< temperature::kelvin >, inverse< substance::moles > > > R(8.3144598)
Gas constant.
static constexpr const unit_t< compound_unit< energy::joule, time::seconds > > h(6.626070040e-34)
Planck constant.