blob: ae92069128ec1863156845f1b0b1a287a5c6526e [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 Kuszmaul074429e2019-03-23 16:01:49 -070052 kLeftVoltageError = 7,
53 kRightVoltageError = 8 ,
54 kAngularError = 9,
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080055 };
James Kuszmaul074429e2019-03-23 16:01:49 -070056 static constexpr int kNStates = 10;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080057 static constexpr int kNInputs = 2;
58 // Number of previous samples to save.
59 static constexpr int kSaveSamples = 50;
60 // Assume that all correction steps will have kNOutputs
61 // dimensions.
62 // TODO(james): Relax this assumption; relaxing it requires
63 // figuring out how to deal with storing variable size
64 // observation matrices, though.
65 static constexpr int kNOutputs = 3;
66 // Inputs are [left_volts, right_volts]
67 typedef Eigen::Matrix<Scalar, kNInputs, 1> Input;
68 // Outputs are either:
69 // [left_encoder, right_encoder, gyro_vel]; or [heading, distance, skew] to
70 // some target. This makes it so we don't have to figure out how we store
71 // variable-size measurement updates.
72 typedef Eigen::Matrix<Scalar, kNOutputs, 1> Output;
73 typedef Eigen::Matrix<Scalar, kNStates, kNStates> StateSquare;
James Kuszmaul074429e2019-03-23 16:01:49 -070074 // State is [x_position, y_position, theta, Kalman States], where
75 // Kalman States are the states from the standard drivetrain Kalman Filter,
76 // which is: [left encoder, left ground vel, right encoder, right ground vel,
77 // left voltage error, right voltage error, angular_error], where:
78 // left/right encoder should correspond directly to encoder readings
79 // left/right velocities are the velocity of the left/right sides over the
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080080 // ground (i.e., corrected for angular_error).
James Kuszmaul074429e2019-03-23 16:01:49 -070081 // voltage errors are the difference between commanded and effective voltage,
82 // used to estimate consistent modelling errors (e.g., friction).
83 // angular error is the difference between the angular velocity as estimated
84 // by the encoders vs. estimated by the gyro, such as might be caused by
85 // wheels on one side of the drivetrain being too small or one side's
86 // wheels slipping more than the other.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080087 typedef Eigen::Matrix<Scalar, kNStates, 1> State;
88
89 // Constructs a HybridEkf for a particular drivetrain.
90 // Currently, we use the drivetrain config for modelling constants
91 // (continuous time A and B matrices) and for the noise matrices for the
92 // encoders/gyro.
93 HybridEkf(const DrivetrainConfig<Scalar> &dt_config)
94 : dt_config_(dt_config),
95 velocity_drivetrain_coefficients_(
96 dt_config.make_hybrid_drivetrain_velocity_loop()
97 .plant()
98 .coefficients()) {
99 InitializeMatrices();
100 }
101
102 // Set the initial guess of the state. Can only be called once, and before
103 // any measurement updates have occured.
104 // TODO(james): We may want to actually re-initialize and reset things on
105 // the field. Create some sort of Reset() function.
106 void ResetInitialState(::aos::monotonic_clock::time_point t,
James Kuszmaul1057ce82019-02-09 17:58:24 -0800107 const State &state, const StateSquare &P) {
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800108 observations_.clear();
109 X_hat_ = state;
James Kuszmaul074429e2019-03-23 16:01:49 -0700110 have_zeroed_encoders_ = true;
James Kuszmaul1057ce82019-02-09 17:58:24 -0800111 P_ = P;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800112 observations_.PushFromBottom(
113 {t,
114 t,
115 X_hat_,
116 P_,
117 Input::Zero(),
118 Output::Zero(),
119 {},
120 [](const State &, const Input &) { return Output::Zero(); },
121 [](const State &) {
122 return Eigen::Matrix<Scalar, kNOutputs, kNStates>::Zero();
123 },
124 Eigen::Matrix<Scalar, kNOutputs, kNOutputs>::Identity()});
125 }
126
127 // Correct with:
128 // A measurement z at time t with z = h(X_hat, U) + v where v has noise
129 // covariance R.
130 // Input U is applied from the previous timestep until time t.
131 // If t is later than any previous measurements, then U must be provided.
132 // If the measurement falls between two previous measurements, then U
133 // can be provided or not; if U is not provided, then it is filled in based
134 // on an assumption that the voltage was held constant between the time steps.
135 // TODO(james): Is it necessary to explicitly to provide a version with H as a
136 // matrix for linear cases?
137 void Correct(
138 const Output &z, const Input *U,
139 ::std::function<
140 void(const State &, const StateSquare &,
141 ::std::function<Output(const State &, const Input &)> *,
142 ::std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(
143 const State &)> *)> make_h,
144 ::std::function<Output(const State &, const Input &)> h,
145 ::std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(const State &)>
146 dhdx, const Eigen::Matrix<Scalar, kNOutputs, kNOutputs> &R,
147 aos::monotonic_clock::time_point t);
148
149 // A utility function for specifically updating with encoder and gyro
150 // measurements.
151 void UpdateEncodersAndGyro(const Scalar left_encoder,
152 const Scalar right_encoder, const Scalar gyro_rate,
153 const Input &U,
154 ::aos::monotonic_clock::time_point t) {
James Kuszmaul074429e2019-03-23 16:01:49 -0700155 // Because the check below for have_zeroed_encoders_ will add an
156 // Observation, do a check here to ensure that initialization has been
157 // performed and so there is at least one observation.
158 CHECK(!observations_.empty());
159 if (!have_zeroed_encoders_) {
160 // This logic handles ensuring that on the first encoder reading, we
161 // update the internal state for the encoders to match the reading.
162 // Otherwise, if we restart the drivetrain without restarting
163 // wpilib_interface, then we can get some obnoxious initial corrections
164 // that mess up the localization.
165 State newstate = X_hat_;
166 newstate(kLeftEncoder, 0) = left_encoder;
167 newstate(kRightEncoder, 0) = right_encoder;
168 newstate(kLeftVoltageError, 0) = 0.0;
169 newstate(kRightVoltageError, 0) = 0.0;
170 newstate(kAngularError, 0) = 0.0;
171 ResetInitialState(t, newstate, P_);
172 // We need to set have_zeroed_encoders_ after ResetInitialPosition because
173 // the reset clears have_zeroed_encoders_...
174 have_zeroed_encoders_ = true;
175 }
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800176 Output z(left_encoder, right_encoder, gyro_rate);
177 Eigen::Matrix<Scalar, kNOutputs, kNOutputs> R;
178 R.setZero();
179 R.diagonal() << encoder_noise_, encoder_noise_, gyro_noise_;
180 Correct(z, &U, {}, [this](const State &X, const Input &) {
181 return H_encoders_and_gyro_ * X;
182 },
183 [this](const State &) { return H_encoders_and_gyro_; }, R, t);
184 }
185
186 // Sundry accessor:
187 State X_hat() const { return X_hat_; }
188 Scalar X_hat(long i) const { return X_hat_(i, 0); }
189 StateSquare P() const { return P_; }
190 ::aos::monotonic_clock::time_point latest_t() const {
191 return observations_.top().t;
192 }
193
194 private:
195 struct Observation {
196 // Time when the observation was taken.
197 aos::monotonic_clock::time_point t;
198 // Time that the previous observation was taken:
199 aos::monotonic_clock::time_point prev_t;
200 // Estimate of state at previous observation time t, after accounting for
201 // the previous observation.
202 State X_hat;
203 // Noise matrix corresponding to X_hat_.
204 StateSquare P;
205 // The input applied from previous observation until time t.
206 Input U;
207 // Measurement taken at that time.
208 Output z;
209 // A function to create h and dhdx from a given position/covariance
210 // estimate. This is used by the camera to make it so that we only have to
211 // match targets once.
212 // Only called if h and dhdx are empty.
213 ::std::function<
214 void(const State &, const StateSquare &,
215 ::std::function<Output(const State &, const Input &)> *,
216 ::std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(
217 const State &)> *)> make_h;
218 // A function to calculate the expected output at a given state/input.
219 // TODO(james): For encoders/gyro, it is linear and the function call may
220 // be expensive. Potential source of optimization.
221 ::std::function<Output(const State &, const Input &)> h;
222 // The Jacobian of h with respect to x.
223 // We assume that U has no impact on the Jacobian.
224 // TODO(james): Currently, none of the users of this actually make use of
225 // the ability to have dynamic dhdx (technically, the camera code should
226 // recalculate it to be strictly correct, but I was both too lazy to do
227 // so and it seemed unnecessary). This is a potential source for future
228 // optimizations if function calls are being expensive.
229 ::std::function<
230 Eigen::Matrix<Scalar, kNOutputs, kNStates>(const State &)> dhdx;
231 // The measurement noise matrix.
232 Eigen::Matrix<Scalar, kNOutputs, kNOutputs> R;
233
234 // In order to sort the observations in the PriorityQueue object, we
235 // need a comparison function.
236 friend bool operator <(const Observation &l, const Observation &r) {
237 return l.t < r.t;
238 }
239 };
240
241 void InitializeMatrices();
242
243 StateSquare AForState(const State &X) const {
244 StateSquare A_continuous = A_continuous_;
245 const Scalar theta = X(kTheta, 0);
246 const Scalar linear_vel =
247 (X(kLeftVelocity, 0) + X(kRightVelocity, 0)) / 2.0;
248 const Scalar stheta = ::std::sin(theta);
249 const Scalar ctheta = ::std::cos(theta);
250 // X and Y derivatives
251 A_continuous(kX, kTheta) = -stheta * linear_vel;
252 A_continuous(kX, kLeftVelocity) = ctheta / 2.0;
253 A_continuous(kX, kRightVelocity) = ctheta / 2.0;
254 A_continuous(kY, kTheta) = ctheta * linear_vel;
255 A_continuous(kY, kLeftVelocity) = stheta / 2.0;
256 A_continuous(kY, kRightVelocity) = stheta / 2.0;
257 return A_continuous;
258 }
259
260 State DiffEq(const State &X, const Input &U) const {
261 State Xdot = A_continuous_ * X + B_continuous_ * U;
262 // And then we need to add on the terms for the x/y change:
263 const Scalar theta = X(kTheta, 0);
264 const Scalar linear_vel =
265 (X(kLeftVelocity, 0) + X(kRightVelocity, 0)) / 2.0;
266 const Scalar stheta = ::std::sin(theta);
267 const Scalar ctheta = ::std::cos(theta);
268 Xdot(kX, 0) = ctheta * linear_vel;
269 Xdot(kY, 0) = stheta * linear_vel;
270 return Xdot;
271 }
272
273 void PredictImpl(const Input &U, std::chrono::nanoseconds dt, State *state,
274 StateSquare *P) {
275 StateSquare A_c = AForState(*state);
276 StateSquare A_d;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800277 StateSquare Q_d;
James Kuszmaulb2a2f352019-03-02 16:59:34 -0800278 controls::DiscretizeQAFast(Q_continuous_, A_c, dt, &Q_d, &A_d);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800279
280 *state = RungeKuttaU(
281 [this](const State &X,
282 const Input &U) { return DiffEq(X, U); },
283 *state, U,
284 ::std::chrono::duration_cast<::std::chrono::duration<double>>(dt)
285 .count());
James Kuszmaulb2a2f352019-03-02 16:59:34 -0800286
287 StateSquare Ptemp = A_d * *P * A_d.transpose() + Q_d;
288 *P = Ptemp;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800289 }
290
291 void CorrectImpl(const Eigen::Matrix<Scalar, kNOutputs, kNOutputs> &R,
292 const Output &Z, const Output &expected_Z,
293 const Eigen::Matrix<Scalar, kNOutputs, kNStates> &H,
294 State *state, StateSquare *P) {
295 Output err = Z - expected_Z;
296 Eigen::Matrix<Scalar, kNStates, kNOutputs> PH = *P * H.transpose();
297 Eigen::Matrix<Scalar, kNOutputs, kNOutputs> S = H * PH + R;
298 Eigen::Matrix<Scalar, kNStates, kNOutputs> K = PH * S.inverse();
James Kuszmaulb2a2f352019-03-02 16:59:34 -0800299 *state += K * err;
300 StateSquare Ptemp = (StateSquare::Identity() - K * H) * *P;
301 *P = Ptemp;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800302 }
303
304 void ProcessObservation(Observation *obs, const std::chrono::nanoseconds dt,
305 State *state, StateSquare *P) {
306 *state = obs->X_hat;
307 *P = obs->P;
308 if (dt.count() != 0) {
309 PredictImpl(obs->U, dt, state, P);
310 }
311 if (!(obs->h && obs->dhdx)) {
312 CHECK(obs->make_h);
313 obs->make_h(*state, *P, &obs->h, &obs->dhdx);
314 }
315 CorrectImpl(obs->R, obs->z, obs->h(*state, obs->U), obs->dhdx(*state),
316 state, P);
317 }
318
319 DrivetrainConfig<Scalar> dt_config_;
320 State X_hat_;
321 StateFeedbackHybridPlantCoefficients<2, 2, 2, Scalar>
322 velocity_drivetrain_coefficients_;
323 StateSquare A_continuous_;
324 StateSquare Q_continuous_;
325 StateSquare P_;
326 Eigen::Matrix<Scalar, kNOutputs, kNStates> H_encoders_and_gyro_;
327 Scalar encoder_noise_, gyro_noise_;
328 Eigen::Matrix<Scalar, kNStates, kNInputs> B_continuous_;
329
James Kuszmaul074429e2019-03-23 16:01:49 -0700330 bool have_zeroed_encoders_ = false;
331
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800332 aos::PriorityQueue<Observation, kSaveSamples, ::std::less<Observation>>
333 observations_;
334
335 friend class testing::HybridEkfTest;
James Kuszmaul1057ce82019-02-09 17:58:24 -0800336 friend class ::y2019::control_loops::testing::ParameterizedLocalizerTest;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800337}; // class HybridEkf
338
339template <typename Scalar>
340void HybridEkf<Scalar>::Correct(
341 const Output &z, const Input *U,
342 ::std::function<
343 void(const State &, const StateSquare &,
344 ::std::function<Output(const State &, const Input &)> *,
345 ::std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(
346 const State &)> *)> make_h,
347 ::std::function<Output(const State &, const Input &)> h,
348 ::std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(const State &)>
349 dhdx, const Eigen::Matrix<Scalar, kNOutputs, kNOutputs> &R,
350 aos::monotonic_clock::time_point t) {
351 CHECK(!observations_.empty());
352 if (!observations_.full() && t < observations_.begin()->t) {
353 LOG(ERROR,
354 "Dropped an observation that was received before we "
355 "initialized.\n");
356 return;
357 }
358 auto cur_it =
359 observations_.PushFromBottom({t, t, State::Zero(), StateSquare::Zero(),
360 Input::Zero(), z, make_h, h, dhdx, R});
361 if (cur_it == observations_.end()) {
362 LOG(DEBUG,
363 "Camera dropped off of end with time of %fs; earliest observation in "
364 "queue has time of %fs.\n",
365 ::std::chrono::duration_cast<::std::chrono::duration<double>>(
366 t.time_since_epoch()).count(),
367 ::std::chrono::duration_cast<::std::chrono::duration<double>>(
368 observations_.begin()->t.time_since_epoch()).count());
369 return;
370 }
371
372 // Now we populate any state information that depends on where the
373 // observation was inserted into the queue. X_hat and P must be populated
374 // from the values present in the observation *following* this one in
375 // the queue (note that the X_hat and P that we store in each observation
376 // is the values that they held after accounting for the previous
377 // measurement and before accounting for the time between the previous and
378 // current measurement). If we appended to the end of the queue, then
379 // we need to pull from X_hat_ and P_ specifically.
380 // Furthermore, for U:
381 // -If the observation was inserted at the end, then the user must've
382 // provided U and we use it.
383 // -Otherwise, only grab U if necessary.
384 auto next_it = cur_it;
385 ++next_it;
386 if (next_it == observations_.end()) {
387 cur_it->X_hat = X_hat_;
388 cur_it->P = P_;
389 // Note that if next_it == observations_.end(), then because we already
390 // checked for !observations_.empty(), we are guaranteed to have
391 // valid prev_it.
392 auto prev_it = cur_it;
393 --prev_it;
394 cur_it->prev_t = prev_it->t;
395 // TODO(james): Figure out a saner way of handling this.
396 CHECK(U != nullptr);
397 cur_it->U = *U;
398 } else {
399 cur_it->X_hat = next_it->X_hat;
400 cur_it->P = next_it->P;
401 cur_it->prev_t = next_it->prev_t;
402 next_it->prev_t = cur_it->t;
403 cur_it->U = (U == nullptr) ? next_it->U : *U;
404 }
405 // Now we need to rerun the predict step from the previous to the new
406 // observation as well as every following correct/predict up to the current
407 // time.
408 while (true) {
409 // We use X_hat_ and P_ to store the intermediate states, and then
410 // once we reach the end they will all be up-to-date.
411 ProcessObservation(&*cur_it, cur_it->t - cur_it->prev_t, &X_hat_, &P_);
412 CHECK(X_hat_.allFinite());
413 if (next_it != observations_.end()) {
414 next_it->X_hat = X_hat_;
415 next_it->P = P_;
416 } else {
417 break;
418 }
419 ++cur_it;
420 ++next_it;
421 }
422}
423
424template <typename Scalar>
425void HybridEkf<Scalar>::InitializeMatrices() {
426 A_continuous_.setZero();
427 const Scalar diameter = 2.0 * dt_config_.robot_radius;
428 // Theta derivative
429 A_continuous_(kTheta, kLeftVelocity) = -1.0 / diameter;
430 A_continuous_(kTheta, kRightVelocity) = 1.0 / diameter;
431
432 // Encoder derivatives
433 A_continuous_(kLeftEncoder, kLeftVelocity) = 1.0;
James Kuszmaul074429e2019-03-23 16:01:49 -0700434 A_continuous_(kLeftEncoder, kAngularError) = 1.0;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800435 A_continuous_(kRightEncoder, kRightVelocity) = 1.0;
James Kuszmaul074429e2019-03-23 16:01:49 -0700436 A_continuous_(kRightEncoder, kAngularError) = -1.0;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800437
438 // Pull velocity derivatives from velocity matrices.
439 // Note that this looks really awkward (doesn't use
440 // Eigen blocks) because someone decided that the full
441 // drivetrain Kalman Filter should half a weird convention.
442 // TODO(james): Support shifting drivetrains with changing A_continuous
443 const auto &vel_coefs = velocity_drivetrain_coefficients_;
444 A_continuous_(kLeftVelocity, kLeftVelocity) = vel_coefs.A_continuous(0, 0);
445 A_continuous_(kLeftVelocity, kRightVelocity) = vel_coefs.A_continuous(0, 1);
446 A_continuous_(kRightVelocity, kLeftVelocity) = vel_coefs.A_continuous(1, 0);
447 A_continuous_(kRightVelocity, kRightVelocity) = vel_coefs.A_continuous(1, 1);
448
449 // Provide for voltage error terms:
450 B_continuous_.setZero();
451 B_continuous_.row(kLeftVelocity) = vel_coefs.B_continuous.row(0);
452 B_continuous_.row(kRightVelocity) = vel_coefs.B_continuous.row(1);
James Kuszmaul074429e2019-03-23 16:01:49 -0700453 A_continuous_.template block<kNStates, kNInputs>(0, 7) = B_continuous_;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800454
455 Q_continuous_.setZero();
456 // TODO(james): Improve estimates of process noise--e.g., X/Y noise can
James Kuszmaul1057ce82019-02-09 17:58:24 -0800457 // probably be reduced when we are stopped because you rarely jump randomly.
458 // Or maybe it's more appropriate to scale wheelspeed noise with wheelspeed,
459 // since the wheels aren't likely to slip much stopped.
James Kuszmaula5632fe2019-03-23 20:28:33 -0700460 Q_continuous_(kX, kX) = 0.002;
461 Q_continuous_(kY, kY) = 0.002;
James Kuszmaul7f1a4082019-04-14 10:50:44 -0700462 Q_continuous_(kTheta, kTheta) = 0.0001;
James Kuszmaul074429e2019-03-23 16:01:49 -0700463 Q_continuous_(kLeftEncoder, kLeftEncoder) = ::std::pow(0.15, 2.0);
464 Q_continuous_(kRightEncoder, kRightEncoder) = ::std::pow(0.15, 2.0);
465 Q_continuous_(kLeftVelocity, kLeftVelocity) = ::std::pow(0.5, 2.0);
466 Q_continuous_(kRightVelocity, kRightVelocity) = ::std::pow(0.5, 2.0);
467 Q_continuous_(kLeftVoltageError, kLeftVoltageError) = ::std::pow(10.0, 2.0);
468 Q_continuous_(kRightVoltageError, kRightVoltageError) = ::std::pow(10.0, 2.0);
469 Q_continuous_(kAngularError, kAngularError) = ::std::pow(2.0, 2.0);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800470
471 P_.setZero();
James Kuszmaul074429e2019-03-23 16:01:49 -0700472 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 -0800473
474 H_encoders_and_gyro_.setZero();
475 // Encoders are stored directly in the state matrix, so are a minor
476 // transform away.
477 H_encoders_and_gyro_(0, kLeftEncoder) = 1.0;
478 H_encoders_and_gyro_(1, kRightEncoder) = 1.0;
479 // Gyro rate is just the difference between right/left side speeds:
480 H_encoders_and_gyro_(2, kLeftVelocity) = -1.0 / diameter;
481 H_encoders_and_gyro_(2, kRightVelocity) = 1.0 / diameter;
482
483 const Eigen::Matrix<Scalar, 4, 4> R_kf_drivetrain =
484 dt_config_.make_kf_drivetrain_loop().observer().coefficients().R;
James Kuszmaul074429e2019-03-23 16:01:49 -0700485 // TODO(james): The multipliers here are hand-waving things that I put in when
486 // tuning things. I haven't yet tried messing with these values again.
James Kuszmaulc40c26e2019-03-24 16:26:43 -0700487 encoder_noise_ = 0.5 * R_kf_drivetrain(0, 0);
James Kuszmaul074429e2019-03-23 16:01:49 -0700488 gyro_noise_ = 0.1 * R_kf_drivetrain(2, 2);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800489}
490
491} // namespace drivetrain
492} // namespace control_loops
493} // namespace frc971
494
495#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_HYBRID_EKF_H_