blob: 737c1796696bb37d78924f810e78136e11b4e979 [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>
James Kuszmaul20a2b772024-03-15 22:46:46 -07005#include <optional>
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -08006
James Kuszmaul651fc3f2019-05-15 21:14:25 -07007#include "Eigen/Dense"
Philipp Schrader790cb542023-07-05 21:06:52 -07008
James Kuszmaul3c5b4d32020-02-11 17:22:14 -08009#include "aos/commonmath.h"
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080010#include "aos/containers/priority_queue.h"
James Kuszmaulfedc4612019-03-10 11:24:51 -070011#include "aos/util/math.h"
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080012#include "frc971/control_loops/c2d.h"
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080013#include "frc971/control_loops/drivetrain/drivetrain_config.h"
James Kuszmaul651fc3f2019-05-15 21:14:25 -070014#include "frc971/control_loops/runge_kutta.h"
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080015
Stephan Pleinesd99b1ee2024-02-02 20:56:44 -080016namespace y2019::control_loops::testing {
James Kuszmaul1057ce82019-02-09 17:58:24 -080017class ParameterizedLocalizerTest;
Stephan Pleinesd99b1ee2024-02-02 20:56:44 -080018} // namespace y2019::control_loops::testing
James Kuszmaul1057ce82019-02-09 17:58:24 -080019
Stephan Pleinesd99b1ee2024-02-02 20:56:44 -080020namespace frc971::control_loops::drivetrain {
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080021
22namespace testing {
23class HybridEkfTest;
24}
25
26// HybridEkf is an EKF for use in robot localization. It is currently
27// coded for use with drivetrains in particular, and so the states and inputs
28// are chosen as such.
29// The "Hybrid" part of the name refers to the fact that it can take in
30// measurements with variable time-steps.
31// measurements can also have been taken in the past and we maintain a buffer
32// so that we can replay the kalman filter whenever we get an old measurement.
33// Currently, this class provides the necessary utilities for doing
34// measurement updates with an encoder/gyro as well as a more generic
35// update function that can be used for arbitrary nonlinear updates (presumably
36// a camera update).
James Kuszmaul3c5b4d32020-02-11 17:22:14 -080037//
38// Discussion of the model:
39// In the current model, we try to rely primarily on IMU measurements for
40// estimating robot state--we also need additional information (some combination
41// of output voltages, encoders, and camera data) to help eliminate the biases
42// that can accumulate due to integration of IMU data.
43// We use IMU measurements as inputs rather than measurement outputs because
44// that seemed to be easier to implement. I tried initially running with
45// the IMU as a measurement, but it seemed to blow up the complexity of the
46// model.
47//
48// On each prediction update, we take in inputs of the left/right voltages and
49// the current measured longitudinal/lateral accelerations. In the current
50// setup, the accelerometer readings will be used for estimating how the
51// evolution of the longitudinal/lateral velocities. The voltages (and voltage
52// errors) will solely be used for estimating the current rotational velocity of
53// the robot (I do this because currently I suspect that the accelerometer is a
54// much better indicator of current robot state than the voltages). We also
55// deliberately decay all of the velocity estimates towards zero to help address
56// potential accelerometer biases. We use two separate decay models:
57// -The longitudinal velocity is modelled as decaying at a constant rate (see
58// the documentation on the VelocityAccel() method)--this needs a more
59// complex model because the robot will, under normal circumstances, be
60// travelling at non-zero velocities.
61// -The lateral velocity is modelled as exponentially decaying towards zero.
62// This is simpler to model and should be reasonably valid, since we will
63// not *normally* be travelling sideways consistently (this assumption may
64// need to be revisited).
65// -The "longitudinal velocity offset" (described below) also uses an
66// exponential decay, albeit with a different time constant. A future
67// improvement may remove the decay modelling on the longitudinal velocity
68// itself and instead use that decay model on the longitudinal velocity offset.
69// This would place a bit more trust in the encoder measurements but also
70// more correctly model situations where the robot is legitimately moving at
71// a certain velocity.
72//
73// For modelling how the drivetrain encoders evolve, and to help prevent the
74// aforementioned decay functions from affecting legitimate high-velocity
75// maneuvers too much, we have a "longitudinal velocity offset" term. This term
76// models the difference between the actual longitudinal velocity of the robot
77// (estimated by the average of the left/right velocities) and the velocity
78// experienced by the wheels (which can be observed from the encoders more
79// directly). Because we model this velocity offset as decaying towards zero,
80// what this will do is allow the encoders to be a constant velocity off from
81// the accelerometer updates for short periods of time but then gradually
82// pull the "actual" longitudinal velocity offset towards that of the encoders,
83// helping to reduce constant biases.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080084template <typename Scalar = double>
85class HybridEkf {
86 public:
87 // An enum specifying what each index in the state vector is for.
88 enum StateIdx {
James Kuszmaul3c5b4d32020-02-11 17:22:14 -080089 // Current X/Y position, in meters, of the robot.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080090 kX = 0,
91 kY = 1,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -080092 // Current heading of the robot.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080093 kTheta = 2,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -080094 // Current estimated encoder reading of the left wheels, in meters.
95 // Rezeroed once on startup.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080096 kLeftEncoder = 3,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -080097 // Current estimated actual velocity of the left side of the robot, in m/s.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -080098 kLeftVelocity = 4,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -080099 // Same variables, for the right side of the robot.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800100 kRightEncoder = 5,
101 kRightVelocity = 6,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800102 // Estimated offset to input voltage. Used as a generic error term, Volts.
James Kuszmaul074429e2019-03-23 16:01:49 -0700103 kLeftVoltageError = 7,
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700104 kRightVoltageError = 8,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800105 // These error terms are used to estimate the difference between the actual
106 // movement of the drivetrain and that implied by the wheel odometry.
107 // Angular error effectively estimates a constant angular rate offset of the
108 // encoders relative to the actual rotation of the robot.
109 // Semi-arbitrary units (we don't bother accounting for robot radius in
110 // this).
James Kuszmaul074429e2019-03-23 16:01:49 -0700111 kAngularError = 9,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800112 // Estimate of slip between the drivetrain wheels and the actual
113 // forwards/backwards velocity of the robot, in m/s.
114 // I.e., (left velocity + right velocity) / 2.0 = (left wheel velocity +
115 // right wheel velocity) / 2.0 + longitudinal velocity offset
116 kLongitudinalVelocityOffset = 10,
117 // Current estimate of the lateral velocity of the robot, in m/s.
118 // Positive implies the robot is moving to its left.
119 kLateralVelocity = 11,
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800120 };
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800121 static constexpr int kNStates = 12;
122 enum InputIdx {
123 // Left/right drivetrain voltages.
124 kLeftVoltage = 0,
125 kRightVoltage = 1,
126 // Current accelerometer readings, in m/s/s, along the longitudinal and
127 // lateral axes of the robot. Should be projected onto the X/Y plane, to
128 // compensate for tilt of the robot before being passed to this filter. The
129 // HybridEkf has no knowledge of the current pitch/roll of the robot, and so
130 // can't do anything to compensate for it.
131 kLongitudinalAccel = 2,
132 kLateralAccel = 3,
133 };
James Kuszmaul2971b5a2023-01-29 15:49:32 -0800134
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800135 static constexpr int kNInputs = 4;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800136 // Number of previous samples to save.
Austin Schuh6e660592021-10-17 17:37:33 -0700137 static constexpr int kSaveSamples = 200;
James Kuszmaul06257f42020-05-09 15:40:09 -0700138 // Whether we should completely rerun the entire stored history of
139 // kSaveSamples on every correction. Enabling this will increase overall CPU
140 // usage substantially; however, leaving it disabled makes it so that we are
141 // less likely to notice if processing camera frames is causing delays in the
142 // drivetrain.
143 // If we are having CPU issues, we have three easy avenues to improve things:
144 // (1) Reduce kSaveSamples (e.g., if all camera frames arive within
145 // 100 ms, then we can reduce kSaveSamples to be 25 (125 ms of samples)).
146 // (2) Don't actually rely on the ability to insert corrections into the
147 // timeline.
148 // (3) Set this to false.
149 static constexpr bool kFullRewindOnEverySample = false;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800150 // Assume that all correction steps will have kNOutputs
151 // dimensions.
152 // TODO(james): Relax this assumption; relaxing it requires
153 // figuring out how to deal with storing variable size
154 // observation matrices, though.
155 static constexpr int kNOutputs = 3;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800156 // Time constant to use for estimating how the longitudinal/lateral velocity
157 // offsets decay, in seconds.
James Kuszmaul5f6d1d42020-03-01 18:10:07 -0800158 static constexpr double kVelocityOffsetTimeConstant = 1.0;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800159 static constexpr double kLateralVelocityTimeConstant = 1.0;
James Kuszmaul91aa0cf2021-02-13 13:15:06 -0800160
James Kuszmaulf3950362020-10-11 18:29:15 -0700161 // The maximum allowable timestep--we use this to check for situations where
162 // measurement updates come in too infrequently and this might cause the
163 // integrator and discretization in the prediction step to be overly
164 // aggressive.
165 static constexpr std::chrono::milliseconds kMaxTimestep{20};
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800166 // Inputs are [left_volts, right_volts]
167 typedef Eigen::Matrix<Scalar, kNInputs, 1> Input;
168 // Outputs are either:
169 // [left_encoder, right_encoder, gyro_vel]; or [heading, distance, skew] to
170 // some target. This makes it so we don't have to figure out how we store
171 // variable-size measurement updates.
172 typedef Eigen::Matrix<Scalar, kNOutputs, 1> Output;
173 typedef Eigen::Matrix<Scalar, kNStates, kNStates> StateSquare;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800174 // State contains the states defined by the StateIdx enum. See comments there.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800175 typedef Eigen::Matrix<Scalar, kNStates, 1> State;
176
James Kuszmaul2971b5a2023-01-29 15:49:32 -0800177 // The following classes exist to allow us to support doing corections in the
178 // past by rewinding the EKF, calling the appropriate H and dhdx functions,
179 // and then playing everything back. Originally, this simply used
180 // std::function's, but doing so causes us to perform dynamic memory
181 // allocation in the core of the drivetrain control loop.
182 //
183 // The ExpectedObservationFunctor class serves to provide an interface for the
184 // actual H and dH/dX that the EKF itself needs. Most implementations end up
185 // just using this; in the degenerate case, ExpectedObservationFunctor could
186 // be implemented as a class that simply stores two std::functions and calls
187 // them when H() and DHDX() are called.
188 //
189 // The ObserveDeletion() and deleted() methods exist for sanity checking--we
190 // don't rely on them to do any work, but in order to ensure that memory is
191 // being managed correctly, we have the HybridEkf call ObserveDeletion() when
192 // it no longer needs an instance of the object.
193 class ExpectedObservationFunctor {
194 public:
195 virtual ~ExpectedObservationFunctor() = default;
196 // Return the expected measurement of the system for a given state and plant
197 // input.
198 virtual Output H(const State &state, const Input &input) = 0;
199 // Return the derivative of H() with respect to the state, given the current
200 // state.
201 virtual Eigen::Matrix<Scalar, kNOutputs, kNStates> DHDX(
202 const State &state) = 0;
203 virtual void ObserveDeletion() {
204 CHECK(!deleted_);
205 deleted_ = true;
206 }
207 bool deleted() const { return deleted_; }
208
209 private:
210 bool deleted_ = false;
211 };
212
213 // The ExpectedObservationBuilder creates a new ExpectedObservationFunctor.
214 // This is used for situations where in order to know what the correction
215 // methods even are we need to know the state at some time in the past. This
216 // is only used in the y2019 code and we've generally stopped using this
217 // pattern.
218 class ExpectedObservationBuilder {
219 public:
220 virtual ~ExpectedObservationBuilder() = default;
221 // The lifetime of the returned object should last at least until
222 // ObserveDeletion() is called on said object.
223 virtual ExpectedObservationFunctor *MakeExpectedObservations(
224 const State &state, const StateSquare &P) = 0;
225 void ObserveDeletion() {
226 CHECK(!deleted_);
227 deleted_ = true;
228 }
229 bool deleted() const { return deleted_; }
230
231 private:
232 bool deleted_ = false;
233 };
234
235 // The ExpectedObservationAllocator provides a utility class which manages the
236 // memory for a single type of correction step for a given localizer.
237 // Using the knowledge that at most kSaveSamples ExpectedObservation* objects
238 // can be referenced by the HybridEkf at any given time, this keeps an
239 // internal queue that more than mirrors the HybridEkf's internal queue, using
240 // the oldest spots in the queue to construct new ExpectedObservation*'s.
241 // This can be used with T as either a ExpectedObservationBuilder or
242 // ExpectedObservationFunctor. The appropriate Correct function will then be
243 // called in place of calling HybridEkf::Correct directly. Note that unless T
244 // implements both the Builder and Functor (which is generally discouraged),
245 // only one of the Correct* functions will build.
246 template <typename T>
247 class ExpectedObservationAllocator {
248 public:
249 ExpectedObservationAllocator(HybridEkf *ekf) : ekf_(ekf) {}
250 void CorrectKnownH(const Output &z, const Input *U, T H,
251 const Eigen::Matrix<Scalar, kNOutputs, kNOutputs> &R,
252 aos::monotonic_clock::time_point t) {
253 if (functors_.full()) {
254 CHECK(functors_.begin()->functor->deleted());
255 }
256 auto pushed = functors_.PushFromBottom(Pair{t, std::move(H)});
257 if (pushed == functors_.end()) {
258 VLOG(1) << "Observation dropped off bottom of queue.";
259 return;
260 }
261 ekf_->Correct(z, U, nullptr, &pushed->functor.value(), R, t);
262 }
263 void CorrectKnownHBuilder(
264 const Output &z, const Input *U, T builder,
265 const Eigen::Matrix<Scalar, kNOutputs, kNOutputs> &R,
266 aos::monotonic_clock::time_point t) {
267 if (functors_.full()) {
268 CHECK(functors_.begin()->functor->deleted());
269 }
270 auto pushed = functors_.PushFromBottom(Pair{t, std::move(builder)});
271 if (pushed == functors_.end()) {
272 VLOG(1) << "Observation dropped off bottom of queue.";
273 return;
274 }
275 ekf_->Correct(z, U, &pushed->functor.value(), nullptr, R, t);
276 }
277
278 private:
279 struct Pair {
280 aos::monotonic_clock::time_point t;
281 std::optional<T> functor;
282 friend bool operator<(const Pair &l, const Pair &r) { return l.t < r.t; }
283 };
284
285 HybridEkf *const ekf_;
286 aos::PriorityQueue<Pair, kSaveSamples + 1, std::less<Pair>> functors_;
287 };
288
289 // A simple implementation of ExpectedObservationFunctor for an LTI correction
290 // step. Does not store any external references, so overrides
291 // ObserveDeletion() to do nothing.
292 class LinearH : public ExpectedObservationFunctor {
293 public:
294 LinearH(const Eigen::Matrix<Scalar, kNOutputs, kNStates> &H) : H_(H) {}
295 virtual ~LinearH() = default;
296 Output H(const State &state, const Input &) final { return H_ * state; }
297 Eigen::Matrix<Scalar, kNOutputs, kNStates> DHDX(const State &) final {
298 return H_;
299 }
300 void ObserveDeletion() {}
301
302 private:
303 const Eigen::Matrix<Scalar, kNOutputs, kNStates> H_;
304 };
305
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800306 // Constructs a HybridEkf for a particular drivetrain.
307 // Currently, we use the drivetrain config for modelling constants
308 // (continuous time A and B matrices) and for the noise matrices for the
309 // encoders/gyro.
James Kuszmaul20a2b772024-03-15 22:46:46 -0700310 // If force_dt is set, then all predict steps will use a dt of force_dt.
311 // This can be used in situations where there is no reliable clock guiding
312 // the measurement updates, but the source is coming in at a reasonably
313 // consistent period.
314 HybridEkf(const DrivetrainConfig<double> &dt_config,
315 std::optional<std::chrono::nanoseconds> force_dt = std::nullopt)
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800316 : dt_config_(dt_config),
317 velocity_drivetrain_coefficients_(
318 dt_config.make_hybrid_drivetrain_velocity_loop()
319 .plant()
James Kuszmaul20a2b772024-03-15 22:46:46 -0700320 .coefficients()),
321 force_dt_(force_dt) {
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800322 InitializeMatrices();
323 }
324
325 // Set the initial guess of the state. Can only be called once, and before
James Kuszmaul20a2b772024-03-15 22:46:46 -0700326 // any measurement updates have occurred.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800327 void ResetInitialState(::aos::monotonic_clock::time_point t,
James Kuszmaul1057ce82019-02-09 17:58:24 -0800328 const State &state, const StateSquare &P) {
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800329 observations_.clear();
330 X_hat_ = state;
James Kuszmaul1057ce82019-02-09 17:58:24 -0800331 P_ = P;
James Kuszmaul06257f42020-05-09 15:40:09 -0700332 observations_.PushFromBottom({
333 t,
334 t,
335 X_hat_,
336 P_,
337 Input::Zero(),
338 Output::Zero(),
James Kuszmaul2971b5a2023-01-29 15:49:32 -0800339 nullptr,
340 &H_encoders_and_gyro_.value(),
James Kuszmaul06257f42020-05-09 15:40:09 -0700341 Eigen::Matrix<Scalar, kNOutputs, kNOutputs>::Identity(),
342 StateSquare::Identity(),
343 StateSquare::Zero(),
344 std::chrono::seconds(0),
345 State::Zero(),
346 });
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800347 }
348
349 // Correct with:
350 // A measurement z at time t with z = h(X_hat, U) + v where v has noise
351 // covariance R.
352 // Input U is applied from the previous timestep until time t.
353 // If t is later than any previous measurements, then U must be provided.
354 // If the measurement falls between two previous measurements, then U
355 // can be provided or not; if U is not provided, then it is filled in based
356 // on an assumption that the voltage was held constant between the time steps.
357 // TODO(james): Is it necessary to explicitly to provide a version with H as a
358 // matrix for linear cases?
James Kuszmaul2971b5a2023-01-29 15:49:32 -0800359 void Correct(const Output &z, const Input *U,
360 ExpectedObservationBuilder *observation_builder,
361 ExpectedObservationFunctor *expected_observations,
362 const Eigen::Matrix<Scalar, kNOutputs, kNOutputs> &R,
363 aos::monotonic_clock::time_point t);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800364
365 // A utility function for specifically updating with encoder and gyro
366 // measurements.
James Kuszmaul2700e0f2024-03-16 16:45:48 -0700367 void UpdateEncodersAndGyro(const std::optional<Scalar> left_encoder,
368 const std::optional<Scalar> right_encoder,
369 const Scalar gyro_rate,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800370 const Eigen::Matrix<Scalar, 2, 1> &voltage,
371 const Eigen::Matrix<Scalar, 3, 1> &accel,
372 aos::monotonic_clock::time_point t) {
373 Input U;
374 U.template block<2, 1>(0, 0) = voltage;
375 U.template block<2, 1>(kLongitudinalAccel, 0) =
376 accel.template block<2, 1>(0, 0);
377 RawUpdateEncodersAndGyro(left_encoder, right_encoder, gyro_rate, U, t);
378 }
379 // Version of UpdateEncodersAndGyro that takes a input matrix rather than
380 // taking in a voltage/acceleration separately.
James Kuszmaul2700e0f2024-03-16 16:45:48 -0700381 void RawUpdateEncodersAndGyro(const std::optional<Scalar> left_encoder,
382 const std::optional<Scalar> right_encoder,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800383 const Scalar gyro_rate, const Input &U,
384 aos::monotonic_clock::time_point t) {
James Kuszmaul074429e2019-03-23 16:01:49 -0700385 // Because the check below for have_zeroed_encoders_ will add an
386 // Observation, do a check here to ensure that initialization has been
387 // performed and so there is at least one observation.
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800388 CHECK(!observations_.empty());
James Kuszmaul074429e2019-03-23 16:01:49 -0700389 if (!have_zeroed_encoders_) {
390 // This logic handles ensuring that on the first encoder reading, we
391 // update the internal state for the encoders to match the reading.
392 // Otherwise, if we restart the drivetrain without restarting
393 // wpilib_interface, then we can get some obnoxious initial corrections
394 // that mess up the localization.
395 State newstate = X_hat_;
James Kuszmaul2700e0f2024-03-16 16:45:48 -0700396 have_zeroed_encoders_ = true;
397 if (left_encoder.has_value()) {
398 newstate(kLeftEncoder) = left_encoder.value();
399 } else {
400 have_zeroed_encoders_ = false;
401 }
402 if (right_encoder.has_value()) {
403 newstate(kRightEncoder) = right_encoder.value();
404 } else {
405 have_zeroed_encoders_ = false;
406 }
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800407 newstate(kLeftVoltageError) = 0.0;
408 newstate(kRightVoltageError) = 0.0;
409 newstate(kAngularError) = 0.0;
410 newstate(kLongitudinalVelocityOffset) = 0.0;
411 newstate(kLateralVelocity) = 0.0;
James Kuszmaul20a2b772024-03-15 22:46:46 -0700412 ResetInitialState(t, newstate, P_);
James Kuszmaul074429e2019-03-23 16:01:49 -0700413 }
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800414
James Kuszmaul2700e0f2024-03-16 16:45:48 -0700415 Output z(left_encoder.value_or(0.0), right_encoder.value_or(0.0),
416 gyro_rate);
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800417
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800418 Eigen::Matrix<Scalar, kNOutputs, kNOutputs> R;
419 R.setZero();
420 R.diagonal() << encoder_noise_, encoder_noise_, gyro_noise_;
James Kuszmaul2971b5a2023-01-29 15:49:32 -0800421 CHECK(H_encoders_and_gyro_.has_value());
James Kuszmaul2700e0f2024-03-16 16:45:48 -0700422 CHECK(H_gyro_only_.has_value());
423 LinearH *H = &H_encoders_and_gyro_.value();
424 if (!left_encoder.has_value() || !right_encoder.has_value()) {
425 H = &H_gyro_only_.value();
426 }
427 Correct(z, &U, nullptr, H, R, t);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800428 }
429
430 // Sundry accessor:
431 State X_hat() const { return X_hat_; }
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800432 Scalar X_hat(long i) const { return X_hat_(i); }
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800433 StateSquare P() const { return P_; }
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800434 aos::monotonic_clock::time_point latest_t() const {
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800435 return observations_.top().t;
436 }
437
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800438 static Scalar CalcLongitudinalVelocity(const State &X) {
439 return (X(kLeftVelocity) + X(kRightVelocity)) / 2.0;
440 }
441
442 Scalar CalcYawRate(const State &X) const {
443 return (X(kRightVelocity) - X(kLeftVelocity)) / 2.0 /
444 dt_config_.robot_radius;
445 }
446
James Kuszmaul06257f42020-05-09 15:40:09 -0700447 // Returns the last state before the specified time.
448 // Returns nullopt if time is older than the oldest measurement.
449 std::optional<State> LastStateBeforeTime(
450 aos::monotonic_clock::time_point time) {
451 if (observations_.empty() || observations_.begin()->t > time) {
452 return std::nullopt;
453 }
454 for (const auto &observation : observations_) {
455 if (observation.t > time) {
456 // Note that observation.X_hat actually references the _previous_ X_hat.
457 return observation.X_hat;
458 }
459 }
460 return X_hat();
461 }
James Kuszmaulba59dc92022-03-12 10:46:54 -0800462 std::optional<State> OldestState() {
463 if (observations_.empty()) {
464 return std::nullopt;
465 }
466 return observations_.begin()->X_hat;
467 }
James Kuszmaul06257f42020-05-09 15:40:09 -0700468
469 // Returns the most recent input vector.
470 Input MostRecentInput() {
471 CHECK(!observations_.empty());
472 Input U = observations_.top().U;
473 return U;
474 }
475
James Kuszmaul91aa0cf2021-02-13 13:15:06 -0800476 void set_ignore_accel(bool ignore_accel) { ignore_accel_ = ignore_accel; }
477
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800478 private:
479 struct Observation {
James Kuszmaul2971b5a2023-01-29 15:49:32 -0800480 Observation(aos::monotonic_clock::time_point t,
481 aos::monotonic_clock::time_point prev_t, State X_hat,
482 StateSquare P, Input U, Output z,
483 ExpectedObservationBuilder *make_h,
484 ExpectedObservationFunctor *h,
485 Eigen::Matrix<Scalar, kNOutputs, kNOutputs> R, StateSquare A_d,
486 StateSquare Q_d,
487 aos::monotonic_clock::duration discretization_time,
488 State predict_update)
489 : t(t),
490 prev_t(prev_t),
491 X_hat(X_hat),
492 P(P),
493 U(U),
494 z(z),
495 make_h(make_h),
496 h(h),
497 R(R),
498 A_d(A_d),
499 Q_d(Q_d),
500 discretization_time(discretization_time),
501 predict_update(predict_update) {}
502 Observation(const Observation &) = delete;
503 Observation &operator=(const Observation &) = delete;
504 // Move-construct an observation by copying over the contents of the struct
505 // and then clearing the old Observation's pointers so that it doesn't try
506 // to clean things up.
507 Observation(Observation &&o)
508 : Observation(o.t, o.prev_t, o.X_hat, o.P, o.U, o.z, o.make_h, o.h, o.R,
509 o.A_d, o.Q_d, o.discretization_time, o.predict_update) {
510 o.make_h = nullptr;
511 o.h = nullptr;
512 }
513 Observation &operator=(Observation &&observation) = delete;
514 ~Observation() {
515 // Observe h being deleted first, since make_h may own its memory.
516 // Shouldn't actually matter, though.
517 if (h != nullptr) {
518 h->ObserveDeletion();
519 }
520 if (make_h != nullptr) {
521 make_h->ObserveDeletion();
522 }
523 }
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800524 // Time when the observation was taken.
525 aos::monotonic_clock::time_point t;
526 // Time that the previous observation was taken:
527 aos::monotonic_clock::time_point prev_t;
528 // Estimate of state at previous observation time t, after accounting for
529 // the previous observation.
530 State X_hat;
531 // Noise matrix corresponding to X_hat_.
532 StateSquare P;
533 // The input applied from previous observation until time t.
534 Input U;
535 // Measurement taken at that time.
536 Output z;
537 // A function to create h and dhdx from a given position/covariance
538 // estimate. This is used by the camera to make it so that we only have to
539 // match targets once.
540 // Only called if h and dhdx are empty.
James Kuszmaul2971b5a2023-01-29 15:49:32 -0800541 ExpectedObservationBuilder *make_h = nullptr;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800542 // A function to calculate the expected output at a given state/input.
543 // TODO(james): For encoders/gyro, it is linear and the function call may
544 // be expensive. Potential source of optimization.
James Kuszmaul2971b5a2023-01-29 15:49:32 -0800545 ExpectedObservationFunctor *h = nullptr;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800546 // The measurement noise matrix.
547 Eigen::Matrix<Scalar, kNOutputs, kNOutputs> R;
548
James Kuszmaul06257f42020-05-09 15:40:09 -0700549 // Discretized A and Q to use on this update step. These will only be
550 // recalculated if the timestep changes.
551 StateSquare A_d;
552 StateSquare Q_d;
553 aos::monotonic_clock::duration discretization_time;
554
555 // A cached value indicating how much we change X_hat in the prediction step
556 // of this Observation.
557 State predict_update;
558
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800559 // In order to sort the observations in the PriorityQueue object, we
560 // need a comparison function.
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700561 friend bool operator<(const Observation &l, const Observation &r) {
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800562 return l.t < r.t;
563 }
564 };
565
566 void InitializeMatrices();
567
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800568 // These constants and functions define how the longitudinal velocity
569 // (the average of the left and right velocities) decays. We model it as
570 // decaying at a constant rate, except very near zero where the decay rate is
571 // exponential (this is more numerically stable than just using a constant
572 // rate the whole time). We use this model rather than a simpler exponential
573 // decay because an exponential decay will result in the robot's velocity
574 // estimate consistently being far too low when at high velocities, and since
575 // the acceleromater-based estimate of the velocity will only drift at a
576 // relatively slow rate and doesn't get worse at higher velocities, we can
577 // safely decay pretty slowly.
578 static constexpr double kMaxVelocityAccel = 0.005;
579 static constexpr double kMaxVelocityGain = 1.0;
580 static Scalar VelocityAccel(Scalar velocity) {
581 return -std::clamp(kMaxVelocityGain * velocity, -kMaxVelocityAccel,
582 kMaxVelocityAccel);
583 }
584
585 static Scalar VelocityAccelDiff(Scalar velocity) {
586 return (std::abs(kMaxVelocityGain * velocity) > kMaxVelocityAccel)
587 ? 0.0
588 : -kMaxVelocityGain;
589 }
590
591 // Returns the "A" matrix for a given state. See DiffEq for discussion of
592 // ignore_accel.
James Kuszmaul91aa0cf2021-02-13 13:15:06 -0800593 StateSquare AForState(const State &X, bool ignore_accel) const {
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800594 // Calculate the A matrix for a given state. Note that A = partial Xdot /
595 // partial X. This is distinct from saying that Xdot = A * X. This is
596 // particularly relevant for the (kX, kTheta) members which otherwise seem
597 // odd.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800598 StateSquare A_continuous = A_continuous_;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800599 const Scalar theta = X(kTheta);
600 const Scalar stheta = std::sin(theta);
601 const Scalar ctheta = std::cos(theta);
602 const Scalar lng_vel = CalcLongitudinalVelocity(X);
603 const Scalar lat_vel = X(kLateralVelocity);
604 const Scalar diameter = 2.0 * dt_config_.robot_radius;
605 const Scalar yaw_rate = CalcYawRate(X);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800606 // X and Y derivatives
Austin Schuhd749d932020-12-30 21:38:40 -0800607 A_continuous(kX, kTheta) = -stheta * lng_vel - ctheta * lat_vel;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800608 A_continuous(kX, kLeftVelocity) = ctheta / 2.0;
609 A_continuous(kX, kRightVelocity) = ctheta / 2.0;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800610 A_continuous(kX, kLateralVelocity) = -stheta;
611 A_continuous(kY, kTheta) = ctheta * lng_vel - stheta * lat_vel;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800612 A_continuous(kY, kLeftVelocity) = stheta / 2.0;
613 A_continuous(kY, kRightVelocity) = stheta / 2.0;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800614 A_continuous(kY, kLateralVelocity) = ctheta;
615
616 if (!ignore_accel) {
617 const Eigen::Matrix<Scalar, 1, kNStates> lng_vel_row =
618 (A_continuous.row(kLeftVelocity) + A_continuous.row(kRightVelocity)) /
619 2.0;
620 A_continuous.row(kLeftVelocity) -= lng_vel_row;
621 A_continuous.row(kRightVelocity) -= lng_vel_row;
622 // Terms to account for centripetal accelerations.
623 // lateral centripetal accel = -yaw_rate * lng_vel
624 A_continuous(kLateralVelocity, kLeftVelocity) +=
625 X(kLeftVelocity) / diameter;
626 A_continuous(kLateralVelocity, kRightVelocity) +=
627 -X(kRightVelocity) / diameter;
628 A_continuous(kRightVelocity, kLateralVelocity) += yaw_rate;
629 A_continuous(kLeftVelocity, kLateralVelocity) += yaw_rate;
630 const Scalar dlng_accel_dwheel_vel = X(kLateralVelocity) / diameter;
631 A_continuous(kRightVelocity, kRightVelocity) += dlng_accel_dwheel_vel;
632 A_continuous(kLeftVelocity, kRightVelocity) += dlng_accel_dwheel_vel;
633 A_continuous(kRightVelocity, kLeftVelocity) += -dlng_accel_dwheel_vel;
634 A_continuous(kLeftVelocity, kLeftVelocity) += -dlng_accel_dwheel_vel;
635
636 A_continuous(kRightVelocity, kRightVelocity) +=
637 VelocityAccelDiff(lng_vel) / 2.0;
638 A_continuous(kRightVelocity, kLeftVelocity) +=
639 VelocityAccelDiff(lng_vel) / 2.0;
640 A_continuous(kLeftVelocity, kRightVelocity) +=
641 VelocityAccelDiff(lng_vel) / 2.0;
642 A_continuous(kLeftVelocity, kLeftVelocity) +=
643 VelocityAccelDiff(lng_vel) / 2.0;
644 }
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800645 return A_continuous;
646 }
647
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800648 // Returns dX / dt given X and U. If ignore_accel is set, then we ignore the
649 // accelerometer-based components of U (this is solely used in testing).
James Kuszmaul91aa0cf2021-02-13 13:15:06 -0800650 State DiffEq(const State &X, const Input &U, bool ignore_accel) const {
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800651 State Xdot = A_continuous_ * X + B_continuous_ * U;
652 // And then we need to add on the terms for the x/y change:
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800653 const Scalar theta = X(kTheta);
654 const Scalar lng_vel = CalcLongitudinalVelocity(X);
655 const Scalar lat_vel = X(kLateralVelocity);
656 const Scalar stheta = std::sin(theta);
657 const Scalar ctheta = std::cos(theta);
658 Xdot(kX) = ctheta * lng_vel - stheta * lat_vel;
659 Xdot(kY) = stheta * lng_vel + ctheta * lat_vel;
660
661 const Scalar yaw_rate = CalcYawRate(X);
662 const Scalar expected_lat_accel = lng_vel * yaw_rate;
663 const Scalar expected_lng_accel =
664 CalcLongitudinalVelocity(Xdot) - yaw_rate * lat_vel;
Austin Schuhd749d932020-12-30 21:38:40 -0800665 const Scalar lng_accel_offset = U(kLongitudinalAccel) - expected_lng_accel;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800666 constexpr double kAccelWeight = 1.0;
667 if (!ignore_accel) {
668 Xdot(kLeftVelocity) += kAccelWeight * lng_accel_offset;
669 Xdot(kRightVelocity) += kAccelWeight * lng_accel_offset;
670 Xdot(kLateralVelocity) += U(kLateralAccel) - expected_lat_accel;
671
672 Xdot(kRightVelocity) += VelocityAccel(lng_vel);
673 Xdot(kLeftVelocity) += VelocityAccel(lng_vel);
674 }
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800675 return Xdot;
676 }
677
James Kuszmaul06257f42020-05-09 15:40:09 -0700678 void PredictImpl(Observation *obs, std::chrono::nanoseconds dt, State *state,
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800679 StateSquare *P) {
James Kuszmaul20a2b772024-03-15 22:46:46 -0700680 if (force_dt_.has_value()) {
681 dt = force_dt_.value();
682 }
James Kuszmaul06257f42020-05-09 15:40:09 -0700683 // Only recalculate the discretization if the timestep has changed.
684 // Technically, this isn't quite correct, since the discretization will
685 // change depending on the current state. However, the slight loss of
686 // precision seems acceptable for the sake of significantly reducing CPU
687 // usage.
688 if (obs->discretization_time != dt) {
689 // TODO(james): By far the biggest CPU sink in the localization appears to
690 // be this discretization--it's possible the spline code spikes higher,
691 // but it doesn't create anywhere near the same sustained load. There
692 // are a few potential options for optimizing this code, but none of
693 // them are entirely trivial, e.g. we could:
694 // -Reduce the number of states (this function grows at O(kNStates^3))
695 // -Adjust the discretization function itself (there're a few things we
696 // can tune there).
697 // -Try to come up with some sort of lookup table or other way of
698 // pre-calculating A_d and Q_d.
699 // I also have to figure out how much we care about the precision of
700 // some of these values--I don't think we care much, but we probably
701 // do want to maintain some of the structure of the matrices.
James Kuszmaul91aa0cf2021-02-13 13:15:06 -0800702 const StateSquare A_c = AForState(*state, ignore_accel_);
James Kuszmaul06257f42020-05-09 15:40:09 -0700703 controls::DiscretizeQAFast(Q_continuous_, A_c, dt, &obs->Q_d, &obs->A_d);
704 obs->discretization_time = dt;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800705
James Kuszmaul06257f42020-05-09 15:40:09 -0700706 obs->predict_update =
707 RungeKuttaU(
James Kuszmaul91aa0cf2021-02-13 13:15:06 -0800708 [this](const State &X, const Input &U) {
709 return DiffEq(X, U, ignore_accel_);
710 },
James Kuszmaul06257f42020-05-09 15:40:09 -0700711 *state, obs->U, aos::time::DurationInSeconds(dt)) -
712 *state;
713 }
James Kuszmaulb2a2f352019-03-02 16:59:34 -0800714
James Kuszmaul06257f42020-05-09 15:40:09 -0700715 *state += obs->predict_update;
716
717 StateSquare Ptemp = obs->A_d * *P * obs->A_d.transpose() + obs->Q_d;
James Kuszmaulb2a2f352019-03-02 16:59:34 -0800718 *P = Ptemp;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800719 }
720
James Kuszmaul06257f42020-05-09 15:40:09 -0700721 void CorrectImpl(Observation *obs, State *state, StateSquare *P) {
James Kuszmaul2971b5a2023-01-29 15:49:32 -0800722 const Eigen::Matrix<Scalar, kNOutputs, kNStates> H = obs->h->DHDX(*state);
James Kuszmaul06257f42020-05-09 15:40:09 -0700723 // Note: Technically, this does calculate P * H.transpose() twice. However,
724 // when I was mucking around with some things, I found that in practice
725 // putting everything into one expression and letting Eigen optimize it
726 // directly actually improved performance relative to precalculating P *
727 // H.transpose().
728 const Eigen::Matrix<Scalar, kNStates, kNOutputs> K =
729 *P * H.transpose() * (H * *P * H.transpose() + obs->R).inverse();
730 const StateSquare Ptemp = (StateSquare::Identity() - K * H) * *P;
James Kuszmaulb2a2f352019-03-02 16:59:34 -0800731 *P = Ptemp;
James Kuszmaul2971b5a2023-01-29 15:49:32 -0800732 *state += K * (obs->z - obs->h->H(*state, obs->U));
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800733 }
734
735 void ProcessObservation(Observation *obs, const std::chrono::nanoseconds dt,
736 State *state, StateSquare *P) {
737 *state = obs->X_hat;
738 *P = obs->P;
James Kuszmaulf3950362020-10-11 18:29:15 -0700739 if (dt.count() != 0 && dt < kMaxTimestep) {
James Kuszmaul06257f42020-05-09 15:40:09 -0700740 PredictImpl(obs, dt, state, P);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800741 }
James Kuszmaul2971b5a2023-01-29 15:49:32 -0800742 if (obs->h == nullptr) {
743 CHECK(obs->make_h != nullptr);
744 obs->h = CHECK_NOTNULL(obs->make_h->MakeExpectedObservations(*state, *P));
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800745 }
James Kuszmaul06257f42020-05-09 15:40:09 -0700746 CorrectImpl(obs, state, P);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800747 }
748
James Kuszmauld478f872020-03-16 20:54:27 -0700749 DrivetrainConfig<double> dt_config_;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800750 State X_hat_;
James Kuszmauld478f872020-03-16 20:54:27 -0700751 StateFeedbackHybridPlantCoefficients<2, 2, 2, double>
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800752 velocity_drivetrain_coefficients_;
James Kuszmaul20a2b772024-03-15 22:46:46 -0700753 std::optional<std::chrono::nanoseconds> force_dt_;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800754 StateSquare A_continuous_;
755 StateSquare Q_continuous_;
756 StateSquare P_;
James Kuszmaul2971b5a2023-01-29 15:49:32 -0800757 std::optional<LinearH> H_encoders_and_gyro_;
James Kuszmaul2700e0f2024-03-16 16:45:48 -0700758 std::optional<LinearH> H_gyro_only_;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800759 Scalar encoder_noise_, gyro_noise_;
760 Eigen::Matrix<Scalar, kNStates, kNInputs> B_continuous_;
761
James Kuszmaul074429e2019-03-23 16:01:49 -0700762 bool have_zeroed_encoders_ = false;
763
James Kuszmaul91aa0cf2021-02-13 13:15:06 -0800764 // Whether to pay attention to accelerometer readings to compensate for wheel
765 // slip.
766 bool ignore_accel_ = false;
767
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800768 aos::PriorityQueue<Observation, kSaveSamples, std::less<Observation>>
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800769 observations_;
770
771 friend class testing::HybridEkfTest;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800772 friend class y2019::control_loops::testing::ParameterizedLocalizerTest;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800773}; // class HybridEkf
774
775template <typename Scalar>
776void HybridEkf<Scalar>::Correct(
777 const Output &z, const Input *U,
James Kuszmaul2971b5a2023-01-29 15:49:32 -0800778 ExpectedObservationBuilder *observation_builder,
779 ExpectedObservationFunctor *expected_observations,
Austin Schuhd749d932020-12-30 21:38:40 -0800780 const Eigen::Matrix<Scalar, kNOutputs, kNOutputs> &R,
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800781 aos::monotonic_clock::time_point t) {
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800782 CHECK(!observations_.empty());
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800783 if (!observations_.full() && t < observations_.begin()->t) {
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800784 AOS_LOG(ERROR,
785 "Dropped an observation that was received before we "
786 "initialized.\n");
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800787 return;
788 }
James Kuszmaul06257f42020-05-09 15:40:09 -0700789 auto cur_it = observations_.PushFromBottom(
James Kuszmaul2971b5a2023-01-29 15:49:32 -0800790 {t, t, State::Zero(), StateSquare::Zero(), Input::Zero(), z,
791 observation_builder, expected_observations, R, StateSquare::Identity(),
792 StateSquare::Zero(), std::chrono::seconds(0), State::Zero()});
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800793 if (cur_it == observations_.end()) {
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800794 VLOG(1) << "Camera dropped off of end with time of "
795 << aos::time::DurationInSeconds(t.time_since_epoch())
796 << "s; earliest observation in "
797 "queue has time of "
798 << aos::time::DurationInSeconds(
799 observations_.begin()->t.time_since_epoch())
800 << "s.\n";
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800801 return;
802 }
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800803 // Now we populate any state information that depends on where the
804 // observation was inserted into the queue. X_hat and P must be populated
805 // from the values present in the observation *following* this one in
806 // the queue (note that the X_hat and P that we store in each observation
807 // is the values that they held after accounting for the previous
808 // measurement and before accounting for the time between the previous and
809 // current measurement). If we appended to the end of the queue, then
810 // we need to pull from X_hat_ and P_ specifically.
811 // Furthermore, for U:
812 // -If the observation was inserted at the end, then the user must've
813 // provided U and we use it.
814 // -Otherwise, only grab U if necessary.
815 auto next_it = cur_it;
816 ++next_it;
817 if (next_it == observations_.end()) {
818 cur_it->X_hat = X_hat_;
819 cur_it->P = P_;
820 // Note that if next_it == observations_.end(), then because we already
821 // checked for !observations_.empty(), we are guaranteed to have
822 // valid prev_it.
823 auto prev_it = cur_it;
824 --prev_it;
825 cur_it->prev_t = prev_it->t;
826 // TODO(james): Figure out a saner way of handling this.
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800827 CHECK(U != nullptr);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800828 cur_it->U = *U;
829 } else {
830 cur_it->X_hat = next_it->X_hat;
831 cur_it->P = next_it->P;
832 cur_it->prev_t = next_it->prev_t;
833 next_it->prev_t = cur_it->t;
834 cur_it->U = (U == nullptr) ? next_it->U : *U;
835 }
James Kuszmaul06257f42020-05-09 15:40:09 -0700836
837 if (kFullRewindOnEverySample) {
838 next_it = observations_.begin();
839 cur_it = next_it++;
840 }
841
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800842 // Now we need to rerun the predict step from the previous to the new
843 // observation as well as every following correct/predict up to the current
844 // time.
845 while (true) {
846 // We use X_hat_ and P_ to store the intermediate states, and then
847 // once we reach the end they will all be up-to-date.
848 ProcessObservation(&*cur_it, cur_it->t - cur_it->prev_t, &X_hat_, &P_);
James Kuszmaul891f4f12020-10-31 17:13:23 -0700849 // TOOD(james): Note that this can be triggered when there are extremely
850 // small values in P_. This is particularly likely if Scalar is just float
851 // and we are performing zero-time updates where the predict step never
852 // runs.
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800853 CHECK(X_hat_.allFinite());
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800854 if (next_it != observations_.end()) {
855 next_it->X_hat = X_hat_;
856 next_it->P = P_;
857 } else {
858 break;
859 }
860 ++cur_it;
861 ++next_it;
862 }
863}
864
865template <typename Scalar>
866void HybridEkf<Scalar>::InitializeMatrices() {
867 A_continuous_.setZero();
868 const Scalar diameter = 2.0 * dt_config_.robot_radius;
869 // Theta derivative
870 A_continuous_(kTheta, kLeftVelocity) = -1.0 / diameter;
871 A_continuous_(kTheta, kRightVelocity) = 1.0 / diameter;
872
873 // Encoder derivatives
874 A_continuous_(kLeftEncoder, kLeftVelocity) = 1.0;
James Kuszmaul074429e2019-03-23 16:01:49 -0700875 A_continuous_(kLeftEncoder, kAngularError) = 1.0;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800876 A_continuous_(kLeftEncoder, kLongitudinalVelocityOffset) = -1.0;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800877 A_continuous_(kRightEncoder, kRightVelocity) = 1.0;
James Kuszmaul074429e2019-03-23 16:01:49 -0700878 A_continuous_(kRightEncoder, kAngularError) = -1.0;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800879 A_continuous_(kRightEncoder, kLongitudinalVelocityOffset) = -1.0;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800880
881 // Pull velocity derivatives from velocity matrices.
882 // Note that this looks really awkward (doesn't use
883 // Eigen blocks) because someone decided that the full
James Kuszmaulbcd96fc2020-10-12 20:29:32 -0700884 // drivetrain Kalman Filter should have a weird convention.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800885 // TODO(james): Support shifting drivetrains with changing A_continuous
886 const auto &vel_coefs = velocity_drivetrain_coefficients_;
887 A_continuous_(kLeftVelocity, kLeftVelocity) = vel_coefs.A_continuous(0, 0);
888 A_continuous_(kLeftVelocity, kRightVelocity) = vel_coefs.A_continuous(0, 1);
889 A_continuous_(kRightVelocity, kLeftVelocity) = vel_coefs.A_continuous(1, 0);
890 A_continuous_(kRightVelocity, kRightVelocity) = vel_coefs.A_continuous(1, 1);
891
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800892 A_continuous_(kLongitudinalVelocityOffset, kLongitudinalVelocityOffset) =
893 -1.0 / kVelocityOffsetTimeConstant;
894 A_continuous_(kLateralVelocity, kLateralVelocity) =
895 -1.0 / kLateralVelocityTimeConstant;
896
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800897 // TODO(james): Decide what to do about these terms. They don't really matter
898 // too much when we have accelerometer readings available.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800899 B_continuous_.setZero();
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800900 B_continuous_.template block<1, 2>(kLeftVelocity, kLeftVoltage) =
James Kuszmauld478f872020-03-16 20:54:27 -0700901 vel_coefs.B_continuous.row(0).template cast<Scalar>();
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800902 B_continuous_.template block<1, 2>(kRightVelocity, kLeftVoltage) =
James Kuszmauld478f872020-03-16 20:54:27 -0700903 vel_coefs.B_continuous.row(1).template cast<Scalar>();
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800904 A_continuous_.template block<kNStates, 2>(0, kLeftVoltageError) =
905 B_continuous_.template block<kNStates, 2>(0, kLeftVoltage);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800906
907 Q_continuous_.setZero();
908 // TODO(james): Improve estimates of process noise--e.g., X/Y noise can
James Kuszmaul1057ce82019-02-09 17:58:24 -0800909 // probably be reduced when we are stopped because you rarely jump randomly.
910 // Or maybe it's more appropriate to scale wheelspeed noise with wheelspeed,
911 // since the wheels aren't likely to slip much stopped.
James Kuszmaula5632fe2019-03-23 20:28:33 -0700912 Q_continuous_(kX, kX) = 0.002;
913 Q_continuous_(kY, kY) = 0.002;
James Kuszmaul7f1a4082019-04-14 10:50:44 -0700914 Q_continuous_(kTheta, kTheta) = 0.0001;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800915 Q_continuous_(kLeftEncoder, kLeftEncoder) = std::pow(0.15, 2.0);
916 Q_continuous_(kRightEncoder, kRightEncoder) = std::pow(0.15, 2.0);
James Kuszmaul592055e2024-03-23 20:12:59 -0700917 Q_continuous_(kLeftVelocity, kLeftVelocity) = std::pow(0.1, 2.0);
918 Q_continuous_(kRightVelocity, kRightVelocity) = std::pow(0.1, 2.0);
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800919 Q_continuous_(kLeftVoltageError, kLeftVoltageError) = std::pow(10.0, 2.0);
920 Q_continuous_(kRightVoltageError, kRightVoltageError) = std::pow(10.0, 2.0);
921 Q_continuous_(kAngularError, kAngularError) = std::pow(2.0, 2.0);
922 // This noise value largely governs whether we will trust the encoders or
923 // accelerometer more for estimating the robot position.
James Kuszmaul5398fae2020-02-17 16:44:03 -0800924 // Note that this also affects how we interpret camera measurements,
925 // particularly when using a heading/distance/skew measurement--if the
926 // noise on these numbers is particularly high, then we can end up with weird
927 // dynamics where a camera update both shifts our X/Y position and adjusts our
928 // velocity estimates substantially, causing the camera updates to create
Austin Schuhd749d932020-12-30 21:38:40 -0800929 // "momentum" and if we don't trust the encoders enough, then we have no way
930 // of determining that the velocity updates are bogus. This also interacts
931 // with kVelocityOffsetTimeConstant.
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800932 Q_continuous_(kLongitudinalVelocityOffset, kLongitudinalVelocityOffset) =
James Kuszmaul592055e2024-03-23 20:12:59 -0700933 std::pow(0.01, 2.0);
934 Q_continuous_(kLateralVelocity, kLateralVelocity) = std::pow(0.01, 2.0);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800935
James Kuszmaul2971b5a2023-01-29 15:49:32 -0800936 {
937 Eigen::Matrix<Scalar, kNOutputs, kNStates> H_encoders_and_gyro;
938 H_encoders_and_gyro.setZero();
James Kuszmaul2700e0f2024-03-16 16:45:48 -0700939 // Gyro rate is just the difference between right/left side speeds:
940 H_encoders_and_gyro(2, kLeftVelocity) = -1.0 / diameter;
941 H_encoders_and_gyro(2, kRightVelocity) = 1.0 / diameter;
942 H_gyro_only_.emplace(H_encoders_and_gyro);
James Kuszmaul2971b5a2023-01-29 15:49:32 -0800943 // Encoders are stored directly in the state matrix, so are a minor
944 // transform away.
945 H_encoders_and_gyro(0, kLeftEncoder) = 1.0;
946 H_encoders_and_gyro(1, kRightEncoder) = 1.0;
James Kuszmaul2971b5a2023-01-29 15:49:32 -0800947 H_encoders_and_gyro_.emplace(H_encoders_and_gyro);
948 }
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800949
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800950 encoder_noise_ = 5e-9;
951 gyro_noise_ = 1e-13;
Austin Schuh9fe68f72019-08-10 19:32:03 -0700952
953 X_hat_.setZero();
954 P_.setZero();
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800955}
956
Stephan Pleinesd99b1ee2024-02-02 20:56:44 -0800957} // namespace frc971::control_loops::drivetrain
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800958
959#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_HYBRID_EKF_H_