WPILibC++ 2024.3.2
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 <wpi/array.h>
8
9#include "frc/EigenCore.h"
11#include "units/time.h"
12
13namespace frc {
14
15/**
16 * A Kalman filter combines predictions from a model and measurements to give an
17 * estimate of the true system state. This is useful because many states cannot
18 * be measured directly as a result of sensor noise, or because the state is
19 * "hidden".
20 *
21 * Kalman filters use a K gain matrix to determine whether to trust the model or
22 * measurements more. Kalman filter theory uses statistics to compute an optimal
23 * K gain which minimizes the sum of squares error in the state estimate. This K
24 * gain is used to correct the state estimate by some amount of the difference
25 * between the actual measurements and the measurements predicted by the model.
26 *
27 * For more on the underlying math, read
28 * https://file.tavsys.net/control/controls-engineering-in-frc.pdf chapter 9
29 * "Stochastic control theory".
30 *
31 * @tparam States Number of states.
32 * @tparam Inputs Number of inputs.
33 * @tparam Outputs Number of outputs.
34 */
35template <int States, int Inputs, int Outputs>
37 public:
41
44
46
47 /**
48 * Constructs a Kalman filter with the given plant.
49 *
50 * See
51 * https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-observers.html#process-and-measurement-noise-covariance-matrices
52 * for how to select the standard deviations.
53 *
54 * @param plant The plant used for the prediction step.
55 * @param stateStdDevs Standard deviations of model states.
56 * @param measurementStdDevs Standard deviations of measurements.
57 * @param dt Nominal discretization timestep.
58 * @throws std::invalid_argument If the system is unobservable.
59 */
61 const StateArray& stateStdDevs,
62 const OutputArray& measurementStdDevs, units::second_t dt);
63
64 /**
65 * Returns the error covariance matrix P.
66 */
67 const StateMatrix& P() const { return m_P; }
68
69 /**
70 * Returns an element of the error covariance matrix P.
71 *
72 * @param i Row of P.
73 * @param j Column of P.
74 */
75 double P(int i, int j) const { return m_P(i, j); }
76
77 /**
78 * Set the current error covariance matrix P.
79 *
80 * @param P The error covariance matrix P.
81 */
82 void SetP(const StateMatrix& P) { m_P = P; }
83
84 /**
85 * Returns the state estimate x-hat.
86 */
87 const StateVector& Xhat() const { return m_xHat; }
88
89 /**
90 * Returns an element of the state estimate x-hat.
91 *
92 * @param i Row of x-hat.
93 */
94 double Xhat(int i) const { return m_xHat(i); }
95
96 /**
97 * Set initial state estimate x-hat.
98 *
99 * @param xHat The state estimate x-hat.
100 */
101 void SetXhat(const StateVector& xHat) { m_xHat = xHat; }
102
103 /**
104 * Set an element of the initial state estimate x-hat.
105 *
106 * @param i Row of x-hat.
107 * @param value Value for element of x-hat.
108 */
109 void SetXhat(int i, double value) { m_xHat(i) = value; }
110
111 /**
112 * Resets the observer.
113 */
114 void Reset() {
115 m_xHat.setZero();
116 m_P = m_initP;
117 }
118
119 /**
120 * Project the model into the future with a new control input u.
121 *
122 * @param u New control input from controller.
123 * @param dt Timestep for prediction.
124 */
125 void Predict(const InputVector& u, units::second_t dt);
126
127 /**
128 * Correct the state estimate x-hat using the measurements in y.
129 *
130 * @param u Same control input used in the predict step.
131 * @param y Measurement vector.
132 */
133 void Correct(const InputVector& u, const OutputVector& y) {
134 Correct(u, y, m_contR);
135 }
136
137 /**
138 * Correct the state estimate x-hat using the measurements in y.
139 *
140 * This is useful for when the measurement noise covariances vary.
141 *
142 * @param u Same control input used in the predict step.
143 * @param y Measurement vector.
144 * @param R Continuous measurement noise covariance matrix.
145 */
146 void Correct(const InputVector& u, const OutputVector& y,
148
149 private:
151 StateVector m_xHat;
152 StateMatrix m_P;
153 StateMatrix m_contQ;
155 units::second_t m_dt;
156
157 StateMatrix m_initP;
158};
159
160extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
161 KalmanFilter<1, 1, 1>;
162extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
163 KalmanFilter<2, 1, 1>;
164
165} // namespace frc
166
167#include "KalmanFilter.inc"
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
A Kalman filter combines predictions from a model and measurements to give an estimate of the true sy...
Definition: KalmanFilter.h:36
void SetXhat(int i, double value)
Set an element of the initial state estimate x-hat.
Definition: KalmanFilter.h:109
Vectord< States > StateVector
Definition: KalmanFilter.h:38
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.inc:23
const StateVector & Xhat() const
Returns the state estimate x-hat.
Definition: KalmanFilter.h:87
void Predict(const InputVector &u, units::second_t dt)
Project the model into the future with a new control input u.
Definition: KalmanFilter.inc:59
Vectord< Outputs > OutputVector
Definition: KalmanFilter.h:40
double Xhat(int i) const
Returns an element of the state estimate x-hat.
Definition: KalmanFilter.h:94
void SetP(const StateMatrix &P)
Set the current error covariance matrix P.
Definition: KalmanFilter.h:82
void Correct(const InputVector &u, const OutputVector &y)
Correct the state estimate x-hat using the measurements in y.
Definition: KalmanFilter.h:133
const StateMatrix & P() const
Returns the error covariance matrix P.
Definition: KalmanFilter.h:67
double P(int i, int j) const
Returns an element of the error covariance matrix P.
Definition: KalmanFilter.h:75
void Reset()
Resets the observer.
Definition: KalmanFilter.h:114
Vectord< Inputs > InputVector
Definition: KalmanFilter.h:39
Matrixd< States, States > StateMatrix
Definition: KalmanFilter.h:45
void SetXhat(const StateVector &xHat)
Set initial state estimate x-hat.
Definition: KalmanFilter.h:101
A plant defined using state-space notation.
Definition: LinearSystem.h:31
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.