RIT VEXU Core API
Loading...
Searching...
No Matches
kalman_filter.h
1#pragma once
2
3#include "math/eigen_interface.h"
4
5#include "math/systems/linear_system.h"
6
24template <int STATES, int INPUTS, int OUTPUTS> class KalmanFilter {
25 public:
26 using StateVector = EVec<STATES>;
27 using InputVector = EVec<INPUTS>;
28 using OutputVector = EVec<OUTPUTS>;
29
30 using StateMatrix = EMat<STATES, STATES>;
31 using InputMatrix = EMat<STATES, INPUTS>;
32
41 LinearSystem<STATES, INPUTS, OUTPUTS> &plant, const StateVector &state_stddevs,
42 const OutputVector &measurement_stddevs
43 )
44 : KalmanFilter(plant.A(), plant.B(), plant.C(), plant.D(), state_stddevs, measurement_stddevs) {}
45
57 const StateMatrix &A, const InputMatrix &B, const EMat<OUTPUTS, STATES> &C, const EMat<OUTPUTS, INPUTS> &D,
58 const StateVector &state_stddevs, const OutputVector &measurement_stddevs
59 ) {
60 A_ = A;
61 B_ = B;
62 C_ = C;
63 D_ = D;
64
65 Q_ = state_stddevs.asDiagonal();
66 Q_ = Q_ * Q_.transpose();
67 R_ = measurement_stddevs.asDiagonal();
68 R_ = R_ * R_.transpose();
69
70 reset();
71 }
72
76 StateMatrix P() const { return P_; }
77
83 void set_P(const StateMatrix &P) { P_ = P; }
84
88 const StateVector &xhat() const { return xhat_; }
89
95 double xhat(int i) const { return xhat_(i); }
96
100 void set_xhat(const StateVector &xhat) { xhat_ = xhat; }
101
107 void set_xhat(int i, double value) { xhat_(i) = value; }
108
112 void reset() {
113 xhat_.setZero();
114 P_.setZero();
115 }
116
123 void predict(const InputVector &u, const double &dt) {
124 // Q is discrete sqrt(process noise)
125 EMat<STATES, STATES> Q = Q_ * dt;
126 auto [A, B] = discretize_AB(A_, B_, dt);
127
128 // Compute prior mean
129 xhat_ = A * xhat_ + B * u;
130
131 // Compute prior covariance
132 P_ = A * P_ * A.transpose() + Q;
133 }
134
141 void correct(const OutputVector &y, const InputVector &u) { correct<OUTPUTS>(y, u, C_, D_, R_); }
142
152 void correct(const OutputVector &y, const InputVector &u, const EMat<OUTPUTS, OUTPUTS> &R) {
153 correct<OUTPUTS>(y, u, C_, D_, R);
154 }
155
168 template <int ROWS>
170 const EVec<ROWS> &y, const InputVector &u, const EMat<ROWS, STATES> &C, const EMat<ROWS, INPUTS> &D,
171 const EMat<ROWS, ROWS> &R
172 ) {
173 // Compute the innovation covariance
174 //
175 // Py = CPCᵀ + R
176 //
177 EMat<ROWS, ROWS> Py = C * P_ * C.transpose() + R;
178
179 // Compute the optimal Kalamn gain
180 //
181 // K = (Py \ CPᵀ)ᵀ
182 //
183 EMat<STATES, ROWS> K = Py.transpose().ldlt().solve(C * P_.transpose()).transpose();
184
185 // Compute the posterior mean
186 //
187 // x̂ = x̂ + K(y - (Cx̂ + Du))
188 //
189 xhat_ += K * (y - (C * xhat_ + D * u));
190
191 // Compute the posterior covariance using the Joseph form update equation
192 //
193 // P = (I - KC)P(I - KC)ᵀ + KRKᵀ
194 //
195 P_ = (EMat<STATES, STATES>::Identity() - K * C) * P_ * (EMat<STATES, STATES>::Identity() - K * C).transpose() +
196 K * R * K.transpose();
197 }
198
199 private:
200 StateVector xhat_;
201 StateMatrix P_;
202
203 StateMatrix Q_;
204 EMat<OUTPUTS, OUTPUTS> R_;
205
206 StateMatrix A_;
207 EMat<STATES, INPUTS> B_;
208 EMat<OUTPUTS, STATES> C_;
209 EMat<OUTPUTS, INPUTS> D_;
210
211 double dt_;
212};
213
214// allow using both names
215template <int STATES, int INPUTS, int OUTPUTS> using KF = KalmanFilter<STATES, INPUTS, OUTPUTS>;
Definition kalman_filter.h:24
StateMatrix P() const
Definition kalman_filter.h:76
void set_P(const StateMatrix &P)
Definition kalman_filter.h:83
const StateVector & xhat() const
Definition kalman_filter.h:88
void correct(const OutputVector &y, const InputVector &u)
Definition kalman_filter.h:141
double xhat(int i) const
Definition kalman_filter.h:95
void reset()
Definition kalman_filter.h:112
KalmanFilter(const StateMatrix &A, const InputMatrix &B, const EMat< OUTPUTS, STATES > &C, const EMat< OUTPUTS, INPUTS > &D, const StateVector &state_stddevs, const OutputVector &measurement_stddevs)
Definition kalman_filter.h:56
void set_xhat(int i, double value)
Definition kalman_filter.h:107
void set_xhat(const StateVector &xhat)
Definition kalman_filter.h:100
KalmanFilter(LinearSystem< STATES, INPUTS, OUTPUTS > &plant, const StateVector &state_stddevs, const OutputVector &measurement_stddevs)
Definition kalman_filter.h:40
void correct(const EVec< ROWS > &y, const InputVector &u, const EMat< ROWS, STATES > &C, const EMat< ROWS, INPUTS > &D, const EMat< ROWS, ROWS > &R)
Definition kalman_filter.h:169
void correct(const OutputVector &y, const InputVector &u, const EMat< OUTPUTS, OUTPUTS > &R)
Definition kalman_filter.h:152
void predict(const InputVector &u, const double &dt)
Definition kalman_filter.h:123
Definition linear_system.h:17