blob: fcbed76dd2ed3f29cd32fc93e81d0c9c9960485c [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 Kuszmaul3c5b4d32020-02-11 17:22:14 -08007#include "aos/commonmath.h"
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -08008#include "aos/containers/priority_queue.h"
James Kuszmaulfedc4612019-03-10 11:24:51 -07009#include "aos/util/math.h"
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080010#include "frc971/control_loops/c2d.h"
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080011#include "frc971/control_loops/drivetrain/drivetrain_config.h"
James Kuszmaul651fc3f2019-05-15 21:14:25 -070012#include "frc971/control_loops/runge_kutta.h"
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080013
James Kuszmaul1057ce82019-02-09 17:58:24 -080014namespace y2019 {
15namespace control_loops {
16namespace testing {
17class ParameterizedLocalizerTest;
18} // namespace testing
19} // namespace control_loops
20} // namespace y2019
21
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080022namespace frc971 {
23namespace control_loops {
24namespace drivetrain {
25
26namespace testing {
27class HybridEkfTest;
28}
29
30// HybridEkf is an EKF for use in robot localization. It is currently
31// coded for use with drivetrains in particular, and so the states and inputs
32// are chosen as such.
33// The "Hybrid" part of the name refers to the fact that it can take in
34// measurements with variable time-steps.
35// measurements can also have been taken in the past and we maintain a buffer
36// so that we can replay the kalman filter whenever we get an old measurement.
37// Currently, this class provides the necessary utilities for doing
38// measurement updates with an encoder/gyro as well as a more generic
39// update function that can be used for arbitrary nonlinear updates (presumably
40// a camera update).
James Kuszmaul3c5b4d32020-02-11 17:22:14 -080041//
42// Discussion of the model:
43// In the current model, we try to rely primarily on IMU measurements for
44// estimating robot state--we also need additional information (some combination
45// of output voltages, encoders, and camera data) to help eliminate the biases
46// that can accumulate due to integration of IMU data.
47// We use IMU measurements as inputs rather than measurement outputs because
48// that seemed to be easier to implement. I tried initially running with
49// the IMU as a measurement, but it seemed to blow up the complexity of the
50// model.
51//
52// On each prediction update, we take in inputs of the left/right voltages and
53// the current measured longitudinal/lateral accelerations. In the current
54// setup, the accelerometer readings will be used for estimating how the
55// evolution of the longitudinal/lateral velocities. The voltages (and voltage
56// errors) will solely be used for estimating the current rotational velocity of
57// the robot (I do this because currently I suspect that the accelerometer is a
58// much better indicator of current robot state than the voltages). We also
59// deliberately decay all of the velocity estimates towards zero to help address
60// potential accelerometer biases. We use two separate decay models:
61// -The longitudinal velocity is modelled as decaying at a constant rate (see
62// the documentation on the VelocityAccel() method)--this needs a more
63// complex model because the robot will, under normal circumstances, be
64// travelling at non-zero velocities.
65// -The lateral velocity is modelled as exponentially decaying towards zero.
66// This is simpler to model and should be reasonably valid, since we will
67// not *normally* be travelling sideways consistently (this assumption may
68// need to be revisited).
69// -The "longitudinal velocity offset" (described below) also uses an
70// exponential decay, albeit with a different time constant. A future
71// improvement may remove the decay modelling on the longitudinal velocity
72// itself and instead use that decay model on the longitudinal velocity offset.
73// This would place a bit more trust in the encoder measurements but also
74// more correctly model situations where the robot is legitimately moving at
75// a certain velocity.
76//
77// For modelling how the drivetrain encoders evolve, and to help prevent the
78// aforementioned decay functions from affecting legitimate high-velocity
79// maneuvers too much, we have a "longitudinal velocity offset" term. This term
80// models the difference between the actual longitudinal velocity of the robot
81// (estimated by the average of the left/right velocities) and the velocity
82// experienced by the wheels (which can be observed from the encoders more
83// directly). Because we model this velocity offset as decaying towards zero,
84// what this will do is allow the encoders to be a constant velocity off from
85// the accelerometer updates for short periods of time but then gradually
86// pull the "actual" longitudinal velocity offset towards that of the encoders,
87// helping to reduce constant biases.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080088template <typename Scalar = double>
89class HybridEkf {
90 public:
91 // An enum specifying what each index in the state vector is for.
92 enum StateIdx {
James Kuszmaul3c5b4d32020-02-11 17:22:14 -080093 // Current X/Y position, in meters, of the robot.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080094 kX = 0,
95 kY = 1,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -080096 // Current heading of the robot.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080097 kTheta = 2,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -080098 // Current estimated encoder reading of the left wheels, in meters.
99 // Rezeroed once on startup.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800100 kLeftEncoder = 3,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800101 // Current estimated actual velocity of the left side of the robot, in m/s.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800102 kLeftVelocity = 4,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800103 // Same variables, for the right side of the robot.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800104 kRightEncoder = 5,
105 kRightVelocity = 6,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800106 // Estimated offset to input voltage. Used as a generic error term, Volts.
James Kuszmaul074429e2019-03-23 16:01:49 -0700107 kLeftVoltageError = 7,
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700108 kRightVoltageError = 8,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800109 // These error terms are used to estimate the difference between the actual
110 // movement of the drivetrain and that implied by the wheel odometry.
111 // Angular error effectively estimates a constant angular rate offset of the
112 // encoders relative to the actual rotation of the robot.
113 // Semi-arbitrary units (we don't bother accounting for robot radius in
114 // this).
James Kuszmaul074429e2019-03-23 16:01:49 -0700115 kAngularError = 9,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800116 // Estimate of slip between the drivetrain wheels and the actual
117 // forwards/backwards velocity of the robot, in m/s.
118 // I.e., (left velocity + right velocity) / 2.0 = (left wheel velocity +
119 // right wheel velocity) / 2.0 + longitudinal velocity offset
120 kLongitudinalVelocityOffset = 10,
121 // Current estimate of the lateral velocity of the robot, in m/s.
122 // Positive implies the robot is moving to its left.
123 kLateralVelocity = 11,
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800124 };
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800125 static constexpr int kNStates = 12;
126 enum InputIdx {
127 // Left/right drivetrain voltages.
128 kLeftVoltage = 0,
129 kRightVoltage = 1,
130 // Current accelerometer readings, in m/s/s, along the longitudinal and
131 // lateral axes of the robot. Should be projected onto the X/Y plane, to
132 // compensate for tilt of the robot before being passed to this filter. The
133 // HybridEkf has no knowledge of the current pitch/roll of the robot, and so
134 // can't do anything to compensate for it.
135 kLongitudinalAccel = 2,
136 kLateralAccel = 3,
137 };
138 static constexpr int kNInputs = 4;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800139 // Number of previous samples to save.
Austin Schuh6e660592021-10-17 17:37:33 -0700140 static constexpr int kSaveSamples = 200;
James Kuszmaul06257f42020-05-09 15:40:09 -0700141 // Whether we should completely rerun the entire stored history of
142 // kSaveSamples on every correction. Enabling this will increase overall CPU
143 // usage substantially; however, leaving it disabled makes it so that we are
144 // less likely to notice if processing camera frames is causing delays in the
145 // drivetrain.
146 // If we are having CPU issues, we have three easy avenues to improve things:
147 // (1) Reduce kSaveSamples (e.g., if all camera frames arive within
148 // 100 ms, then we can reduce kSaveSamples to be 25 (125 ms of samples)).
149 // (2) Don't actually rely on the ability to insert corrections into the
150 // timeline.
151 // (3) Set this to false.
152 static constexpr bool kFullRewindOnEverySample = false;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800153 // Assume that all correction steps will have kNOutputs
154 // dimensions.
155 // TODO(james): Relax this assumption; relaxing it requires
156 // figuring out how to deal with storing variable size
157 // observation matrices, though.
158 static constexpr int kNOutputs = 3;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800159 // Time constant to use for estimating how the longitudinal/lateral velocity
160 // offsets decay, in seconds.
James Kuszmaul5f6d1d42020-03-01 18:10:07 -0800161 static constexpr double kVelocityOffsetTimeConstant = 1.0;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800162 static constexpr double kLateralVelocityTimeConstant = 1.0;
James Kuszmaul91aa0cf2021-02-13 13:15:06 -0800163
James Kuszmaulf3950362020-10-11 18:29:15 -0700164 // The maximum allowable timestep--we use this to check for situations where
165 // measurement updates come in too infrequently and this might cause the
166 // integrator and discretization in the prediction step to be overly
167 // aggressive.
168 static constexpr std::chrono::milliseconds kMaxTimestep{20};
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800169 // Inputs are [left_volts, right_volts]
170 typedef Eigen::Matrix<Scalar, kNInputs, 1> Input;
171 // Outputs are either:
172 // [left_encoder, right_encoder, gyro_vel]; or [heading, distance, skew] to
173 // some target. This makes it so we don't have to figure out how we store
174 // variable-size measurement updates.
175 typedef Eigen::Matrix<Scalar, kNOutputs, 1> Output;
176 typedef Eigen::Matrix<Scalar, kNStates, kNStates> StateSquare;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800177 // State contains the states defined by the StateIdx enum. See comments there.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800178 typedef Eigen::Matrix<Scalar, kNStates, 1> State;
179
180 // Constructs a HybridEkf for a particular drivetrain.
181 // Currently, we use the drivetrain config for modelling constants
182 // (continuous time A and B matrices) and for the noise matrices for the
183 // encoders/gyro.
James Kuszmauld478f872020-03-16 20:54:27 -0700184 HybridEkf(const DrivetrainConfig<double> &dt_config)
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800185 : dt_config_(dt_config),
186 velocity_drivetrain_coefficients_(
187 dt_config.make_hybrid_drivetrain_velocity_loop()
188 .plant()
189 .coefficients()) {
190 InitializeMatrices();
191 }
192
193 // Set the initial guess of the state. Can only be called once, and before
194 // any measurement updates have occured.
195 // TODO(james): We may want to actually re-initialize and reset things on
196 // the field. Create some sort of Reset() function.
197 void ResetInitialState(::aos::monotonic_clock::time_point t,
James Kuszmaul1057ce82019-02-09 17:58:24 -0800198 const State &state, const StateSquare &P) {
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800199 observations_.clear();
200 X_hat_ = state;
James Kuszmaul074429e2019-03-23 16:01:49 -0700201 have_zeroed_encoders_ = true;
James Kuszmaul1057ce82019-02-09 17:58:24 -0800202 P_ = P;
James Kuszmaul06257f42020-05-09 15:40:09 -0700203 observations_.PushFromBottom({
204 t,
205 t,
206 X_hat_,
207 P_,
208 Input::Zero(),
209 Output::Zero(),
210 {},
211 [](const State &, const Input &) { return Output::Zero(); },
212 [](const State &) {
213 return Eigen::Matrix<Scalar, kNOutputs, kNStates>::Zero();
214 },
215 Eigen::Matrix<Scalar, kNOutputs, kNOutputs>::Identity(),
216 StateSquare::Identity(),
217 StateSquare::Zero(),
218 std::chrono::seconds(0),
219 State::Zero(),
220 });
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800221 }
222
223 // Correct with:
224 // A measurement z at time t with z = h(X_hat, U) + v where v has noise
225 // covariance R.
226 // Input U is applied from the previous timestep until time t.
227 // If t is later than any previous measurements, then U must be provided.
228 // If the measurement falls between two previous measurements, then U
229 // can be provided or not; if U is not provided, then it is filled in based
230 // on an assumption that the voltage was held constant between the time steps.
231 // TODO(james): Is it necessary to explicitly to provide a version with H as a
232 // matrix for linear cases?
233 void Correct(
234 const Output &z, const Input *U,
Austin Schuhd749d932020-12-30 21:38:40 -0800235 std::function<void(const State &, const StateSquare &,
236 std::function<Output(const State &, const Input &)> *,
237 std::function<Eigen::Matrix<
238 Scalar, kNOutputs, kNStates>(const State &)> *)>
239 make_h,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800240 std::function<Output(const State &, const Input &)> h,
241 std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(const State &)>
Austin Schuhd749d932020-12-30 21:38:40 -0800242 dhdx,
243 const Eigen::Matrix<Scalar, kNOutputs, kNOutputs> &R,
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800244 aos::monotonic_clock::time_point t);
245
246 // A utility function for specifically updating with encoder and gyro
247 // measurements.
248 void UpdateEncodersAndGyro(const Scalar left_encoder,
249 const Scalar right_encoder, const Scalar gyro_rate,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800250 const Eigen::Matrix<Scalar, 2, 1> &voltage,
251 const Eigen::Matrix<Scalar, 3, 1> &accel,
252 aos::monotonic_clock::time_point t) {
253 Input U;
254 U.template block<2, 1>(0, 0) = voltage;
255 U.template block<2, 1>(kLongitudinalAccel, 0) =
256 accel.template block<2, 1>(0, 0);
257 RawUpdateEncodersAndGyro(left_encoder, right_encoder, gyro_rate, U, t);
258 }
259 // Version of UpdateEncodersAndGyro that takes a input matrix rather than
260 // taking in a voltage/acceleration separately.
261 void RawUpdateEncodersAndGyro(const Scalar left_encoder,
262 const Scalar right_encoder,
263 const Scalar gyro_rate, const Input &U,
264 aos::monotonic_clock::time_point t) {
James Kuszmaul074429e2019-03-23 16:01:49 -0700265 // Because the check below for have_zeroed_encoders_ will add an
266 // Observation, do a check here to ensure that initialization has been
267 // performed and so there is at least one observation.
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800268 CHECK(!observations_.empty());
James Kuszmaul074429e2019-03-23 16:01:49 -0700269 if (!have_zeroed_encoders_) {
270 // This logic handles ensuring that on the first encoder reading, we
271 // update the internal state for the encoders to match the reading.
272 // Otherwise, if we restart the drivetrain without restarting
273 // wpilib_interface, then we can get some obnoxious initial corrections
274 // that mess up the localization.
275 State newstate = X_hat_;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800276 newstate(kLeftEncoder) = left_encoder;
277 newstate(kRightEncoder) = right_encoder;
278 newstate(kLeftVoltageError) = 0.0;
279 newstate(kRightVoltageError) = 0.0;
280 newstate(kAngularError) = 0.0;
281 newstate(kLongitudinalVelocityOffset) = 0.0;
282 newstate(kLateralVelocity) = 0.0;
James Kuszmaul074429e2019-03-23 16:01:49 -0700283 ResetInitialState(t, newstate, P_);
284 // We need to set have_zeroed_encoders_ after ResetInitialPosition because
285 // the reset clears have_zeroed_encoders_...
286 have_zeroed_encoders_ = true;
287 }
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800288
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800289 Output z(left_encoder, right_encoder, gyro_rate);
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800290
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800291 Eigen::Matrix<Scalar, kNOutputs, kNOutputs> R;
292 R.setZero();
293 R.diagonal() << encoder_noise_, encoder_noise_, gyro_noise_;
Austin Schuhd749d932020-12-30 21:38:40 -0800294 Correct(z, &U, {},
295 [this](const State &X, const Input &) {
296 return H_encoders_and_gyro_ * X;
297 },
298 [this](const State &) { return H_encoders_and_gyro_; }, R, t);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800299 }
300
301 // Sundry accessor:
302 State X_hat() const { return X_hat_; }
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800303 Scalar X_hat(long i) const { return X_hat_(i); }
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800304 StateSquare P() const { return P_; }
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800305 aos::monotonic_clock::time_point latest_t() const {
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800306 return observations_.top().t;
307 }
308
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800309 static Scalar CalcLongitudinalVelocity(const State &X) {
310 return (X(kLeftVelocity) + X(kRightVelocity)) / 2.0;
311 }
312
313 Scalar CalcYawRate(const State &X) const {
314 return (X(kRightVelocity) - X(kLeftVelocity)) / 2.0 /
315 dt_config_.robot_radius;
316 }
317
James Kuszmaul06257f42020-05-09 15:40:09 -0700318 // Returns the last state before the specified time.
319 // Returns nullopt if time is older than the oldest measurement.
320 std::optional<State> LastStateBeforeTime(
321 aos::monotonic_clock::time_point time) {
322 if (observations_.empty() || observations_.begin()->t > time) {
323 return std::nullopt;
324 }
325 for (const auto &observation : observations_) {
326 if (observation.t > time) {
327 // Note that observation.X_hat actually references the _previous_ X_hat.
328 return observation.X_hat;
329 }
330 }
331 return X_hat();
332 }
James Kuszmaulba59dc92022-03-12 10:46:54 -0800333 std::optional<State> OldestState() {
334 if (observations_.empty()) {
335 return std::nullopt;
336 }
337 return observations_.begin()->X_hat;
338 }
James Kuszmaul06257f42020-05-09 15:40:09 -0700339
340 // Returns the most recent input vector.
341 Input MostRecentInput() {
342 CHECK(!observations_.empty());
343 Input U = observations_.top().U;
344 return U;
345 }
346
James Kuszmaul91aa0cf2021-02-13 13:15:06 -0800347 void set_ignore_accel(bool ignore_accel) { ignore_accel_ = ignore_accel; }
348
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800349 private:
350 struct Observation {
351 // Time when the observation was taken.
352 aos::monotonic_clock::time_point t;
353 // Time that the previous observation was taken:
354 aos::monotonic_clock::time_point prev_t;
355 // Estimate of state at previous observation time t, after accounting for
356 // the previous observation.
357 State X_hat;
358 // Noise matrix corresponding to X_hat_.
359 StateSquare P;
360 // The input applied from previous observation until time t.
361 Input U;
362 // Measurement taken at that time.
363 Output z;
364 // A function to create h and dhdx from a given position/covariance
365 // estimate. This is used by the camera to make it so that we only have to
366 // match targets once.
367 // Only called if h and dhdx are empty.
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800368 std::function<void(const State &, const StateSquare &,
369 std::function<Output(const State &, const Input &)> *,
370 std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(
Austin Schuhd749d932020-12-30 21:38:40 -0800371 const State &)> *)>
372 make_h;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800373 // A function to calculate the expected output at a given state/input.
374 // TODO(james): For encoders/gyro, it is linear and the function call may
375 // be expensive. Potential source of optimization.
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800376 std::function<Output(const State &, const Input &)> h;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800377 // The Jacobian of h with respect to x.
378 // We assume that U has no impact on the Jacobian.
379 // TODO(james): Currently, none of the users of this actually make use of
380 // the ability to have dynamic dhdx (technically, the camera code should
381 // recalculate it to be strictly correct, but I was both too lazy to do
382 // so and it seemed unnecessary). This is a potential source for future
383 // optimizations if function calls are being expensive.
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800384 std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(const State &)>
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700385 dhdx;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800386 // The measurement noise matrix.
387 Eigen::Matrix<Scalar, kNOutputs, kNOutputs> R;
388
James Kuszmaul06257f42020-05-09 15:40:09 -0700389 // Discretized A and Q to use on this update step. These will only be
390 // recalculated if the timestep changes.
391 StateSquare A_d;
392 StateSquare Q_d;
393 aos::monotonic_clock::duration discretization_time;
394
395 // A cached value indicating how much we change X_hat in the prediction step
396 // of this Observation.
397 State predict_update;
398
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800399 // In order to sort the observations in the PriorityQueue object, we
400 // need a comparison function.
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700401 friend bool operator<(const Observation &l, const Observation &r) {
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800402 return l.t < r.t;
403 }
404 };
405
406 void InitializeMatrices();
407
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800408 // These constants and functions define how the longitudinal velocity
409 // (the average of the left and right velocities) decays. We model it as
410 // decaying at a constant rate, except very near zero where the decay rate is
411 // exponential (this is more numerically stable than just using a constant
412 // rate the whole time). We use this model rather than a simpler exponential
413 // decay because an exponential decay will result in the robot's velocity
414 // estimate consistently being far too low when at high velocities, and since
415 // the acceleromater-based estimate of the velocity will only drift at a
416 // relatively slow rate and doesn't get worse at higher velocities, we can
417 // safely decay pretty slowly.
418 static constexpr double kMaxVelocityAccel = 0.005;
419 static constexpr double kMaxVelocityGain = 1.0;
420 static Scalar VelocityAccel(Scalar velocity) {
421 return -std::clamp(kMaxVelocityGain * velocity, -kMaxVelocityAccel,
422 kMaxVelocityAccel);
423 }
424
425 static Scalar VelocityAccelDiff(Scalar velocity) {
426 return (std::abs(kMaxVelocityGain * velocity) > kMaxVelocityAccel)
427 ? 0.0
428 : -kMaxVelocityGain;
429 }
430
431 // Returns the "A" matrix for a given state. See DiffEq for discussion of
432 // ignore_accel.
James Kuszmaul91aa0cf2021-02-13 13:15:06 -0800433 StateSquare AForState(const State &X, bool ignore_accel) const {
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800434 // Calculate the A matrix for a given state. Note that A = partial Xdot /
435 // partial X. This is distinct from saying that Xdot = A * X. This is
436 // particularly relevant for the (kX, kTheta) members which otherwise seem
437 // odd.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800438 StateSquare A_continuous = A_continuous_;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800439 const Scalar theta = X(kTheta);
440 const Scalar stheta = std::sin(theta);
441 const Scalar ctheta = std::cos(theta);
442 const Scalar lng_vel = CalcLongitudinalVelocity(X);
443 const Scalar lat_vel = X(kLateralVelocity);
444 const Scalar diameter = 2.0 * dt_config_.robot_radius;
445 const Scalar yaw_rate = CalcYawRate(X);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800446 // X and Y derivatives
Austin Schuhd749d932020-12-30 21:38:40 -0800447 A_continuous(kX, kTheta) = -stheta * lng_vel - ctheta * lat_vel;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800448 A_continuous(kX, kLeftVelocity) = ctheta / 2.0;
449 A_continuous(kX, kRightVelocity) = ctheta / 2.0;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800450 A_continuous(kX, kLateralVelocity) = -stheta;
451 A_continuous(kY, kTheta) = ctheta * lng_vel - stheta * lat_vel;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800452 A_continuous(kY, kLeftVelocity) = stheta / 2.0;
453 A_continuous(kY, kRightVelocity) = stheta / 2.0;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800454 A_continuous(kY, kLateralVelocity) = ctheta;
455
456 if (!ignore_accel) {
457 const Eigen::Matrix<Scalar, 1, kNStates> lng_vel_row =
458 (A_continuous.row(kLeftVelocity) + A_continuous.row(kRightVelocity)) /
459 2.0;
460 A_continuous.row(kLeftVelocity) -= lng_vel_row;
461 A_continuous.row(kRightVelocity) -= lng_vel_row;
462 // Terms to account for centripetal accelerations.
463 // lateral centripetal accel = -yaw_rate * lng_vel
464 A_continuous(kLateralVelocity, kLeftVelocity) +=
465 X(kLeftVelocity) / diameter;
466 A_continuous(kLateralVelocity, kRightVelocity) +=
467 -X(kRightVelocity) / diameter;
468 A_continuous(kRightVelocity, kLateralVelocity) += yaw_rate;
469 A_continuous(kLeftVelocity, kLateralVelocity) += yaw_rate;
470 const Scalar dlng_accel_dwheel_vel = X(kLateralVelocity) / diameter;
471 A_continuous(kRightVelocity, kRightVelocity) += dlng_accel_dwheel_vel;
472 A_continuous(kLeftVelocity, kRightVelocity) += dlng_accel_dwheel_vel;
473 A_continuous(kRightVelocity, kLeftVelocity) += -dlng_accel_dwheel_vel;
474 A_continuous(kLeftVelocity, kLeftVelocity) += -dlng_accel_dwheel_vel;
475
476 A_continuous(kRightVelocity, kRightVelocity) +=
477 VelocityAccelDiff(lng_vel) / 2.0;
478 A_continuous(kRightVelocity, kLeftVelocity) +=
479 VelocityAccelDiff(lng_vel) / 2.0;
480 A_continuous(kLeftVelocity, kRightVelocity) +=
481 VelocityAccelDiff(lng_vel) / 2.0;
482 A_continuous(kLeftVelocity, kLeftVelocity) +=
483 VelocityAccelDiff(lng_vel) / 2.0;
484 }
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800485 return A_continuous;
486 }
487
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800488 // Returns dX / dt given X and U. If ignore_accel is set, then we ignore the
489 // accelerometer-based components of U (this is solely used in testing).
James Kuszmaul91aa0cf2021-02-13 13:15:06 -0800490 State DiffEq(const State &X, const Input &U, bool ignore_accel) const {
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800491 State Xdot = A_continuous_ * X + B_continuous_ * U;
492 // And then we need to add on the terms for the x/y change:
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800493 const Scalar theta = X(kTheta);
494 const Scalar lng_vel = CalcLongitudinalVelocity(X);
495 const Scalar lat_vel = X(kLateralVelocity);
496 const Scalar stheta = std::sin(theta);
497 const Scalar ctheta = std::cos(theta);
498 Xdot(kX) = ctheta * lng_vel - stheta * lat_vel;
499 Xdot(kY) = stheta * lng_vel + ctheta * lat_vel;
500
501 const Scalar yaw_rate = CalcYawRate(X);
502 const Scalar expected_lat_accel = lng_vel * yaw_rate;
503 const Scalar expected_lng_accel =
504 CalcLongitudinalVelocity(Xdot) - yaw_rate * lat_vel;
Austin Schuhd749d932020-12-30 21:38:40 -0800505 const Scalar lng_accel_offset = U(kLongitudinalAccel) - expected_lng_accel;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800506 constexpr double kAccelWeight = 1.0;
507 if (!ignore_accel) {
508 Xdot(kLeftVelocity) += kAccelWeight * lng_accel_offset;
509 Xdot(kRightVelocity) += kAccelWeight * lng_accel_offset;
510 Xdot(kLateralVelocity) += U(kLateralAccel) - expected_lat_accel;
511
512 Xdot(kRightVelocity) += VelocityAccel(lng_vel);
513 Xdot(kLeftVelocity) += VelocityAccel(lng_vel);
514 }
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800515 return Xdot;
516 }
517
James Kuszmaul06257f42020-05-09 15:40:09 -0700518 void PredictImpl(Observation *obs, std::chrono::nanoseconds dt, State *state,
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800519 StateSquare *P) {
James Kuszmaul06257f42020-05-09 15:40:09 -0700520 // Only recalculate the discretization if the timestep has changed.
521 // Technically, this isn't quite correct, since the discretization will
522 // change depending on the current state. However, the slight loss of
523 // precision seems acceptable for the sake of significantly reducing CPU
524 // usage.
525 if (obs->discretization_time != dt) {
526 // TODO(james): By far the biggest CPU sink in the localization appears to
527 // be this discretization--it's possible the spline code spikes higher,
528 // but it doesn't create anywhere near the same sustained load. There
529 // are a few potential options for optimizing this code, but none of
530 // them are entirely trivial, e.g. we could:
531 // -Reduce the number of states (this function grows at O(kNStates^3))
532 // -Adjust the discretization function itself (there're a few things we
533 // can tune there).
534 // -Try to come up with some sort of lookup table or other way of
535 // pre-calculating A_d and Q_d.
536 // I also have to figure out how much we care about the precision of
537 // some of these values--I don't think we care much, but we probably
538 // do want to maintain some of the structure of the matrices.
James Kuszmaul91aa0cf2021-02-13 13:15:06 -0800539 const StateSquare A_c = AForState(*state, ignore_accel_);
James Kuszmaul06257f42020-05-09 15:40:09 -0700540 controls::DiscretizeQAFast(Q_continuous_, A_c, dt, &obs->Q_d, &obs->A_d);
541 obs->discretization_time = dt;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800542
James Kuszmaul06257f42020-05-09 15:40:09 -0700543 obs->predict_update =
544 RungeKuttaU(
James Kuszmaul91aa0cf2021-02-13 13:15:06 -0800545 [this](const State &X, const Input &U) {
546 return DiffEq(X, U, ignore_accel_);
547 },
James Kuszmaul06257f42020-05-09 15:40:09 -0700548 *state, obs->U, aos::time::DurationInSeconds(dt)) -
549 *state;
550 }
James Kuszmaulb2a2f352019-03-02 16:59:34 -0800551
James Kuszmaul06257f42020-05-09 15:40:09 -0700552 *state += obs->predict_update;
553
554 StateSquare Ptemp = obs->A_d * *P * obs->A_d.transpose() + obs->Q_d;
James Kuszmaulb2a2f352019-03-02 16:59:34 -0800555 *P = Ptemp;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800556 }
557
James Kuszmaul06257f42020-05-09 15:40:09 -0700558 void CorrectImpl(Observation *obs, State *state, StateSquare *P) {
559 const Eigen::Matrix<Scalar, kNOutputs, kNStates> H = obs->dhdx(*state);
560 // Note: Technically, this does calculate P * H.transpose() twice. However,
561 // when I was mucking around with some things, I found that in practice
562 // putting everything into one expression and letting Eigen optimize it
563 // directly actually improved performance relative to precalculating P *
564 // H.transpose().
565 const Eigen::Matrix<Scalar, kNStates, kNOutputs> K =
566 *P * H.transpose() * (H * *P * H.transpose() + obs->R).inverse();
567 const StateSquare Ptemp = (StateSquare::Identity() - K * H) * *P;
James Kuszmaulb2a2f352019-03-02 16:59:34 -0800568 *P = Ptemp;
James Kuszmaul06257f42020-05-09 15:40:09 -0700569 *state += K * (obs->z - obs->h(*state, obs->U));
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800570 }
571
572 void ProcessObservation(Observation *obs, const std::chrono::nanoseconds dt,
573 State *state, StateSquare *P) {
574 *state = obs->X_hat;
575 *P = obs->P;
James Kuszmaulf3950362020-10-11 18:29:15 -0700576 if (dt.count() != 0 && dt < kMaxTimestep) {
James Kuszmaul06257f42020-05-09 15:40:09 -0700577 PredictImpl(obs, dt, state, P);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800578 }
579 if (!(obs->h && obs->dhdx)) {
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800580 CHECK(obs->make_h);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800581 obs->make_h(*state, *P, &obs->h, &obs->dhdx);
582 }
James Kuszmaul06257f42020-05-09 15:40:09 -0700583 CorrectImpl(obs, state, P);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800584 }
585
James Kuszmauld478f872020-03-16 20:54:27 -0700586 DrivetrainConfig<double> dt_config_;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800587 State X_hat_;
James Kuszmauld478f872020-03-16 20:54:27 -0700588 StateFeedbackHybridPlantCoefficients<2, 2, 2, double>
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800589 velocity_drivetrain_coefficients_;
590 StateSquare A_continuous_;
591 StateSquare Q_continuous_;
592 StateSquare P_;
593 Eigen::Matrix<Scalar, kNOutputs, kNStates> H_encoders_and_gyro_;
594 Scalar encoder_noise_, gyro_noise_;
595 Eigen::Matrix<Scalar, kNStates, kNInputs> B_continuous_;
596
James Kuszmaul074429e2019-03-23 16:01:49 -0700597 bool have_zeroed_encoders_ = false;
598
James Kuszmaul91aa0cf2021-02-13 13:15:06 -0800599 // Whether to pay attention to accelerometer readings to compensate for wheel
600 // slip.
601 bool ignore_accel_ = false;
602
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800603 aos::PriorityQueue<Observation, kSaveSamples, std::less<Observation>>
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800604 observations_;
605
606 friend class testing::HybridEkfTest;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800607 friend class y2019::control_loops::testing::ParameterizedLocalizerTest;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800608}; // class HybridEkf
609
610template <typename Scalar>
611void HybridEkf<Scalar>::Correct(
612 const Output &z, const Input *U,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800613 std::function<void(const State &, const StateSquare &,
614 std::function<Output(const State &, const Input &)> *,
615 std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(
Austin Schuhd749d932020-12-30 21:38:40 -0800616 const State &)> *)>
617 make_h,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800618 std::function<Output(const State &, const Input &)> h,
619 std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(const State &)>
Austin Schuhd749d932020-12-30 21:38:40 -0800620 dhdx,
621 const Eigen::Matrix<Scalar, kNOutputs, kNOutputs> &R,
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800622 aos::monotonic_clock::time_point t) {
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800623 CHECK(!observations_.empty());
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800624 if (!observations_.full() && t < observations_.begin()->t) {
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800625 LOG(ERROR) << "Dropped an observation that was received before we "
626 "initialized.\n";
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800627 return;
628 }
James Kuszmaul06257f42020-05-09 15:40:09 -0700629 auto cur_it = observations_.PushFromBottom(
630 {t, t, State::Zero(), StateSquare::Zero(), Input::Zero(), z, make_h, h,
631 dhdx, R, StateSquare::Identity(), StateSquare::Zero(),
632 std::chrono::seconds(0), State::Zero()});
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800633 if (cur_it == observations_.end()) {
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800634 VLOG(1) << "Camera dropped off of end with time of "
635 << aos::time::DurationInSeconds(t.time_since_epoch())
636 << "s; earliest observation in "
637 "queue has time of "
638 << aos::time::DurationInSeconds(
639 observations_.begin()->t.time_since_epoch())
640 << "s.\n";
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800641 return;
642 }
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800643 // Now we populate any state information that depends on where the
644 // observation was inserted into the queue. X_hat and P must be populated
645 // from the values present in the observation *following* this one in
646 // the queue (note that the X_hat and P that we store in each observation
647 // is the values that they held after accounting for the previous
648 // measurement and before accounting for the time between the previous and
649 // current measurement). If we appended to the end of the queue, then
650 // we need to pull from X_hat_ and P_ specifically.
651 // Furthermore, for U:
652 // -If the observation was inserted at the end, then the user must've
653 // provided U and we use it.
654 // -Otherwise, only grab U if necessary.
655 auto next_it = cur_it;
656 ++next_it;
657 if (next_it == observations_.end()) {
658 cur_it->X_hat = X_hat_;
659 cur_it->P = P_;
660 // Note that if next_it == observations_.end(), then because we already
661 // checked for !observations_.empty(), we are guaranteed to have
662 // valid prev_it.
663 auto prev_it = cur_it;
664 --prev_it;
665 cur_it->prev_t = prev_it->t;
666 // TODO(james): Figure out a saner way of handling this.
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800667 CHECK(U != nullptr);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800668 cur_it->U = *U;
669 } else {
670 cur_it->X_hat = next_it->X_hat;
671 cur_it->P = next_it->P;
672 cur_it->prev_t = next_it->prev_t;
673 next_it->prev_t = cur_it->t;
674 cur_it->U = (U == nullptr) ? next_it->U : *U;
675 }
James Kuszmaul06257f42020-05-09 15:40:09 -0700676
677 if (kFullRewindOnEverySample) {
678 next_it = observations_.begin();
679 cur_it = next_it++;
680 }
681
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800682 // Now we need to rerun the predict step from the previous to the new
683 // observation as well as every following correct/predict up to the current
684 // time.
685 while (true) {
686 // We use X_hat_ and P_ to store the intermediate states, and then
687 // once we reach the end they will all be up-to-date.
688 ProcessObservation(&*cur_it, cur_it->t - cur_it->prev_t, &X_hat_, &P_);
James Kuszmaul891f4f12020-10-31 17:13:23 -0700689 // TOOD(james): Note that this can be triggered when there are extremely
690 // small values in P_. This is particularly likely if Scalar is just float
691 // and we are performing zero-time updates where the predict step never
692 // runs.
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800693 CHECK(X_hat_.allFinite());
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800694 if (next_it != observations_.end()) {
695 next_it->X_hat = X_hat_;
696 next_it->P = P_;
697 } else {
698 break;
699 }
700 ++cur_it;
701 ++next_it;
702 }
703}
704
705template <typename Scalar>
706void HybridEkf<Scalar>::InitializeMatrices() {
707 A_continuous_.setZero();
708 const Scalar diameter = 2.0 * dt_config_.robot_radius;
709 // Theta derivative
710 A_continuous_(kTheta, kLeftVelocity) = -1.0 / diameter;
711 A_continuous_(kTheta, kRightVelocity) = 1.0 / diameter;
712
713 // Encoder derivatives
714 A_continuous_(kLeftEncoder, kLeftVelocity) = 1.0;
James Kuszmaul074429e2019-03-23 16:01:49 -0700715 A_continuous_(kLeftEncoder, kAngularError) = 1.0;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800716 A_continuous_(kLeftEncoder, kLongitudinalVelocityOffset) = -1.0;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800717 A_continuous_(kRightEncoder, kRightVelocity) = 1.0;
James Kuszmaul074429e2019-03-23 16:01:49 -0700718 A_continuous_(kRightEncoder, kAngularError) = -1.0;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800719 A_continuous_(kRightEncoder, kLongitudinalVelocityOffset) = -1.0;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800720
721 // Pull velocity derivatives from velocity matrices.
722 // Note that this looks really awkward (doesn't use
723 // Eigen blocks) because someone decided that the full
James Kuszmaulbcd96fc2020-10-12 20:29:32 -0700724 // drivetrain Kalman Filter should have a weird convention.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800725 // TODO(james): Support shifting drivetrains with changing A_continuous
726 const auto &vel_coefs = velocity_drivetrain_coefficients_;
727 A_continuous_(kLeftVelocity, kLeftVelocity) = vel_coefs.A_continuous(0, 0);
728 A_continuous_(kLeftVelocity, kRightVelocity) = vel_coefs.A_continuous(0, 1);
729 A_continuous_(kRightVelocity, kLeftVelocity) = vel_coefs.A_continuous(1, 0);
730 A_continuous_(kRightVelocity, kRightVelocity) = vel_coefs.A_continuous(1, 1);
731
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800732 A_continuous_(kLongitudinalVelocityOffset, kLongitudinalVelocityOffset) =
733 -1.0 / kVelocityOffsetTimeConstant;
734 A_continuous_(kLateralVelocity, kLateralVelocity) =
735 -1.0 / kLateralVelocityTimeConstant;
736
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800737 // TODO(james): Decide what to do about these terms. They don't really matter
738 // too much when we have accelerometer readings available.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800739 B_continuous_.setZero();
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800740 B_continuous_.template block<1, 2>(kLeftVelocity, kLeftVoltage) =
James Kuszmauld478f872020-03-16 20:54:27 -0700741 vel_coefs.B_continuous.row(0).template cast<Scalar>();
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800742 B_continuous_.template block<1, 2>(kRightVelocity, kLeftVoltage) =
James Kuszmauld478f872020-03-16 20:54:27 -0700743 vel_coefs.B_continuous.row(1).template cast<Scalar>();
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800744 A_continuous_.template block<kNStates, 2>(0, kLeftVoltageError) =
745 B_continuous_.template block<kNStates, 2>(0, kLeftVoltage);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800746
747 Q_continuous_.setZero();
748 // TODO(james): Improve estimates of process noise--e.g., X/Y noise can
James Kuszmaul1057ce82019-02-09 17:58:24 -0800749 // probably be reduced when we are stopped because you rarely jump randomly.
750 // Or maybe it's more appropriate to scale wheelspeed noise with wheelspeed,
751 // since the wheels aren't likely to slip much stopped.
James Kuszmaula5632fe2019-03-23 20:28:33 -0700752 Q_continuous_(kX, kX) = 0.002;
753 Q_continuous_(kY, kY) = 0.002;
James Kuszmaul7f1a4082019-04-14 10:50:44 -0700754 Q_continuous_(kTheta, kTheta) = 0.0001;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800755 Q_continuous_(kLeftEncoder, kLeftEncoder) = std::pow(0.15, 2.0);
756 Q_continuous_(kRightEncoder, kRightEncoder) = std::pow(0.15, 2.0);
757 Q_continuous_(kLeftVelocity, kLeftVelocity) = std::pow(0.5, 2.0);
758 Q_continuous_(kRightVelocity, kRightVelocity) = std::pow(0.5, 2.0);
759 Q_continuous_(kLeftVoltageError, kLeftVoltageError) = std::pow(10.0, 2.0);
760 Q_continuous_(kRightVoltageError, kRightVoltageError) = std::pow(10.0, 2.0);
761 Q_continuous_(kAngularError, kAngularError) = std::pow(2.0, 2.0);
762 // This noise value largely governs whether we will trust the encoders or
763 // accelerometer more for estimating the robot position.
James Kuszmaul5398fae2020-02-17 16:44:03 -0800764 // Note that this also affects how we interpret camera measurements,
765 // particularly when using a heading/distance/skew measurement--if the
766 // noise on these numbers is particularly high, then we can end up with weird
767 // dynamics where a camera update both shifts our X/Y position and adjusts our
768 // velocity estimates substantially, causing the camera updates to create
Austin Schuhd749d932020-12-30 21:38:40 -0800769 // "momentum" and if we don't trust the encoders enough, then we have no way
770 // of determining that the velocity updates are bogus. This also interacts
771 // with kVelocityOffsetTimeConstant.
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800772 Q_continuous_(kLongitudinalVelocityOffset, kLongitudinalVelocityOffset) =
773 std::pow(1.1, 2.0);
774 Q_continuous_(kLateralVelocity, kLateralVelocity) = std::pow(0.1, 2.0);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800775
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800776 H_encoders_and_gyro_.setZero();
777 // Encoders are stored directly in the state matrix, so are a minor
778 // transform away.
779 H_encoders_and_gyro_(0, kLeftEncoder) = 1.0;
780 H_encoders_and_gyro_(1, kRightEncoder) = 1.0;
781 // Gyro rate is just the difference between right/left side speeds:
782 H_encoders_and_gyro_(2, kLeftVelocity) = -1.0 / diameter;
783 H_encoders_and_gyro_(2, kRightVelocity) = 1.0 / diameter;
784
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800785 encoder_noise_ = 5e-9;
786 gyro_noise_ = 1e-13;
Austin Schuh9fe68f72019-08-10 19:32:03 -0700787
788 X_hat_.setZero();
789 P_.setZero();
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800790}
791
792} // namespace drivetrain
793} // namespace control_loops
794} // namespace frc971
795
796#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_HYBRID_EKF_H_