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