blob: 245e77253681f176ec7ca5c16acb532b7cc8e582 [file] [log] [blame]
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -08001#ifndef FRC971_CONTROL_LOOPS_DRIVETRAIN_HYBRID_EKF_H_
2#define FRC971_CONTROL_LOOPS_DRIVETRAIN_HYBRID_EKF_H_
3
4#include <chrono>
5
6#include "aos/containers/priority_queue.h"
7#include "frc971/control_loops/c2d.h"
8#include "frc971/control_loops/runge_kutta.h"
9#include "Eigen/Dense"
10#include "frc971/control_loops/drivetrain/drivetrain_config.h"
11
12namespace frc971 {
13namespace control_loops {
14namespace drivetrain {
15
16namespace testing {
17class HybridEkfTest;
18}
19
20// HybridEkf is an EKF for use in robot localization. It is currently
21// coded for use with drivetrains in particular, and so the states and inputs
22// are chosen as such.
23// The "Hybrid" part of the name refers to the fact that it can take in
24// measurements with variable time-steps.
25// measurements can also have been taken in the past and we maintain a buffer
26// so that we can replay the kalman filter whenever we get an old measurement.
27// Currently, this class provides the necessary utilities for doing
28// measurement updates with an encoder/gyro as well as a more generic
29// update function that can be used for arbitrary nonlinear updates (presumably
30// a camera update).
31template <typename Scalar = double>
32class HybridEkf {
33 public:
34 // An enum specifying what each index in the state vector is for.
35 enum StateIdx {
36 kX = 0,
37 kY = 1,
38 kTheta = 2,
39 kLeftEncoder = 3,
40 kLeftVelocity = 4,
41 kRightEncoder = 5,
42 kRightVelocity = 6,
43 kLeftVoltageError = 7,
44 kRightVoltageError = 8 ,
45 kAngularError = 9,
46 };
47 static constexpr int kNStates = 10;
48 static constexpr int kNInputs = 2;
49 // Number of previous samples to save.
50 static constexpr int kSaveSamples = 50;
51 // Assume that all correction steps will have kNOutputs
52 // dimensions.
53 // TODO(james): Relax this assumption; relaxing it requires
54 // figuring out how to deal with storing variable size
55 // observation matrices, though.
56 static constexpr int kNOutputs = 3;
57 // Inputs are [left_volts, right_volts]
58 typedef Eigen::Matrix<Scalar, kNInputs, 1> Input;
59 // Outputs are either:
60 // [left_encoder, right_encoder, gyro_vel]; or [heading, distance, skew] to
61 // some target. This makes it so we don't have to figure out how we store
62 // variable-size measurement updates.
63 typedef Eigen::Matrix<Scalar, kNOutputs, 1> Output;
64 typedef Eigen::Matrix<Scalar, kNStates, kNStates> StateSquare;
65 // State is [x_position, y_position, theta, Kalman States], where
66 // Kalman States are the states from the standard drivetrain Kalman Filter,
67 // which is: [left encoder, left ground vel, right encoder, right ground vel,
68 // left voltage error, right voltage error, angular_error], where:
69 // left/right encoder should correspond directly to encoder readings
70 // left/right velocities are the velocity of the left/right sides over the
71 // ground (i.e., corrected for angular_error).
72 // voltage errors are the difference between commanded and effective voltage,
73 // used to estimate consistent modelling errors (e.g., friction).
74 // angular error is the difference between the angular velocity as estimated
75 // by the encoders vs. estimated by the gyro, such as might be caused by
76 // wheels on one side of the drivetrain being too small or one side's
77 // wheels slipping more than the other.
78 typedef Eigen::Matrix<Scalar, kNStates, 1> State;
79
80 // Constructs a HybridEkf for a particular drivetrain.
81 // Currently, we use the drivetrain config for modelling constants
82 // (continuous time A and B matrices) and for the noise matrices for the
83 // encoders/gyro.
84 HybridEkf(const DrivetrainConfig<Scalar> &dt_config)
85 : dt_config_(dt_config),
86 velocity_drivetrain_coefficients_(
87 dt_config.make_hybrid_drivetrain_velocity_loop()
88 .plant()
89 .coefficients()) {
90 InitializeMatrices();
91 }
92
93 // Set the initial guess of the state. Can only be called once, and before
94 // any measurement updates have occured.
95 // TODO(james): We may want to actually re-initialize and reset things on
96 // the field. Create some sort of Reset() function.
97 void ResetInitialState(::aos::monotonic_clock::time_point t,
98 const State &state) {
99 observations_.clear();
100 X_hat_ = state;
101 observations_.PushFromBottom(
102 {t,
103 t,
104 X_hat_,
105 P_,
106 Input::Zero(),
107 Output::Zero(),
108 {},
109 [](const State &, const Input &) { return Output::Zero(); },
110 [](const State &) {
111 return Eigen::Matrix<Scalar, kNOutputs, kNStates>::Zero();
112 },
113 Eigen::Matrix<Scalar, kNOutputs, kNOutputs>::Identity()});
114 }
115
116 // Correct with:
117 // A measurement z at time t with z = h(X_hat, U) + v where v has noise
118 // covariance R.
119 // Input U is applied from the previous timestep until time t.
120 // If t is later than any previous measurements, then U must be provided.
121 // If the measurement falls between two previous measurements, then U
122 // can be provided or not; if U is not provided, then it is filled in based
123 // on an assumption that the voltage was held constant between the time steps.
124 // TODO(james): Is it necessary to explicitly to provide a version with H as a
125 // matrix for linear cases?
126 void Correct(
127 const Output &z, const Input *U,
128 ::std::function<
129 void(const State &, const StateSquare &,
130 ::std::function<Output(const State &, const Input &)> *,
131 ::std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(
132 const State &)> *)> make_h,
133 ::std::function<Output(const State &, const Input &)> h,
134 ::std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(const State &)>
135 dhdx, const Eigen::Matrix<Scalar, kNOutputs, kNOutputs> &R,
136 aos::monotonic_clock::time_point t);
137
138 // A utility function for specifically updating with encoder and gyro
139 // measurements.
140 void UpdateEncodersAndGyro(const Scalar left_encoder,
141 const Scalar right_encoder, const Scalar gyro_rate,
142 const Input &U,
143 ::aos::monotonic_clock::time_point t) {
144 Output z(left_encoder, right_encoder, gyro_rate);
145 Eigen::Matrix<Scalar, kNOutputs, kNOutputs> R;
146 R.setZero();
147 R.diagonal() << encoder_noise_, encoder_noise_, gyro_noise_;
148 Correct(z, &U, {}, [this](const State &X, const Input &) {
149 return H_encoders_and_gyro_ * X;
150 },
151 [this](const State &) { return H_encoders_and_gyro_; }, R, t);
152 }
153
154 // Sundry accessor:
155 State X_hat() const { return X_hat_; }
156 Scalar X_hat(long i) const { return X_hat_(i, 0); }
157 StateSquare P() const { return P_; }
158 ::aos::monotonic_clock::time_point latest_t() const {
159 return observations_.top().t;
160 }
161
162 private:
163 struct Observation {
164 // Time when the observation was taken.
165 aos::monotonic_clock::time_point t;
166 // Time that the previous observation was taken:
167 aos::monotonic_clock::time_point prev_t;
168 // Estimate of state at previous observation time t, after accounting for
169 // the previous observation.
170 State X_hat;
171 // Noise matrix corresponding to X_hat_.
172 StateSquare P;
173 // The input applied from previous observation until time t.
174 Input U;
175 // Measurement taken at that time.
176 Output z;
177 // A function to create h and dhdx from a given position/covariance
178 // estimate. This is used by the camera to make it so that we only have to
179 // match targets once.
180 // Only called if h and dhdx are empty.
181 ::std::function<
182 void(const State &, const StateSquare &,
183 ::std::function<Output(const State &, const Input &)> *,
184 ::std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(
185 const State &)> *)> make_h;
186 // A function to calculate the expected output at a given state/input.
187 // TODO(james): For encoders/gyro, it is linear and the function call may
188 // be expensive. Potential source of optimization.
189 ::std::function<Output(const State &, const Input &)> h;
190 // The Jacobian of h with respect to x.
191 // We assume that U has no impact on the Jacobian.
192 // TODO(james): Currently, none of the users of this actually make use of
193 // the ability to have dynamic dhdx (technically, the camera code should
194 // recalculate it to be strictly correct, but I was both too lazy to do
195 // so and it seemed unnecessary). This is a potential source for future
196 // optimizations if function calls are being expensive.
197 ::std::function<
198 Eigen::Matrix<Scalar, kNOutputs, kNStates>(const State &)> dhdx;
199 // The measurement noise matrix.
200 Eigen::Matrix<Scalar, kNOutputs, kNOutputs> R;
201
202 // In order to sort the observations in the PriorityQueue object, we
203 // need a comparison function.
204 friend bool operator <(const Observation &l, const Observation &r) {
205 return l.t < r.t;
206 }
207 };
208
209 void InitializeMatrices();
210
211 StateSquare AForState(const State &X) const {
212 StateSquare A_continuous = A_continuous_;
213 const Scalar theta = X(kTheta, 0);
214 const Scalar linear_vel =
215 (X(kLeftVelocity, 0) + X(kRightVelocity, 0)) / 2.0;
216 const Scalar stheta = ::std::sin(theta);
217 const Scalar ctheta = ::std::cos(theta);
218 // X and Y derivatives
219 A_continuous(kX, kTheta) = -stheta * linear_vel;
220 A_continuous(kX, kLeftVelocity) = ctheta / 2.0;
221 A_continuous(kX, kRightVelocity) = ctheta / 2.0;
222 A_continuous(kY, kTheta) = ctheta * linear_vel;
223 A_continuous(kY, kLeftVelocity) = stheta / 2.0;
224 A_continuous(kY, kRightVelocity) = stheta / 2.0;
225 return A_continuous;
226 }
227
228 State DiffEq(const State &X, const Input &U) const {
229 State Xdot = A_continuous_ * X + B_continuous_ * U;
230 // And then we need to add on the terms for the x/y change:
231 const Scalar theta = X(kTheta, 0);
232 const Scalar linear_vel =
233 (X(kLeftVelocity, 0) + X(kRightVelocity, 0)) / 2.0;
234 const Scalar stheta = ::std::sin(theta);
235 const Scalar ctheta = ::std::cos(theta);
236 Xdot(kX, 0) = ctheta * linear_vel;
237 Xdot(kY, 0) = stheta * linear_vel;
238 return Xdot;
239 }
240
241 void PredictImpl(const Input &U, std::chrono::nanoseconds dt, State *state,
242 StateSquare *P) {
243 StateSquare A_c = AForState(*state);
244 StateSquare A_d;
245 Eigen::Matrix<Scalar, kNStates, 0> dummy_B;
246 controls::C2D<Scalar, kNStates, 0>(
247 A_c, Eigen::Matrix<Scalar, kNStates, 0>::Zero(), dt, &A_d, &dummy_B);
248 StateSquare Q_d;
249 controls::DiscretizeQ(Q_continuous_, A_c, dt, &Q_d);
250 *P = A_d * *P * A_d.transpose() + Q_d;
251
252 *state = RungeKuttaU(
253 [this](const State &X,
254 const Input &U) { return DiffEq(X, U); },
255 *state, U,
256 ::std::chrono::duration_cast<::std::chrono::duration<double>>(dt)
257 .count());
258 }
259
260 void CorrectImpl(const Eigen::Matrix<Scalar, kNOutputs, kNOutputs> &R,
261 const Output &Z, const Output &expected_Z,
262 const Eigen::Matrix<Scalar, kNOutputs, kNStates> &H,
263 State *state, StateSquare *P) {
264 Output err = Z - expected_Z;
265 Eigen::Matrix<Scalar, kNStates, kNOutputs> PH = *P * H.transpose();
266 Eigen::Matrix<Scalar, kNOutputs, kNOutputs> S = H * PH + R;
267 Eigen::Matrix<Scalar, kNStates, kNOutputs> K = PH * S.inverse();
268 *state = *state + K * err;
269 *P = (StateSquare::Identity() - K * H) * *P;
270 }
271
272 void ProcessObservation(Observation *obs, const std::chrono::nanoseconds dt,
273 State *state, StateSquare *P) {
274 *state = obs->X_hat;
275 *P = obs->P;
276 if (dt.count() != 0) {
277 PredictImpl(obs->U, dt, state, P);
278 }
279 if (!(obs->h && obs->dhdx)) {
280 CHECK(obs->make_h);
281 obs->make_h(*state, *P, &obs->h, &obs->dhdx);
282 }
283 CorrectImpl(obs->R, obs->z, obs->h(*state, obs->U), obs->dhdx(*state),
284 state, P);
285 }
286
287 DrivetrainConfig<Scalar> dt_config_;
288 State X_hat_;
289 StateFeedbackHybridPlantCoefficients<2, 2, 2, Scalar>
290 velocity_drivetrain_coefficients_;
291 StateSquare A_continuous_;
292 StateSquare Q_continuous_;
293 StateSquare P_;
294 Eigen::Matrix<Scalar, kNOutputs, kNStates> H_encoders_and_gyro_;
295 Scalar encoder_noise_, gyro_noise_;
296 Eigen::Matrix<Scalar, kNStates, kNInputs> B_continuous_;
297
298 aos::PriorityQueue<Observation, kSaveSamples, ::std::less<Observation>>
299 observations_;
300
301 friend class testing::HybridEkfTest;
302}; // class HybridEkf
303
304template <typename Scalar>
305void HybridEkf<Scalar>::Correct(
306 const Output &z, const Input *U,
307 ::std::function<
308 void(const State &, const StateSquare &,
309 ::std::function<Output(const State &, const Input &)> *,
310 ::std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(
311 const State &)> *)> make_h,
312 ::std::function<Output(const State &, const Input &)> h,
313 ::std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(const State &)>
314 dhdx, const Eigen::Matrix<Scalar, kNOutputs, kNOutputs> &R,
315 aos::monotonic_clock::time_point t) {
316 CHECK(!observations_.empty());
317 if (!observations_.full() && t < observations_.begin()->t) {
318 LOG(ERROR,
319 "Dropped an observation that was received before we "
320 "initialized.\n");
321 return;
322 }
323 auto cur_it =
324 observations_.PushFromBottom({t, t, State::Zero(), StateSquare::Zero(),
325 Input::Zero(), z, make_h, h, dhdx, R});
326 if (cur_it == observations_.end()) {
327 LOG(DEBUG,
328 "Camera dropped off of end with time of %fs; earliest observation in "
329 "queue has time of %fs.\n",
330 ::std::chrono::duration_cast<::std::chrono::duration<double>>(
331 t.time_since_epoch()).count(),
332 ::std::chrono::duration_cast<::std::chrono::duration<double>>(
333 observations_.begin()->t.time_since_epoch()).count());
334 return;
335 }
336
337 // Now we populate any state information that depends on where the
338 // observation was inserted into the queue. X_hat and P must be populated
339 // from the values present in the observation *following* this one in
340 // the queue (note that the X_hat and P that we store in each observation
341 // is the values that they held after accounting for the previous
342 // measurement and before accounting for the time between the previous and
343 // current measurement). If we appended to the end of the queue, then
344 // we need to pull from X_hat_ and P_ specifically.
345 // Furthermore, for U:
346 // -If the observation was inserted at the end, then the user must've
347 // provided U and we use it.
348 // -Otherwise, only grab U if necessary.
349 auto next_it = cur_it;
350 ++next_it;
351 if (next_it == observations_.end()) {
352 cur_it->X_hat = X_hat_;
353 cur_it->P = P_;
354 // Note that if next_it == observations_.end(), then because we already
355 // checked for !observations_.empty(), we are guaranteed to have
356 // valid prev_it.
357 auto prev_it = cur_it;
358 --prev_it;
359 cur_it->prev_t = prev_it->t;
360 // TODO(james): Figure out a saner way of handling this.
361 CHECK(U != nullptr);
362 cur_it->U = *U;
363 } else {
364 cur_it->X_hat = next_it->X_hat;
365 cur_it->P = next_it->P;
366 cur_it->prev_t = next_it->prev_t;
367 next_it->prev_t = cur_it->t;
368 cur_it->U = (U == nullptr) ? next_it->U : *U;
369 }
370 // Now we need to rerun the predict step from the previous to the new
371 // observation as well as every following correct/predict up to the current
372 // time.
373 while (true) {
374 // We use X_hat_ and P_ to store the intermediate states, and then
375 // once we reach the end they will all be up-to-date.
376 ProcessObservation(&*cur_it, cur_it->t - cur_it->prev_t, &X_hat_, &P_);
377 CHECK(X_hat_.allFinite());
378 if (next_it != observations_.end()) {
379 next_it->X_hat = X_hat_;
380 next_it->P = P_;
381 } else {
382 break;
383 }
384 ++cur_it;
385 ++next_it;
386 }
387}
388
389template <typename Scalar>
390void HybridEkf<Scalar>::InitializeMatrices() {
391 A_continuous_.setZero();
392 const Scalar diameter = 2.0 * dt_config_.robot_radius;
393 // Theta derivative
394 A_continuous_(kTheta, kLeftVelocity) = -1.0 / diameter;
395 A_continuous_(kTheta, kRightVelocity) = 1.0 / diameter;
396
397 // Encoder derivatives
398 A_continuous_(kLeftEncoder, kLeftVelocity) = 1.0;
399 A_continuous_(kLeftEncoder, kAngularError) = 1.0;
400 A_continuous_(kRightEncoder, kRightVelocity) = 1.0;
401 A_continuous_(kRightEncoder, kAngularError) = -1.0;
402
403 // Pull velocity derivatives from velocity matrices.
404 // Note that this looks really awkward (doesn't use
405 // Eigen blocks) because someone decided that the full
406 // drivetrain Kalman Filter should half a weird convention.
407 // TODO(james): Support shifting drivetrains with changing A_continuous
408 const auto &vel_coefs = velocity_drivetrain_coefficients_;
409 A_continuous_(kLeftVelocity, kLeftVelocity) = vel_coefs.A_continuous(0, 0);
410 A_continuous_(kLeftVelocity, kRightVelocity) = vel_coefs.A_continuous(0, 1);
411 A_continuous_(kRightVelocity, kLeftVelocity) = vel_coefs.A_continuous(1, 0);
412 A_continuous_(kRightVelocity, kRightVelocity) = vel_coefs.A_continuous(1, 1);
413
414 // Provide for voltage error terms:
415 B_continuous_.setZero();
416 B_continuous_.row(kLeftVelocity) = vel_coefs.B_continuous.row(0);
417 B_continuous_.row(kRightVelocity) = vel_coefs.B_continuous.row(1);
418 A_continuous_.template block<kNStates, kNInputs>(0, 7) = B_continuous_;
419
420 Q_continuous_.setZero();
421 // TODO(james): Improve estimates of process noise--e.g., X/Y noise can
422 // probably be reduced because we rarely randomly jump in space, but maybe
423 // wheel speed noise should increase due to likelihood of slippage.
424 Q_continuous_(kX, kX) = 0.005;
425 Q_continuous_(kY, kY) = 0.005;
426 Q_continuous_(kTheta, kTheta) = 0.001;
427 Q_continuous_.template block<7, 7>(3, 3) =
428 dt_config_.make_kf_drivetrain_loop().observer().coefficients().Q;
429
430 P_.setZero();
431 P_.diagonal() << 1, 1, 1, 0.5, 0.1, 0.5, 0.1, 1, 1, 1;
432
433 H_encoders_and_gyro_.setZero();
434 // Encoders are stored directly in the state matrix, so are a minor
435 // transform away.
436 H_encoders_and_gyro_(0, kLeftEncoder) = 1.0;
437 H_encoders_and_gyro_(1, kRightEncoder) = 1.0;
438 // Gyro rate is just the difference between right/left side speeds:
439 H_encoders_and_gyro_(2, kLeftVelocity) = -1.0 / diameter;
440 H_encoders_and_gyro_(2, kRightVelocity) = 1.0 / diameter;
441
442 const Eigen::Matrix<Scalar, 4, 4> R_kf_drivetrain =
443 dt_config_.make_kf_drivetrain_loop().observer().coefficients().R;
444 encoder_noise_ = R_kf_drivetrain(0, 0);
445 gyro_noise_ = R_kf_drivetrain(2, 2);
446}
447
448} // namespace drivetrain
449} // namespace control_loops
450} // namespace frc971
451
452#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_HYBRID_EKF_H_