blob: 119386add0c7333cb4489ba5eb208a8aff967759 [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"
James Kuszmaulfedc4612019-03-10 11:24:51 -07007#include "aos/util/math.h"
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -08008#include "frc971/control_loops/c2d.h"
9#include "frc971/control_loops/runge_kutta.h"
10#include "Eigen/Dense"
11#include "frc971/control_loops/drivetrain/drivetrain_config.h"
12
James Kuszmaul1057ce82019-02-09 17:58:24 -080013namespace y2019 {
14namespace control_loops {
15namespace testing {
16class ParameterizedLocalizerTest;
17} // namespace testing
18} // namespace control_loops
19} // namespace y2019
20
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080021namespace frc971 {
22namespace control_loops {
23namespace drivetrain {
24
25namespace testing {
26class HybridEkfTest;
27}
28
29// HybridEkf is an EKF for use in robot localization. It is currently
30// coded for use with drivetrains in particular, and so the states and inputs
31// are chosen as such.
32// The "Hybrid" part of the name refers to the fact that it can take in
33// measurements with variable time-steps.
34// measurements can also have been taken in the past and we maintain a buffer
35// so that we can replay the kalman filter whenever we get an old measurement.
36// Currently, this class provides the necessary utilities for doing
37// measurement updates with an encoder/gyro as well as a more generic
38// update function that can be used for arbitrary nonlinear updates (presumably
39// a camera update).
40template <typename Scalar = double>
41class HybridEkf {
42 public:
43 // An enum specifying what each index in the state vector is for.
44 enum StateIdx {
45 kX = 0,
46 kY = 1,
47 kTheta = 2,
48 kLeftEncoder = 3,
49 kLeftVelocity = 4,
50 kRightEncoder = 5,
51 kRightVelocity = 6,
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080052 };
James Kuszmaulfedc4612019-03-10 11:24:51 -070053 static constexpr int kNStates = 7;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080054 static constexpr int kNInputs = 2;
55 // Number of previous samples to save.
56 static constexpr int kSaveSamples = 50;
57 // Assume that all correction steps will have kNOutputs
58 // dimensions.
59 // TODO(james): Relax this assumption; relaxing it requires
60 // figuring out how to deal with storing variable size
61 // observation matrices, though.
62 static constexpr int kNOutputs = 3;
63 // Inputs are [left_volts, right_volts]
64 typedef Eigen::Matrix<Scalar, kNInputs, 1> Input;
65 // Outputs are either:
66 // [left_encoder, right_encoder, gyro_vel]; or [heading, distance, skew] to
67 // some target. This makes it so we don't have to figure out how we store
68 // variable-size measurement updates.
69 typedef Eigen::Matrix<Scalar, kNOutputs, 1> Output;
70 typedef Eigen::Matrix<Scalar, kNStates, kNStates> StateSquare;
James Kuszmaulfedc4612019-03-10 11:24:51 -070071 // State is [x_position, y_position, theta, left encoder, left ground vel,
72 // right encoder, right ground vel]. left/right encoder should correspond
73 // directly to encoder readings left/right velocities are the velocity of the
74 // left/right sides over the
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080075 // ground (i.e., corrected for angular_error).
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080076 typedef Eigen::Matrix<Scalar, kNStates, 1> State;
77
78 // Constructs a HybridEkf for a particular drivetrain.
79 // Currently, we use the drivetrain config for modelling constants
80 // (continuous time A and B matrices) and for the noise matrices for the
81 // encoders/gyro.
82 HybridEkf(const DrivetrainConfig<Scalar> &dt_config)
83 : dt_config_(dt_config),
84 velocity_drivetrain_coefficients_(
85 dt_config.make_hybrid_drivetrain_velocity_loop()
86 .plant()
87 .coefficients()) {
88 InitializeMatrices();
89 }
90
91 // Set the initial guess of the state. Can only be called once, and before
92 // any measurement updates have occured.
93 // TODO(james): We may want to actually re-initialize and reset things on
94 // the field. Create some sort of Reset() function.
95 void ResetInitialState(::aos::monotonic_clock::time_point t,
James Kuszmaul1057ce82019-02-09 17:58:24 -080096 const State &state, const StateSquare &P) {
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080097 observations_.clear();
98 X_hat_ = state;
James Kuszmaul1057ce82019-02-09 17:58:24 -080099 P_ = P;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800100 observations_.PushFromBottom(
101 {t,
102 t,
103 X_hat_,
104 P_,
105 Input::Zero(),
106 Output::Zero(),
107 {},
108 [](const State &, const Input &) { return Output::Zero(); },
109 [](const State &) {
110 return Eigen::Matrix<Scalar, kNOutputs, kNStates>::Zero();
111 },
112 Eigen::Matrix<Scalar, kNOutputs, kNOutputs>::Identity()});
113 }
114
115 // Correct with:
116 // A measurement z at time t with z = h(X_hat, U) + v where v has noise
117 // covariance R.
118 // Input U is applied from the previous timestep until time t.
119 // If t is later than any previous measurements, then U must be provided.
120 // If the measurement falls between two previous measurements, then U
121 // can be provided or not; if U is not provided, then it is filled in based
122 // on an assumption that the voltage was held constant between the time steps.
123 // TODO(james): Is it necessary to explicitly to provide a version with H as a
124 // matrix for linear cases?
125 void Correct(
126 const Output &z, const Input *U,
127 ::std::function<
128 void(const State &, const StateSquare &,
129 ::std::function<Output(const State &, const Input &)> *,
130 ::std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(
131 const State &)> *)> make_h,
132 ::std::function<Output(const State &, const Input &)> h,
133 ::std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(const State &)>
134 dhdx, const Eigen::Matrix<Scalar, kNOutputs, kNOutputs> &R,
135 aos::monotonic_clock::time_point t);
136
137 // A utility function for specifically updating with encoder and gyro
138 // measurements.
139 void UpdateEncodersAndGyro(const Scalar left_encoder,
140 const Scalar right_encoder, const Scalar gyro_rate,
141 const Input &U,
142 ::aos::monotonic_clock::time_point t) {
143 Output z(left_encoder, right_encoder, gyro_rate);
144 Eigen::Matrix<Scalar, kNOutputs, kNOutputs> R;
145 R.setZero();
146 R.diagonal() << encoder_noise_, encoder_noise_, gyro_noise_;
147 Correct(z, &U, {}, [this](const State &X, const Input &) {
148 return H_encoders_and_gyro_ * X;
149 },
150 [this](const State &) { return H_encoders_and_gyro_; }, R, t);
151 }
152
153 // Sundry accessor:
154 State X_hat() const { return X_hat_; }
155 Scalar X_hat(long i) const { return X_hat_(i, 0); }
156 StateSquare P() const { return P_; }
157 ::aos::monotonic_clock::time_point latest_t() const {
158 return observations_.top().t;
159 }
160
161 private:
162 struct Observation {
163 // Time when the observation was taken.
164 aos::monotonic_clock::time_point t;
165 // Time that the previous observation was taken:
166 aos::monotonic_clock::time_point prev_t;
167 // Estimate of state at previous observation time t, after accounting for
168 // the previous observation.
169 State X_hat;
170 // Noise matrix corresponding to X_hat_.
171 StateSquare P;
172 // The input applied from previous observation until time t.
173 Input U;
174 // Measurement taken at that time.
175 Output z;
176 // A function to create h and dhdx from a given position/covariance
177 // estimate. This is used by the camera to make it so that we only have to
178 // match targets once.
179 // Only called if h and dhdx are empty.
180 ::std::function<
181 void(const State &, const StateSquare &,
182 ::std::function<Output(const State &, const Input &)> *,
183 ::std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(
184 const State &)> *)> make_h;
185 // A function to calculate the expected output at a given state/input.
186 // TODO(james): For encoders/gyro, it is linear and the function call may
187 // be expensive. Potential source of optimization.
188 ::std::function<Output(const State &, const Input &)> h;
189 // The Jacobian of h with respect to x.
190 // We assume that U has no impact on the Jacobian.
191 // TODO(james): Currently, none of the users of this actually make use of
192 // the ability to have dynamic dhdx (technically, the camera code should
193 // recalculate it to be strictly correct, but I was both too lazy to do
194 // so and it seemed unnecessary). This is a potential source for future
195 // optimizations if function calls are being expensive.
196 ::std::function<
197 Eigen::Matrix<Scalar, kNOutputs, kNStates>(const State &)> dhdx;
198 // The measurement noise matrix.
199 Eigen::Matrix<Scalar, kNOutputs, kNOutputs> R;
200
201 // In order to sort the observations in the PriorityQueue object, we
202 // need a comparison function.
203 friend bool operator <(const Observation &l, const Observation &r) {
204 return l.t < r.t;
205 }
206 };
207
208 void InitializeMatrices();
209
210 StateSquare AForState(const State &X) const {
211 StateSquare A_continuous = A_continuous_;
212 const Scalar theta = X(kTheta, 0);
213 const Scalar linear_vel =
214 (X(kLeftVelocity, 0) + X(kRightVelocity, 0)) / 2.0;
215 const Scalar stheta = ::std::sin(theta);
216 const Scalar ctheta = ::std::cos(theta);
217 // X and Y derivatives
218 A_continuous(kX, kTheta) = -stheta * linear_vel;
219 A_continuous(kX, kLeftVelocity) = ctheta / 2.0;
220 A_continuous(kX, kRightVelocity) = ctheta / 2.0;
221 A_continuous(kY, kTheta) = ctheta * linear_vel;
222 A_continuous(kY, kLeftVelocity) = stheta / 2.0;
223 A_continuous(kY, kRightVelocity) = stheta / 2.0;
224 return A_continuous;
225 }
226
227 State DiffEq(const State &X, const Input &U) const {
228 State Xdot = A_continuous_ * X + B_continuous_ * U;
229 // And then we need to add on the terms for the x/y change:
230 const Scalar theta = X(kTheta, 0);
231 const Scalar linear_vel =
232 (X(kLeftVelocity, 0) + X(kRightVelocity, 0)) / 2.0;
233 const Scalar stheta = ::std::sin(theta);
234 const Scalar ctheta = ::std::cos(theta);
235 Xdot(kX, 0) = ctheta * linear_vel;
236 Xdot(kY, 0) = stheta * linear_vel;
237 return Xdot;
238 }
239
240 void PredictImpl(const Input &U, std::chrono::nanoseconds dt, State *state,
241 StateSquare *P) {
242 StateSquare A_c = AForState(*state);
243 StateSquare A_d;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800244 StateSquare Q_d;
James Kuszmaulb2a2f352019-03-02 16:59:34 -0800245 controls::DiscretizeQAFast(Q_continuous_, A_c, dt, &Q_d, &A_d);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800246
247 *state = RungeKuttaU(
248 [this](const State &X,
249 const Input &U) { return DiffEq(X, U); },
250 *state, U,
251 ::std::chrono::duration_cast<::std::chrono::duration<double>>(dt)
252 .count());
James Kuszmaulb2a2f352019-03-02 16:59:34 -0800253
254 StateSquare Ptemp = A_d * *P * A_d.transpose() + Q_d;
255 *P = Ptemp;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800256 }
257
258 void CorrectImpl(const Eigen::Matrix<Scalar, kNOutputs, kNOutputs> &R,
259 const Output &Z, const Output &expected_Z,
260 const Eigen::Matrix<Scalar, kNOutputs, kNStates> &H,
261 State *state, StateSquare *P) {
262 Output err = Z - expected_Z;
263 Eigen::Matrix<Scalar, kNStates, kNOutputs> PH = *P * H.transpose();
264 Eigen::Matrix<Scalar, kNOutputs, kNOutputs> S = H * PH + R;
265 Eigen::Matrix<Scalar, kNStates, kNOutputs> K = PH * S.inverse();
James Kuszmaulb2a2f352019-03-02 16:59:34 -0800266 *state += K * err;
267 StateSquare Ptemp = (StateSquare::Identity() - K * H) * *P;
268 *P = Ptemp;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800269 }
270
271 void ProcessObservation(Observation *obs, const std::chrono::nanoseconds dt,
272 State *state, StateSquare *P) {
273 *state = obs->X_hat;
274 *P = obs->P;
275 if (dt.count() != 0) {
276 PredictImpl(obs->U, dt, state, P);
277 }
278 if (!(obs->h && obs->dhdx)) {
279 CHECK(obs->make_h);
280 obs->make_h(*state, *P, &obs->h, &obs->dhdx);
281 }
282 CorrectImpl(obs->R, obs->z, obs->h(*state, obs->U), obs->dhdx(*state),
283 state, P);
284 }
285
286 DrivetrainConfig<Scalar> dt_config_;
287 State X_hat_;
288 StateFeedbackHybridPlantCoefficients<2, 2, 2, Scalar>
289 velocity_drivetrain_coefficients_;
290 StateSquare A_continuous_;
291 StateSquare Q_continuous_;
292 StateSquare P_;
293 Eigen::Matrix<Scalar, kNOutputs, kNStates> H_encoders_and_gyro_;
294 Scalar encoder_noise_, gyro_noise_;
295 Eigen::Matrix<Scalar, kNStates, kNInputs> B_continuous_;
296
297 aos::PriorityQueue<Observation, kSaveSamples, ::std::less<Observation>>
298 observations_;
299
300 friend class testing::HybridEkfTest;
James Kuszmaul1057ce82019-02-09 17:58:24 -0800301 friend class ::y2019::control_loops::testing::ParameterizedLocalizerTest;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800302}; // 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;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800399 A_continuous_(kRightEncoder, kRightVelocity) = 1.0;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800400
401 // Pull velocity derivatives from velocity matrices.
402 // Note that this looks really awkward (doesn't use
403 // Eigen blocks) because someone decided that the full
404 // drivetrain Kalman Filter should half a weird convention.
405 // TODO(james): Support shifting drivetrains with changing A_continuous
406 const auto &vel_coefs = velocity_drivetrain_coefficients_;
407 A_continuous_(kLeftVelocity, kLeftVelocity) = vel_coefs.A_continuous(0, 0);
408 A_continuous_(kLeftVelocity, kRightVelocity) = vel_coefs.A_continuous(0, 1);
409 A_continuous_(kRightVelocity, kLeftVelocity) = vel_coefs.A_continuous(1, 0);
410 A_continuous_(kRightVelocity, kRightVelocity) = vel_coefs.A_continuous(1, 1);
411
412 // Provide for voltage error terms:
413 B_continuous_.setZero();
414 B_continuous_.row(kLeftVelocity) = vel_coefs.B_continuous.row(0);
415 B_continuous_.row(kRightVelocity) = vel_coefs.B_continuous.row(1);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800416
417 Q_continuous_.setZero();
418 // TODO(james): Improve estimates of process noise--e.g., X/Y noise can
James Kuszmaul1057ce82019-02-09 17:58:24 -0800419 // probably be reduced when we are stopped because you rarely jump randomly.
420 // Or maybe it's more appropriate to scale wheelspeed noise with wheelspeed,
421 // since the wheels aren't likely to slip much stopped.
James Kuszmaulfedc4612019-03-10 11:24:51 -0700422 Q_continuous_(kX, kX) = 0.01;
423 Q_continuous_(kY, kY) = 0.01;
424 Q_continuous_(kTheta, kTheta) = 0.0002;
425 Q_continuous_(kLeftEncoder, kLeftEncoder) = ::std::pow(0.03, 2.0);
426 Q_continuous_(kRightEncoder, kRightEncoder) = ::std::pow(0.03, 2.0);
427 Q_continuous_(kLeftVelocity, kLeftVelocity) = ::std::pow(0.1, 2.0);
428 Q_continuous_(kRightVelocity, kRightVelocity) = ::std::pow(0.1, 2.0);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800429
430 P_.setZero();
James Kuszmaulfedc4612019-03-10 11:24:51 -0700431 P_.diagonal() << 0.1, 0.1, 0.01, 0.02, 0.01, 0.02, 0.01;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800432
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_