WPILibC++ 2024.3.2
UnscentedKalmanFilter.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/SymbolExports.h>
10#include <wpi/array.h>
11
12#include "frc/EigenCore.h"
14#include "units/time.h"
15
16namespace frc {
17
18/**
19 * A Kalman filter combines predictions from a model and measurements to give an
20 * estimate of the true system state. This is useful because many states cannot
21 * be measured directly as a result of sensor noise, or because the state is
22 * "hidden".
23 *
24 * Kalman filters use a K gain matrix to determine whether to trust the model or
25 * measurements more. Kalman filter theory uses statistics to compute an optimal
26 * K gain which minimizes the sum of squares error in the state estimate. This K
27 * gain is used to correct the state estimate by some amount of the difference
28 * between the actual measurements and the measurements predicted by the model.
29 *
30 * An unscented Kalman filter uses nonlinear state and measurement models. It
31 * propagates the error covariance using sigma points chosen to approximate the
32 * true probability distribution.
33 *
34 * For more on the underlying math, read
35 * https://file.tavsys.net/control/controls-engineering-in-frc.pdf chapter 9
36 * "Stochastic control theory".
37 *
38 * <p> This class implements a square-root-form unscented Kalman filter
39 * (SR-UKF). For more information about the SR-UKF, see
40 * https://www.researchgate.net/publication/3908304.
41 *
42 * @tparam States Number of states.
43 * @tparam Inputs Number of inputs.
44 * @tparam Outputs Number of outputs.
45 */
46template <int States, int Inputs, int Outputs>
48 public:
52
55
57
58 /**
59 * Constructs an unscented Kalman filter.
60 *
61 * See
62 * https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices
63 * for how to select the standard deviations.
64 *
65 * @param f A vector-valued function of x and u that returns
66 * the derivative of the state vector.
67 * @param h A vector-valued function of x and u that returns
68 * the measurement vector.
69 * @param stateStdDevs Standard deviations of model states.
70 * @param measurementStdDevs Standard deviations of measurements.
71 * @param dt Nominal discretization timestep.
72 */
74 std::function<StateVector(const StateVector&, const InputVector&)> f,
75 std::function<OutputVector(const StateVector&, const InputVector&)> h,
76 const StateArray& stateStdDevs, const OutputArray& measurementStdDevs,
77 units::second_t dt);
78
79 /**
80 * Constructs an unscented Kalman filter with custom mean, residual, and
81 * addition functions. Using custom functions for arithmetic can be useful if
82 * you have angles in the state or measurements, because they allow you to
83 * correctly account for the modular nature of angle arithmetic.
84 *
85 * See
86 * https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices
87 * for how to select the standard deviations.
88 *
89 * @param f A vector-valued function of x and u that returns
90 * the derivative of the state vector.
91 * @param h A vector-valued function of x and u that returns
92 * the measurement vector.
93 * @param stateStdDevs Standard deviations of model states.
94 * @param measurementStdDevs Standard deviations of measurements.
95 * @param meanFuncX A function that computes the mean of 2 * States +
96 * 1 state vectors using a given set of weights.
97 * @param meanFuncY A function that computes the mean of 2 * States +
98 * 1 measurement vectors using a given set of
99 * weights.
100 * @param residualFuncX A function that computes the residual of two
101 * state vectors (i.e. it subtracts them.)
102 * @param residualFuncY A function that computes the residual of two
103 * measurement vectors (i.e. it subtracts them.)
104 * @param addFuncX A function that adds two state vectors.
105 * @param dt Nominal discretization timestep.
106 */
108 std::function<StateVector(const StateVector&, const InputVector&)> f,
109 std::function<OutputVector(const StateVector&, const InputVector&)> h,
110 const StateArray& stateStdDevs, const OutputArray& measurementStdDevs,
111 std::function<StateVector(const Matrixd<States, 2 * States + 1>&,
113 meanFuncX,
116 meanFuncY,
117 std::function<StateVector(const StateVector&, const StateVector&)>
118 residualFuncX,
119 std::function<OutputVector(const OutputVector&, const OutputVector&)>
120 residualFuncY,
121 std::function<StateVector(const StateVector&, const StateVector&)>
122 addFuncX,
123 units::second_t dt);
124
125 /**
126 * Returns the square-root error covariance matrix S.
127 */
128 const StateMatrix& S() const { return m_S; }
129
130 /**
131 * Returns an element of the square-root error covariance matrix S.
132 *
133 * @param i Row of S.
134 * @param j Column of S.
135 */
136 double S(int i, int j) const { return m_S(i, j); }
137
138 /**
139 * Set the current square-root error covariance matrix S.
140 *
141 * @param S The square-root error covariance matrix S.
142 */
143 void SetS(const StateMatrix& S) { m_S = S; }
144
145 /**
146 * Returns the reconstructed error covariance matrix P.
147 */
148 StateMatrix P() const { return m_S.transpose() * m_S; }
149
150 /**
151 * Set the current square-root error covariance matrix S by taking the square
152 * root of P.
153 *
154 * @param P The error covariance matrix P.
155 */
156 void SetP(const StateMatrix& P) { m_S = P.llt().matrixU(); }
157
158 /**
159 * Returns the state estimate x-hat.
160 */
161 const StateVector& Xhat() const { return m_xHat; }
162
163 /**
164 * Returns an element of the state estimate x-hat.
165 *
166 * @param i Row of x-hat.
167 */
168 double Xhat(int i) const { return m_xHat(i); }
169
170 /**
171 * Set initial state estimate x-hat.
172 *
173 * @param xHat The state estimate x-hat.
174 */
175 void SetXhat(const StateVector& xHat) { m_xHat = xHat; }
176
177 /**
178 * Set an element of the initial state estimate x-hat.
179 *
180 * @param i Row of x-hat.
181 * @param value Value for element of x-hat.
182 */
183 void SetXhat(int i, double value) { m_xHat(i) = value; }
184
185 /**
186 * Resets the observer.
187 */
188 void Reset() {
189 m_xHat.setZero();
190 m_S.setZero();
191 m_sigmasF.setZero();
192 }
193
194 /**
195 * Project the model into the future with a new control input u.
196 *
197 * @param u New control input from controller.
198 * @param dt Timestep for prediction.
199 */
200 void Predict(const InputVector& u, units::second_t dt);
201
202 /**
203 * Correct the state estimate x-hat using the measurements in y.
204 *
205 * @param u Same control input used in the predict step.
206 * @param y Measurement vector.
207 */
208 void Correct(const InputVector& u, const OutputVector& y) {
209 Correct<Outputs>(u, y, m_h, m_contR, m_meanFuncY, m_residualFuncY,
210 m_residualFuncX, m_addFuncX);
211 }
212
213 /**
214 * Correct the state estimate x-hat using the measurements in y.
215 *
216 * This is useful for when the measurement noise covariances vary.
217 *
218 * @param u Same control input used in the predict step.
219 * @param y Measurement vector.
220 * @param R Continuous measurement noise covariance matrix.
221 */
222 void Correct(const InputVector& u, const OutputVector& y,
224 Correct<Outputs>(u, y, m_h, R, m_meanFuncY, m_residualFuncY,
225 m_residualFuncX, m_addFuncX);
226 }
227
228 /**
229 * Correct the state estimate x-hat using the measurements in y.
230 *
231 * This is useful for when the measurements available during a timestep's
232 * Correct() call vary. The h(x, u) passed to the constructor is used if one
233 * is not provided (the two-argument version of this function).
234 *
235 * @param u Same control input used in the predict step.
236 * @param y Measurement vector.
237 * @param h A vector-valued function of x and u that returns the measurement
238 * vector.
239 * @param R Continuous measurement noise covariance matrix.
240 */
241 template <int Rows>
242 void Correct(
243 const InputVector& u, const Vectord<Rows>& y,
244 std::function<Vectord<Rows>(const StateVector&, const InputVector&)> h,
245 const Matrixd<Rows, Rows>& R);
246
247 /**
248 * Correct the state estimate x-hat using the measurements in y.
249 *
250 * This is useful for when the measurements available during a timestep's
251 * Correct() call vary. The h(x, u) passed to the constructor is used if one
252 * is not provided (the two-argument version of this function).
253 *
254 * @param u Same control input used in the predict step.
255 * @param y Measurement vector.
256 * @param h A vector-valued function of x and u that returns the
257 * measurement vector.
258 * @param R Continuous measurement noise covariance matrix.
259 * @param meanFuncY A function that computes the mean of 2 * States + 1
260 * measurement vectors using a given set of weights.
261 * @param residualFuncY A function that computes the residual of two
262 * measurement vectors (i.e. it subtracts them.)
263 * @param residualFuncX A function that computes the residual of two state
264 * vectors (i.e. it subtracts them.)
265 * @param addFuncX A function that adds two state vectors.
266 */
267 template <int Rows>
268 void Correct(
269 const InputVector& u, const Vectord<Rows>& y,
270 std::function<Vectord<Rows>(const StateVector&, const InputVector&)> h,
271 const Matrixd<Rows, Rows>& R,
272 std::function<Vectord<Rows>(const Matrixd<Rows, 2 * States + 1>&,
274 meanFuncY,
275 std::function<Vectord<Rows>(const Vectord<Rows>&, const Vectord<Rows>&)>
276 residualFuncY,
277 std::function<StateVector(const StateVector&, const StateVector&)>
278 residualFuncX,
279 std::function<StateVector(const StateVector&, const StateVector&)>
280 addFuncX);
281
282 private:
283 std::function<StateVector(const StateVector&, const InputVector&)> m_f;
284 std::function<OutputVector(const StateVector&, const InputVector&)> m_h;
285 std::function<StateVector(const Matrixd<States, 2 * States + 1>&,
287 m_meanFuncX;
290 m_meanFuncY;
291 std::function<StateVector(const StateVector&, const StateVector&)>
292 m_residualFuncX;
293 std::function<OutputVector(const OutputVector&, const OutputVector&)>
294 m_residualFuncY;
295 std::function<StateVector(const StateVector&, const StateVector&)> m_addFuncX;
296 StateVector m_xHat;
297 StateMatrix m_S;
298 StateMatrix m_contQ;
301 units::second_t m_dt;
302
304};
305
306extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
307 UnscentedKalmanFilter<3, 3, 1>;
308extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
309 UnscentedKalmanFilter<5, 3, 3>;
310
311} // namespace frc
312
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Generates sigma points and weights according to Van der Merwe's 2004 dissertation[1] for the Unscente...
Definition: MerweScaledSigmaPoints.h:28
A Kalman filter combines predictions from a model and measurements to give an estimate of the true sy...
Definition: UnscentedKalmanFilter.h:47
const StateVector & Xhat() const
Returns the state estimate x-hat.
Definition: UnscentedKalmanFilter.h:161
Matrixd< States, States > StateMatrix
Definition: UnscentedKalmanFilter.h:56
const StateMatrix & S() const
Returns the square-root error covariance matrix S.
Definition: UnscentedKalmanFilter.h:128
Vectord< Outputs > OutputVector
Definition: UnscentedKalmanFilter.h:51
double Xhat(int i) const
Returns an element of the state estimate x-hat.
Definition: UnscentedKalmanFilter.h:168
void Predict(const InputVector &u, units::second_t dt)
Project the model into the future with a new control input u.
Definition: UnscentedKalmanFilter.inc:73
double S(int i, int j) const
Returns an element of the square-root error covariance matrix S.
Definition: UnscentedKalmanFilter.h:136
Vectord< States > StateVector
Definition: UnscentedKalmanFilter.h:49
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: UnscentedKalmanFilter.h:222
void SetS(const StateMatrix &S)
Set the current square-root error covariance matrix S.
Definition: UnscentedKalmanFilter.h:143
StateMatrix P() const
Returns the reconstructed error covariance matrix P.
Definition: UnscentedKalmanFilter.h:148
void SetXhat(const StateVector &xHat)
Set initial state estimate x-hat.
Definition: UnscentedKalmanFilter.h:175
UnscentedKalmanFilter(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 unscented Kalman filter.
Definition: UnscentedKalmanFilter.inc:21
void SetXhat(int i, double value)
Set an element of the initial state estimate x-hat.
Definition: UnscentedKalmanFilter.h:183
Vectord< Inputs > InputVector
Definition: UnscentedKalmanFilter.h:50
void SetP(const StateMatrix &P)
Set the current square-root error covariance matrix S by taking the square root of P.
Definition: UnscentedKalmanFilter.h:156
void Reset()
Resets the observer.
Definition: UnscentedKalmanFilter.h:188
void Correct(const InputVector &u, const OutputVector &y)
Correct the state estimate x-hat using the measurements in y.
Definition: UnscentedKalmanFilter.h:208
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
template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) LinearQuadraticRegulator< 1
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.