WPILibC++ 2025.2.1
Loading...
Searching...
No Matches
KalmanFilter.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 <cmath>
8#include <stdexcept>
9#include <string>
10
11#include <Eigen/Cholesky>
12#include <wpi/array.h>
13
14#include "frc/DARE.h"
15#include "frc/EigenCore.h"
16#include "frc/StateSpaceUtil.h"
17#include "frc/fmt/Eigen.h"
20#include "units/time.h"
21#include "wpimath/MathShared.h"
22
23namespace frc {
24
25/**
26 * A Kalman filter combines predictions from a model and measurements to give an
27 * estimate of the true system state. This is useful because many states cannot
28 * be measured directly as a result of sensor noise, or because the state is
29 * "hidden".
30 *
31 * Kalman filters use a K gain matrix to determine whether to trust the model or
32 * measurements more. Kalman filter theory uses statistics to compute an optimal
33 * K gain which minimizes the sum of squares error in the state estimate. This K
34 * gain is used to correct the state estimate by some amount of the difference
35 * between the actual measurements and the measurements predicted by the model.
36 *
37 * For more on the underlying math, read
38 * https://file.tavsys.net/control/controls-engineering-in-frc.pdf chapter 9
39 * "Stochastic control theory".
40 *
41 * @tparam States Number of states.
42 * @tparam Inputs Number of inputs.
43 * @tparam Outputs Number of outputs.
44 */
45template <int States, int Inputs, int Outputs>
47 public:
51
54
56
57 /**
58 * Constructs a Kalman filter with the given plant.
59 *
60 * See
61 * https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices
62 * for how to select the standard deviations.
63 *
64 * @param plant The plant used for the prediction step.
65 * @param stateStdDevs Standard deviations of model states.
66 * @param measurementStdDevs Standard deviations of measurements.
67 * @param dt Nominal discretization timestep.
68 * @throws std::invalid_argument If the system is undetectable.
69 */
71 const StateArray& stateStdDevs,
72 const OutputArray& measurementStdDevs, units::second_t dt) {
73 m_plant = &plant;
74
75 m_contQ = MakeCovMatrix(stateStdDevs);
76 m_contR = MakeCovMatrix(measurementStdDevs);
77 m_dt = dt;
78
79 // Find discrete A and Q
82 DiscretizeAQ<States>(plant.A(), m_contQ, dt, &discA, &discQ);
83
85
86 const auto& C = plant.C();
87
88 if (auto P = DARE<States, Outputs>(discA.transpose(), C.transpose(), discQ,
89 discR)) {
90 m_initP = P.value();
91 } else if (P.error() == DAREError::QNotSymmetric ||
93 std::string msg =
94 fmt::format("{}\n\nQ =\n{}\n", to_string(P.error()), discQ);
95
97 throw std::invalid_argument(msg);
98 } else if (P.error() == DAREError::RNotSymmetric ||
100 std::string msg =
101 fmt::format("{}\n\nR =\n{}\n", to_string(P.error()), discR);
102
104 throw std::invalid_argument(msg);
105 } else if (P.error() == DAREError::ABNotStabilizable) {
106 std::string msg = fmt::format(
107 "The (A, C) pair is not detectable.\n\nA =\n{}\nC =\n{}\n",
108 to_string(P.error()), discA, C);
109
111 throw std::invalid_argument(msg);
112 } else if (P.error() == DAREError::ACNotDetectable) {
113 std::string msg = fmt::format("{}\n\nA =\n{}\nQ =\n{}\n",
114 to_string(P.error()), discA, discQ);
115
117 throw std::invalid_argument(msg);
118 }
119
120 Reset();
121 }
122
123 /**
124 * Returns the error covariance matrix P.
125 */
126 const StateMatrix& P() const { return m_P; }
127
128 /**
129 * Returns an element of the error covariance matrix P.
130 *
131 * @param i Row of P.
132 * @param j Column of P.
133 */
134 double P(int i, int j) const { return m_P(i, j); }
135
136 /**
137 * Set the current error covariance matrix P.
138 *
139 * @param P The error covariance matrix P.
140 */
141 void SetP(const StateMatrix& P) { m_P = P; }
142
143 /**
144 * Returns the state estimate x-hat.
145 */
146 const StateVector& Xhat() const { return m_xHat; }
147
148 /**
149 * Returns an element of the state estimate x-hat.
150 *
151 * @param i Row of x-hat.
152 */
153 double Xhat(int i) const { return m_xHat(i); }
154
155 /**
156 * Set initial state estimate x-hat.
157 *
158 * @param xHat The state estimate x-hat.
159 */
160 void SetXhat(const StateVector& xHat) { m_xHat = xHat; }
161
162 /**
163 * Set an element of the initial state estimate x-hat.
164 *
165 * @param i Row of x-hat.
166 * @param value Value for element of x-hat.
167 */
168 void SetXhat(int i, double value) { m_xHat(i) = value; }
169
170 /**
171 * Resets the observer.
172 */
173 void Reset() {
174 m_xHat.setZero();
175 m_P = m_initP;
176 }
177
178 /**
179 * Project the model into the future with a new control input u.
180 *
181 * @param u New control input from controller.
182 * @param dt Timestep for prediction.
183 */
184 void Predict(const InputVector& u, units::second_t dt) {
185 // Find discrete A and Q
186 StateMatrix discA;
187 StateMatrix discQ;
188 DiscretizeAQ<States>(m_plant->A(), m_contQ, dt, &discA, &discQ);
189
190 m_xHat = m_plant->CalculateX(m_xHat, u, dt);
191
192 // Pₖ₊₁⁻ = APₖ⁻Aᵀ + Q
193 m_P = discA * m_P * discA.transpose() + discQ;
194
195 m_dt = dt;
196 }
197
198 /**
199 * Correct the state estimate x-hat using the measurements in y.
200 *
201 * @param u Same control input used in the predict step.
202 * @param y Measurement vector.
203 */
204 void Correct(const InputVector& u, const OutputVector& y) {
205 Correct(u, y, m_contR);
206 }
207
208 /**
209 * Correct the state estimate x-hat using the measurements in y.
210 *
211 * This is useful for when the measurement noise covariances vary.
212 *
213 * @param u Same control input used in the predict step.
214 * @param y Measurement vector.
215 * @param R Continuous measurement noise covariance matrix.
216 */
217 void Correct(const InputVector& u, const OutputVector& y,
218 const Matrixd<Outputs, Outputs>& R) {
219 const auto& C = m_plant->C();
220 const auto& D = m_plant->D();
221
222 const Matrixd<Outputs, Outputs> discR = DiscretizeR<Outputs>(R, m_dt);
223
224 Matrixd<Outputs, Outputs> S = C * m_P * C.transpose() + discR;
225
226 // We want to put K = PCᵀS⁻¹ into Ax = b form so we can solve it more
227 // efficiently.
228 //
229 // K = PCᵀS⁻¹
230 // KS = PCᵀ
231 // (KS)ᵀ = (PCᵀ)ᵀ
232 // SᵀKᵀ = CPᵀ
233 //
234 // The solution of Ax = b can be found via x = A.solve(b).
235 //
236 // Kᵀ = Sᵀ.solve(CPᵀ)
237 // K = (Sᵀ.solve(CPᵀ))ᵀ
239 S.transpose().ldlt().solve(C * m_P.transpose()).transpose();
240
241 // x̂ₖ₊₁⁺ = x̂ₖ₊₁⁻ + K(y − (Cx̂ₖ₊₁⁻ + Duₖ₊₁))
242 m_xHat += K * (y - (C * m_xHat + D * u));
243
244 // Pₖ₊₁⁺ = (I−Kₖ₊₁C)Pₖ₊₁⁻(I−Kₖ₊₁C)ᵀ + Kₖ₊₁RKₖ₊₁ᵀ
245 // Use Joseph form for numerical stability
246 m_P = (StateMatrix::Identity() - K * C) * m_P *
247 (StateMatrix::Identity() - K * C).transpose() +
248 K * discR * K.transpose();
249 }
250
251 private:
253 StateVector m_xHat;
254 StateMatrix m_P;
255 StateMatrix m_contQ;
257 units::second_t m_dt;
258
259 StateMatrix m_initP;
260};
261
264extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
266
267} // namespace frc
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
#define EXPORT_TEMPLATE_DECLARE(export)
Definition SymbolExports.hpp:92
A Kalman filter combines predictions from a model and measurements to give an estimate of the true sy...
Definition KalmanFilter.h:46
void SetXhat(int i, double value)
Set an element of the initial state estimate x-hat.
Definition KalmanFilter.h:168
Vectord< States > StateVector
Definition KalmanFilter.h:48
KalmanFilter(LinearSystem< States, Inputs, Outputs > &plant, const StateArray &stateStdDevs, const OutputArray &measurementStdDevs, units::second_t dt)
Constructs a Kalman filter with the given plant.
Definition KalmanFilter.h:70
const StateVector & Xhat() const
Returns the state estimate x-hat.
Definition KalmanFilter.h:146
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 KalmanFilter.h:217
void Predict(const InputVector &u, units::second_t dt)
Project the model into the future with a new control input u.
Definition KalmanFilter.h:184
Vectord< Outputs > OutputVector
Definition KalmanFilter.h:50
double Xhat(int i) const
Returns an element of the state estimate x-hat.
Definition KalmanFilter.h:153
void SetP(const StateMatrix &P)
Set the current error covariance matrix P.
Definition KalmanFilter.h:141
void Correct(const InputVector &u, const OutputVector &y)
Correct the state estimate x-hat using the measurements in y.
Definition KalmanFilter.h:204
const StateMatrix & P() const
Returns the error covariance matrix P.
Definition KalmanFilter.h:126
double P(int i, int j) const
Returns an element of the error covariance matrix P.
Definition KalmanFilter.h:134
void Reset()
Resets the observer.
Definition KalmanFilter.h:173
Vectord< Inputs > InputVector
Definition KalmanFilter.h:49
Matrixd< States, States > StateMatrix
Definition KalmanFilter.h:55
void SetXhat(const StateVector &xHat)
Set initial state estimate x-hat.
Definition KalmanFilter.h:160
A plant defined using state-space notation.
Definition LinearSystem.h:35
constexpr const Matrixd< Outputs, States > & C() const
Returns the output matrix C.
Definition LinearSystem.h:130
constexpr const Matrixd< States, States > & A() const
Returns the system matrix A.
Definition LinearSystem.h:104
This class is a wrapper around std::array that does compile time size checking.
Definition array.h:26
static void ReportError(const S &format, Args &&... args)
Definition MathShared.h:62
Definition CAN.h:11
void DiscretizeAQ(const Matrixd< States, States > &contA, const Matrixd< States, States > &contQ, units::second_t dt, Matrixd< States, States > *discA, Matrixd< States, States > *discQ)
Discretizes the given continuous A and Q matrices.
Definition Discretization.h:71
Eigen::Matrix< double, Rows, Cols, Options, MaxRows, MaxCols > Matrixd
Definition EigenCore.h:21
Eigen::Vector< double, Size > Vectord
Definition EigenCore.h:12
Matrixd< Outputs, Outputs > DiscretizeR(const Matrixd< Outputs, Outputs > &R, units::second_t dt)
Returns a discretized version of the provided continuous measurement noise covariance matrix.
Definition Discretization.h:113
constexpr Matrixd< sizeof...(Ts), sizeof...(Ts)> MakeCovMatrix(Ts... stdDevs)
Creates a covariance matrix from the given vector for use with Kalman filters.
Definition StateSpaceUtil.h:75
wpi::expected< Eigen::Matrix< double, States, States >, DAREError > DARE(const Eigen::Matrix< double, States, States > &A, const Eigen::Matrix< double, States, Inputs > &B, const Eigen::Matrix< double, States, States > &Q, const Eigen::Matrix< double, Inputs, Inputs > &R, bool checkPreconditions=true)
Computes the unique stabilizing solution X to the discrete-time algebraic Riccati equation:
Definition DARE.h:165
constexpr std::string_view to_string(const DAREError &error)
Converts the given DAREError enum to a string.
Definition DARE.h:39
@ QNotPositiveSemidefinite
Q was not positive semidefinite.
@ RNotSymmetric
R was not symmetric.
@ QNotSymmetric
Q was not symmetric.
@ ACNotDetectable
(A, C) pair where Q = CᵀC was not detectable.
@ RNotPositiveDefinite
R was not positive definite.
@ ABNotStabilizable
(A, B) pair was not stabilizable.
#define S(label, offset, message)
Definition Errors.h:113