blob: 16b0b61bd995dffd8424589b99640707b2fceaed [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
James Kuszmaul651fc3f2019-05-15 21:14:25 -07006#include "Eigen/Dense"
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -08007#include "aos/containers/priority_queue.h"
James Kuszmaulfedc4612019-03-10 11:24:51 -07008#include "aos/util/math.h"
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -08009#include "frc971/control_loops/c2d.h"
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080010#include "frc971/control_loops/drivetrain/drivetrain_config.h"
James Kuszmaul651fc3f2019-05-15 21:14:25 -070011#include "frc971/control_loops/runge_kutta.h"
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080012
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,
James Kuszmaul651fc3f2019-05-15 21:14:25 -070053 kRightVoltageError = 8,
James Kuszmaul074429e2019-03-23 16:01:49 -070054 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>(
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700143 const State &)> *)>
144 make_h,
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800145 ::std::function<Output(const State &, const Input &)> h,
146 ::std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(const State &)>
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700147 dhdx,
148 const Eigen::Matrix<Scalar, kNOutputs, kNOutputs> &R,
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800149 aos::monotonic_clock::time_point t);
150
151 // A utility function for specifically updating with encoder and gyro
152 // measurements.
153 void UpdateEncodersAndGyro(const Scalar left_encoder,
154 const Scalar right_encoder, const Scalar gyro_rate,
155 const Input &U,
156 ::aos::monotonic_clock::time_point t) {
James Kuszmaul074429e2019-03-23 16:01:49 -0700157 // Because the check below for have_zeroed_encoders_ will add an
158 // Observation, do a check here to ensure that initialization has been
159 // performed and so there is at least one observation.
160 CHECK(!observations_.empty());
161 if (!have_zeroed_encoders_) {
162 // This logic handles ensuring that on the first encoder reading, we
163 // update the internal state for the encoders to match the reading.
164 // Otherwise, if we restart the drivetrain without restarting
165 // wpilib_interface, then we can get some obnoxious initial corrections
166 // that mess up the localization.
167 State newstate = X_hat_;
168 newstate(kLeftEncoder, 0) = left_encoder;
169 newstate(kRightEncoder, 0) = right_encoder;
170 newstate(kLeftVoltageError, 0) = 0.0;
171 newstate(kRightVoltageError, 0) = 0.0;
172 newstate(kAngularError, 0) = 0.0;
173 ResetInitialState(t, newstate, P_);
174 // We need to set have_zeroed_encoders_ after ResetInitialPosition because
175 // the reset clears have_zeroed_encoders_...
176 have_zeroed_encoders_ = true;
177 }
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800178 Output z(left_encoder, right_encoder, gyro_rate);
179 Eigen::Matrix<Scalar, kNOutputs, kNOutputs> R;
180 R.setZero();
181 R.diagonal() << encoder_noise_, encoder_noise_, gyro_noise_;
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700182 Correct(z, &U, {},
183 [this](const State &X, const Input &) {
184 return H_encoders_and_gyro_ * X;
185 },
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800186 [this](const State &) { return H_encoders_and_gyro_; }, R, t);
187 }
188
189 // Sundry accessor:
190 State X_hat() const { return X_hat_; }
191 Scalar X_hat(long i) const { return X_hat_(i, 0); }
192 StateSquare P() const { return P_; }
193 ::aos::monotonic_clock::time_point latest_t() const {
194 return observations_.top().t;
195 }
196
197 private:
198 struct Observation {
199 // Time when the observation was taken.
200 aos::monotonic_clock::time_point t;
201 // Time that the previous observation was taken:
202 aos::monotonic_clock::time_point prev_t;
203 // Estimate of state at previous observation time t, after accounting for
204 // the previous observation.
205 State X_hat;
206 // Noise matrix corresponding to X_hat_.
207 StateSquare P;
208 // The input applied from previous observation until time t.
209 Input U;
210 // Measurement taken at that time.
211 Output z;
212 // A function to create h and dhdx from a given position/covariance
213 // estimate. This is used by the camera to make it so that we only have to
214 // match targets once.
215 // Only called if h and dhdx are empty.
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700216 ::std::function<void(
217 const State &, const StateSquare &,
218 ::std::function<Output(const State &, const Input &)> *,
219 ::std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(
220 const State &)> *)>
221 make_h;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800222 // A function to calculate the expected output at a given state/input.
223 // TODO(james): For encoders/gyro, it is linear and the function call may
224 // be expensive. Potential source of optimization.
225 ::std::function<Output(const State &, const Input &)> h;
226 // The Jacobian of h with respect to x.
227 // We assume that U has no impact on the Jacobian.
228 // TODO(james): Currently, none of the users of this actually make use of
229 // the ability to have dynamic dhdx (technically, the camera code should
230 // recalculate it to be strictly correct, but I was both too lazy to do
231 // so and it seemed unnecessary). This is a potential source for future
232 // optimizations if function calls are being expensive.
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700233 ::std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(const State &)>
234 dhdx;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800235 // The measurement noise matrix.
236 Eigen::Matrix<Scalar, kNOutputs, kNOutputs> R;
237
238 // In order to sort the observations in the PriorityQueue object, we
239 // need a comparison function.
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700240 friend bool operator<(const Observation &l, const Observation &r) {
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800241 return l.t < r.t;
242 }
243 };
244
245 void InitializeMatrices();
246
247 StateSquare AForState(const State &X) const {
248 StateSquare A_continuous = A_continuous_;
249 const Scalar theta = X(kTheta, 0);
250 const Scalar linear_vel =
251 (X(kLeftVelocity, 0) + X(kRightVelocity, 0)) / 2.0;
252 const Scalar stheta = ::std::sin(theta);
253 const Scalar ctheta = ::std::cos(theta);
254 // X and Y derivatives
255 A_continuous(kX, kTheta) = -stheta * linear_vel;
256 A_continuous(kX, kLeftVelocity) = ctheta / 2.0;
257 A_continuous(kX, kRightVelocity) = ctheta / 2.0;
258 A_continuous(kY, kTheta) = ctheta * linear_vel;
259 A_continuous(kY, kLeftVelocity) = stheta / 2.0;
260 A_continuous(kY, kRightVelocity) = stheta / 2.0;
261 return A_continuous;
262 }
263
264 State DiffEq(const State &X, const Input &U) const {
265 State Xdot = A_continuous_ * X + B_continuous_ * U;
266 // And then we need to add on the terms for the x/y change:
267 const Scalar theta = X(kTheta, 0);
268 const Scalar linear_vel =
269 (X(kLeftVelocity, 0) + X(kRightVelocity, 0)) / 2.0;
270 const Scalar stheta = ::std::sin(theta);
271 const Scalar ctheta = ::std::cos(theta);
272 Xdot(kX, 0) = ctheta * linear_vel;
273 Xdot(kY, 0) = stheta * linear_vel;
274 return Xdot;
275 }
276
277 void PredictImpl(const Input &U, std::chrono::nanoseconds dt, State *state,
278 StateSquare *P) {
279 StateSquare A_c = AForState(*state);
280 StateSquare A_d;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800281 StateSquare Q_d;
James Kuszmaulb2a2f352019-03-02 16:59:34 -0800282 controls::DiscretizeQAFast(Q_continuous_, A_c, dt, &Q_d, &A_d);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800283
284 *state = RungeKuttaU(
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700285 [this](const State &X, const Input &U) { return DiffEq(X, U); }, *state,
286 U, ::aos::time::DurationInSeconds(dt));
James Kuszmaulb2a2f352019-03-02 16:59:34 -0800287
288 StateSquare Ptemp = A_d * *P * A_d.transpose() + Q_d;
289 *P = Ptemp;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800290 }
291
292 void CorrectImpl(const Eigen::Matrix<Scalar, kNOutputs, kNOutputs> &R,
293 const Output &Z, const Output &expected_Z,
294 const Eigen::Matrix<Scalar, kNOutputs, kNStates> &H,
295 State *state, StateSquare *P) {
296 Output err = Z - expected_Z;
297 Eigen::Matrix<Scalar, kNStates, kNOutputs> PH = *P * H.transpose();
298 Eigen::Matrix<Scalar, kNOutputs, kNOutputs> S = H * PH + R;
299 Eigen::Matrix<Scalar, kNStates, kNOutputs> K = PH * S.inverse();
James Kuszmaulb2a2f352019-03-02 16:59:34 -0800300 *state += K * err;
301 StateSquare Ptemp = (StateSquare::Identity() - K * H) * *P;
302 *P = Ptemp;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800303 }
304
305 void ProcessObservation(Observation *obs, const std::chrono::nanoseconds dt,
306 State *state, StateSquare *P) {
307 *state = obs->X_hat;
308 *P = obs->P;
309 if (dt.count() != 0) {
310 PredictImpl(obs->U, dt, state, P);
311 }
312 if (!(obs->h && obs->dhdx)) {
313 CHECK(obs->make_h);
314 obs->make_h(*state, *P, &obs->h, &obs->dhdx);
315 }
316 CorrectImpl(obs->R, obs->z, obs->h(*state, obs->U), obs->dhdx(*state),
317 state, P);
318 }
319
320 DrivetrainConfig<Scalar> dt_config_;
321 State X_hat_;
322 StateFeedbackHybridPlantCoefficients<2, 2, 2, Scalar>
323 velocity_drivetrain_coefficients_;
324 StateSquare A_continuous_;
325 StateSquare Q_continuous_;
326 StateSquare P_;
327 Eigen::Matrix<Scalar, kNOutputs, kNStates> H_encoders_and_gyro_;
328 Scalar encoder_noise_, gyro_noise_;
329 Eigen::Matrix<Scalar, kNStates, kNInputs> B_continuous_;
330
James Kuszmaul074429e2019-03-23 16:01:49 -0700331 bool have_zeroed_encoders_ = false;
332
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800333 aos::PriorityQueue<Observation, kSaveSamples, ::std::less<Observation>>
334 observations_;
335
336 friend class testing::HybridEkfTest;
James Kuszmaul1057ce82019-02-09 17:58:24 -0800337 friend class ::y2019::control_loops::testing::ParameterizedLocalizerTest;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800338}; // class HybridEkf
339
340template <typename Scalar>
341void HybridEkf<Scalar>::Correct(
342 const Output &z, const Input *U,
343 ::std::function<
344 void(const State &, const StateSquare &,
345 ::std::function<Output(const State &, const Input &)> *,
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700346 ::std::function<
347 Eigen::Matrix<Scalar, kNOutputs, kNStates>(const State &)> *)>
348 make_h,
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800349 ::std::function<Output(const State &, const Input &)> h,
350 ::std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(const State &)>
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700351 dhdx,
352 const Eigen::Matrix<Scalar, kNOutputs, kNOutputs> &R,
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800353 aos::monotonic_clock::time_point t) {
354 CHECK(!observations_.empty());
355 if (!observations_.full() && t < observations_.begin()->t) {
356 LOG(ERROR,
357 "Dropped an observation that was received before we "
358 "initialized.\n");
359 return;
360 }
361 auto cur_it =
362 observations_.PushFromBottom({t, t, State::Zero(), StateSquare::Zero(),
363 Input::Zero(), z, make_h, h, dhdx, R});
364 if (cur_it == observations_.end()) {
365 LOG(DEBUG,
366 "Camera dropped off of end with time of %fs; earliest observation in "
367 "queue has time of %fs.\n",
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700368 ::aos::time::DurationInSeconds(t.time_since_epoch()),
369 ::aos::time::DurationInSeconds(
370 observations_.begin()->t.time_since_epoch()));
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800371 return;
372 }
373
374 // Now we populate any state information that depends on where the
375 // observation was inserted into the queue. X_hat and P must be populated
376 // from the values present in the observation *following* this one in
377 // the queue (note that the X_hat and P that we store in each observation
378 // is the values that they held after accounting for the previous
379 // measurement and before accounting for the time between the previous and
380 // current measurement). If we appended to the end of the queue, then
381 // we need to pull from X_hat_ and P_ specifically.
382 // Furthermore, for U:
383 // -If the observation was inserted at the end, then the user must've
384 // provided U and we use it.
385 // -Otherwise, only grab U if necessary.
386 auto next_it = cur_it;
387 ++next_it;
388 if (next_it == observations_.end()) {
389 cur_it->X_hat = X_hat_;
390 cur_it->P = P_;
391 // Note that if next_it == observations_.end(), then because we already
392 // checked for !observations_.empty(), we are guaranteed to have
393 // valid prev_it.
394 auto prev_it = cur_it;
395 --prev_it;
396 cur_it->prev_t = prev_it->t;
397 // TODO(james): Figure out a saner way of handling this.
398 CHECK(U != nullptr);
399 cur_it->U = *U;
400 } else {
401 cur_it->X_hat = next_it->X_hat;
402 cur_it->P = next_it->P;
403 cur_it->prev_t = next_it->prev_t;
404 next_it->prev_t = cur_it->t;
405 cur_it->U = (U == nullptr) ? next_it->U : *U;
406 }
407 // Now we need to rerun the predict step from the previous to the new
408 // observation as well as every following correct/predict up to the current
409 // time.
410 while (true) {
411 // We use X_hat_ and P_ to store the intermediate states, and then
412 // once we reach the end they will all be up-to-date.
413 ProcessObservation(&*cur_it, cur_it->t - cur_it->prev_t, &X_hat_, &P_);
414 CHECK(X_hat_.allFinite());
415 if (next_it != observations_.end()) {
416 next_it->X_hat = X_hat_;
417 next_it->P = P_;
418 } else {
419 break;
420 }
421 ++cur_it;
422 ++next_it;
423 }
424}
425
426template <typename Scalar>
427void HybridEkf<Scalar>::InitializeMatrices() {
428 A_continuous_.setZero();
429 const Scalar diameter = 2.0 * dt_config_.robot_radius;
430 // Theta derivative
431 A_continuous_(kTheta, kLeftVelocity) = -1.0 / diameter;
432 A_continuous_(kTheta, kRightVelocity) = 1.0 / diameter;
433
434 // Encoder derivatives
435 A_continuous_(kLeftEncoder, kLeftVelocity) = 1.0;
James Kuszmaul074429e2019-03-23 16:01:49 -0700436 A_continuous_(kLeftEncoder, kAngularError) = 1.0;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800437 A_continuous_(kRightEncoder, kRightVelocity) = 1.0;
James Kuszmaul074429e2019-03-23 16:01:49 -0700438 A_continuous_(kRightEncoder, kAngularError) = -1.0;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800439
440 // Pull velocity derivatives from velocity matrices.
441 // Note that this looks really awkward (doesn't use
442 // Eigen blocks) because someone decided that the full
443 // drivetrain Kalman Filter should half a weird convention.
444 // TODO(james): Support shifting drivetrains with changing A_continuous
445 const auto &vel_coefs = velocity_drivetrain_coefficients_;
446 A_continuous_(kLeftVelocity, kLeftVelocity) = vel_coefs.A_continuous(0, 0);
447 A_continuous_(kLeftVelocity, kRightVelocity) = vel_coefs.A_continuous(0, 1);
448 A_continuous_(kRightVelocity, kLeftVelocity) = vel_coefs.A_continuous(1, 0);
449 A_continuous_(kRightVelocity, kRightVelocity) = vel_coefs.A_continuous(1, 1);
450
451 // Provide for voltage error terms:
452 B_continuous_.setZero();
453 B_continuous_.row(kLeftVelocity) = vel_coefs.B_continuous.row(0);
454 B_continuous_.row(kRightVelocity) = vel_coefs.B_continuous.row(1);
James Kuszmaul074429e2019-03-23 16:01:49 -0700455 A_continuous_.template block<kNStates, kNInputs>(0, 7) = B_continuous_;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800456
457 Q_continuous_.setZero();
458 // TODO(james): Improve estimates of process noise--e.g., X/Y noise can
James Kuszmaul1057ce82019-02-09 17:58:24 -0800459 // probably be reduced when we are stopped because you rarely jump randomly.
460 // Or maybe it's more appropriate to scale wheelspeed noise with wheelspeed,
461 // since the wheels aren't likely to slip much stopped.
James Kuszmaula5632fe2019-03-23 20:28:33 -0700462 Q_continuous_(kX, kX) = 0.002;
463 Q_continuous_(kY, kY) = 0.002;
James Kuszmaul7f1a4082019-04-14 10:50:44 -0700464 Q_continuous_(kTheta, kTheta) = 0.0001;
James Kuszmaul074429e2019-03-23 16:01:49 -0700465 Q_continuous_(kLeftEncoder, kLeftEncoder) = ::std::pow(0.15, 2.0);
466 Q_continuous_(kRightEncoder, kRightEncoder) = ::std::pow(0.15, 2.0);
467 Q_continuous_(kLeftVelocity, kLeftVelocity) = ::std::pow(0.5, 2.0);
468 Q_continuous_(kRightVelocity, kRightVelocity) = ::std::pow(0.5, 2.0);
469 Q_continuous_(kLeftVoltageError, kLeftVoltageError) = ::std::pow(10.0, 2.0);
470 Q_continuous_(kRightVoltageError, kRightVoltageError) = ::std::pow(10.0, 2.0);
471 Q_continuous_(kAngularError, kAngularError) = ::std::pow(2.0, 2.0);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800472
473 P_.setZero();
James Kuszmaul7dedecc2019-05-01 21:45:17 -0500474 P_.diagonal() << 0.01, 0.01, 0.01, 0.02, 0.01, 0.02, 0.01, 1, 1, 0.03;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800475
476 H_encoders_and_gyro_.setZero();
477 // Encoders are stored directly in the state matrix, so are a minor
478 // transform away.
479 H_encoders_and_gyro_(0, kLeftEncoder) = 1.0;
480 H_encoders_and_gyro_(1, kRightEncoder) = 1.0;
481 // Gyro rate is just the difference between right/left side speeds:
482 H_encoders_and_gyro_(2, kLeftVelocity) = -1.0 / diameter;
483 H_encoders_and_gyro_(2, kRightVelocity) = 1.0 / diameter;
484
485 const Eigen::Matrix<Scalar, 4, 4> R_kf_drivetrain =
486 dt_config_.make_kf_drivetrain_loop().observer().coefficients().R;
James Kuszmaul074429e2019-03-23 16:01:49 -0700487 // TODO(james): The multipliers here are hand-waving things that I put in when
488 // tuning things. I haven't yet tried messing with these values again.
James Kuszmaulc40c26e2019-03-24 16:26:43 -0700489 encoder_noise_ = 0.5 * R_kf_drivetrain(0, 0);
James Kuszmaul074429e2019-03-23 16:01:49 -0700490 gyro_noise_ = 0.1 * R_kf_drivetrain(2, 2);
Austin Schuh9fe68f72019-08-10 19:32:03 -0700491
492 X_hat_.setZero();
493 P_.setZero();
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800494}
495
496} // namespace drivetrain
497} // namespace control_loops
498} // namespace frc971
499
500#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_HYBRID_EKF_H_