blob: d2c0be3b87c111011f5d38f9cdd96f7cc25a03dc [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.
140 static constexpr int kSaveSamples = 50;
141 // Assume that all correction steps will have kNOutputs
142 // dimensions.
143 // TODO(james): Relax this assumption; relaxing it requires
144 // figuring out how to deal with storing variable size
145 // observation matrices, though.
146 static constexpr int kNOutputs = 3;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800147 // Time constant to use for estimating how the longitudinal/lateral velocity
148 // offsets decay, in seconds.
149 static constexpr double kVelocityOffsetTimeConstant = 10.0;
150 static constexpr double kLateralVelocityTimeConstant = 1.0;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800151 // Inputs are [left_volts, right_volts]
152 typedef Eigen::Matrix<Scalar, kNInputs, 1> Input;
153 // Outputs are either:
154 // [left_encoder, right_encoder, gyro_vel]; or [heading, distance, skew] to
155 // some target. This makes it so we don't have to figure out how we store
156 // variable-size measurement updates.
157 typedef Eigen::Matrix<Scalar, kNOutputs, 1> Output;
158 typedef Eigen::Matrix<Scalar, kNStates, kNStates> StateSquare;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800159 // State contains the states defined by the StateIdx enum. See comments there.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800160 typedef Eigen::Matrix<Scalar, kNStates, 1> State;
161
162 // Constructs a HybridEkf for a particular drivetrain.
163 // Currently, we use the drivetrain config for modelling constants
164 // (continuous time A and B matrices) and for the noise matrices for the
165 // encoders/gyro.
166 HybridEkf(const DrivetrainConfig<Scalar> &dt_config)
167 : dt_config_(dt_config),
168 velocity_drivetrain_coefficients_(
169 dt_config.make_hybrid_drivetrain_velocity_loop()
170 .plant()
171 .coefficients()) {
172 InitializeMatrices();
173 }
174
175 // Set the initial guess of the state. Can only be called once, and before
176 // any measurement updates have occured.
177 // TODO(james): We may want to actually re-initialize and reset things on
178 // the field. Create some sort of Reset() function.
179 void ResetInitialState(::aos::monotonic_clock::time_point t,
James Kuszmaul1057ce82019-02-09 17:58:24 -0800180 const State &state, const StateSquare &P) {
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800181 observations_.clear();
182 X_hat_ = state;
James Kuszmaul074429e2019-03-23 16:01:49 -0700183 have_zeroed_encoders_ = true;
James Kuszmaul1057ce82019-02-09 17:58:24 -0800184 P_ = P;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800185 observations_.PushFromBottom(
186 {t,
187 t,
188 X_hat_,
189 P_,
190 Input::Zero(),
191 Output::Zero(),
192 {},
193 [](const State &, const Input &) { return Output::Zero(); },
194 [](const State &) {
195 return Eigen::Matrix<Scalar, kNOutputs, kNStates>::Zero();
196 },
197 Eigen::Matrix<Scalar, kNOutputs, kNOutputs>::Identity()});
198 }
199
200 // Correct with:
201 // A measurement z at time t with z = h(X_hat, U) + v where v has noise
202 // covariance R.
203 // Input U is applied from the previous timestep until time t.
204 // If t is later than any previous measurements, then U must be provided.
205 // If the measurement falls between two previous measurements, then U
206 // can be provided or not; if U is not provided, then it is filled in based
207 // on an assumption that the voltage was held constant between the time steps.
208 // TODO(james): Is it necessary to explicitly to provide a version with H as a
209 // matrix for linear cases?
210 void Correct(
211 const Output &z, const Input *U,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800212 std::function<
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800213 void(const State &, const StateSquare &,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800214 std::function<Output(const State &, const Input &)> *,
215 std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(
216 const State &)> *)> make_h,
217 std::function<Output(const State &, const Input &)> h,
218 std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(const State &)>
219 dhdx, const Eigen::Matrix<Scalar, kNOutputs, kNOutputs> &R,
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800220 aos::monotonic_clock::time_point t);
221
222 // A utility function for specifically updating with encoder and gyro
223 // measurements.
224 void UpdateEncodersAndGyro(const Scalar left_encoder,
225 const Scalar right_encoder, const Scalar gyro_rate,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800226 const Eigen::Matrix<Scalar, 2, 1> &voltage,
227 const Eigen::Matrix<Scalar, 3, 1> &accel,
228 aos::monotonic_clock::time_point t) {
229 Input U;
230 U.template block<2, 1>(0, 0) = voltage;
231 U.template block<2, 1>(kLongitudinalAccel, 0) =
232 accel.template block<2, 1>(0, 0);
233 RawUpdateEncodersAndGyro(left_encoder, right_encoder, gyro_rate, U, t);
234 }
235 // Version of UpdateEncodersAndGyro that takes a input matrix rather than
236 // taking in a voltage/acceleration separately.
237 void RawUpdateEncodersAndGyro(const Scalar left_encoder,
238 const Scalar right_encoder,
239 const Scalar gyro_rate, const Input &U,
240 aos::monotonic_clock::time_point t) {
James Kuszmaul074429e2019-03-23 16:01:49 -0700241 // Because the check below for have_zeroed_encoders_ will add an
242 // Observation, do a check here to ensure that initialization has been
243 // performed and so there is at least one observation.
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800244 CHECK(!observations_.empty());
James Kuszmaul074429e2019-03-23 16:01:49 -0700245 if (!have_zeroed_encoders_) {
246 // This logic handles ensuring that on the first encoder reading, we
247 // update the internal state for the encoders to match the reading.
248 // Otherwise, if we restart the drivetrain without restarting
249 // wpilib_interface, then we can get some obnoxious initial corrections
250 // that mess up the localization.
251 State newstate = X_hat_;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800252 newstate(kLeftEncoder) = left_encoder;
253 newstate(kRightEncoder) = right_encoder;
254 newstate(kLeftVoltageError) = 0.0;
255 newstate(kRightVoltageError) = 0.0;
256 newstate(kAngularError) = 0.0;
257 newstate(kLongitudinalVelocityOffset) = 0.0;
258 newstate(kLateralVelocity) = 0.0;
James Kuszmaul074429e2019-03-23 16:01:49 -0700259 ResetInitialState(t, newstate, P_);
260 // We need to set have_zeroed_encoders_ after ResetInitialPosition because
261 // the reset clears have_zeroed_encoders_...
262 have_zeroed_encoders_ = true;
263 }
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800264
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800265 Output z(left_encoder, right_encoder, gyro_rate);
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800266
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800267 Eigen::Matrix<Scalar, kNOutputs, kNOutputs> R;
268 R.setZero();
269 R.diagonal() << encoder_noise_, encoder_noise_, gyro_noise_;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800270 Correct(
271 z, &U, {},
272 [this](const State &X, const Input &) {
273 return H_encoders_and_gyro_ * X;
274 },
275 [this](const State &) { return H_encoders_and_gyro_; }, R, t);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800276 }
277
278 // Sundry accessor:
279 State X_hat() const { return X_hat_; }
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800280 Scalar X_hat(long i) const { return X_hat_(i); }
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800281 StateSquare P() const { return P_; }
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800282 aos::monotonic_clock::time_point latest_t() const {
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800283 return observations_.top().t;
284 }
285
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800286 static Scalar CalcLongitudinalVelocity(const State &X) {
287 return (X(kLeftVelocity) + X(kRightVelocity)) / 2.0;
288 }
289
290 Scalar CalcYawRate(const State &X) const {
291 return (X(kRightVelocity) - X(kLeftVelocity)) / 2.0 /
292 dt_config_.robot_radius;
293 }
294
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800295 private:
296 struct Observation {
297 // Time when the observation was taken.
298 aos::monotonic_clock::time_point t;
299 // Time that the previous observation was taken:
300 aos::monotonic_clock::time_point prev_t;
301 // Estimate of state at previous observation time t, after accounting for
302 // the previous observation.
303 State X_hat;
304 // Noise matrix corresponding to X_hat_.
305 StateSquare P;
306 // The input applied from previous observation until time t.
307 Input U;
308 // Measurement taken at that time.
309 Output z;
310 // A function to create h and dhdx from a given position/covariance
311 // estimate. This is used by the camera to make it so that we only have to
312 // match targets once.
313 // Only called if h and dhdx are empty.
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800314 std::function<void(const State &, const StateSquare &,
315 std::function<Output(const State &, const Input &)> *,
316 std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(
317 const State &)> *)> make_h;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800318 // A function to calculate the expected output at a given state/input.
319 // TODO(james): For encoders/gyro, it is linear and the function call may
320 // be expensive. Potential source of optimization.
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800321 std::function<Output(const State &, const Input &)> h;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800322 // The Jacobian of h with respect to x.
323 // We assume that U has no impact on the Jacobian.
324 // TODO(james): Currently, none of the users of this actually make use of
325 // the ability to have dynamic dhdx (technically, the camera code should
326 // recalculate it to be strictly correct, but I was both too lazy to do
327 // so and it seemed unnecessary). This is a potential source for future
328 // optimizations if function calls are being expensive.
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800329 std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(const State &)>
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700330 dhdx;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800331 // The measurement noise matrix.
332 Eigen::Matrix<Scalar, kNOutputs, kNOutputs> R;
333
334 // In order to sort the observations in the PriorityQueue object, we
335 // need a comparison function.
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700336 friend bool operator<(const Observation &l, const Observation &r) {
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800337 return l.t < r.t;
338 }
339 };
340
341 void InitializeMatrices();
342
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800343 // These constants and functions define how the longitudinal velocity
344 // (the average of the left and right velocities) decays. We model it as
345 // decaying at a constant rate, except very near zero where the decay rate is
346 // exponential (this is more numerically stable than just using a constant
347 // rate the whole time). We use this model rather than a simpler exponential
348 // decay because an exponential decay will result in the robot's velocity
349 // estimate consistently being far too low when at high velocities, and since
350 // the acceleromater-based estimate of the velocity will only drift at a
351 // relatively slow rate and doesn't get worse at higher velocities, we can
352 // safely decay pretty slowly.
353 static constexpr double kMaxVelocityAccel = 0.005;
354 static constexpr double kMaxVelocityGain = 1.0;
355 static Scalar VelocityAccel(Scalar velocity) {
356 return -std::clamp(kMaxVelocityGain * velocity, -kMaxVelocityAccel,
357 kMaxVelocityAccel);
358 }
359
360 static Scalar VelocityAccelDiff(Scalar velocity) {
361 return (std::abs(kMaxVelocityGain * velocity) > kMaxVelocityAccel)
362 ? 0.0
363 : -kMaxVelocityGain;
364 }
365
366 // Returns the "A" matrix for a given state. See DiffEq for discussion of
367 // ignore_accel.
368 StateSquare AForState(const State &X, bool ignore_accel = false) const {
369 // Calculate the A matrix for a given state. Note that A = partial Xdot /
370 // partial X. This is distinct from saying that Xdot = A * X. This is
371 // particularly relevant for the (kX, kTheta) members which otherwise seem
372 // odd.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800373 StateSquare A_continuous = A_continuous_;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800374 const Scalar theta = X(kTheta);
375 const Scalar stheta = std::sin(theta);
376 const Scalar ctheta = std::cos(theta);
377 const Scalar lng_vel = CalcLongitudinalVelocity(X);
378 const Scalar lat_vel = X(kLateralVelocity);
379 const Scalar diameter = 2.0 * dt_config_.robot_radius;
380 const Scalar yaw_rate = CalcYawRate(X);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800381 // X and Y derivatives
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800382 A_continuous(kX, kTheta) =
383 -stheta * lng_vel - ctheta * lat_vel;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800384 A_continuous(kX, kLeftVelocity) = ctheta / 2.0;
385 A_continuous(kX, kRightVelocity) = ctheta / 2.0;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800386 A_continuous(kX, kLateralVelocity) = -stheta;
387 A_continuous(kY, kTheta) = ctheta * lng_vel - stheta * lat_vel;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800388 A_continuous(kY, kLeftVelocity) = stheta / 2.0;
389 A_continuous(kY, kRightVelocity) = stheta / 2.0;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800390 A_continuous(kY, kLateralVelocity) = ctheta;
391
392 if (!ignore_accel) {
393 const Eigen::Matrix<Scalar, 1, kNStates> lng_vel_row =
394 (A_continuous.row(kLeftVelocity) + A_continuous.row(kRightVelocity)) /
395 2.0;
396 A_continuous.row(kLeftVelocity) -= lng_vel_row;
397 A_continuous.row(kRightVelocity) -= lng_vel_row;
398 // Terms to account for centripetal accelerations.
399 // lateral centripetal accel = -yaw_rate * lng_vel
400 A_continuous(kLateralVelocity, kLeftVelocity) +=
401 X(kLeftVelocity) / diameter;
402 A_continuous(kLateralVelocity, kRightVelocity) +=
403 -X(kRightVelocity) / diameter;
404 A_continuous(kRightVelocity, kLateralVelocity) += yaw_rate;
405 A_continuous(kLeftVelocity, kLateralVelocity) += yaw_rate;
406 const Scalar dlng_accel_dwheel_vel = X(kLateralVelocity) / diameter;
407 A_continuous(kRightVelocity, kRightVelocity) += dlng_accel_dwheel_vel;
408 A_continuous(kLeftVelocity, kRightVelocity) += dlng_accel_dwheel_vel;
409 A_continuous(kRightVelocity, kLeftVelocity) += -dlng_accel_dwheel_vel;
410 A_continuous(kLeftVelocity, kLeftVelocity) += -dlng_accel_dwheel_vel;
411
412 A_continuous(kRightVelocity, kRightVelocity) +=
413 VelocityAccelDiff(lng_vel) / 2.0;
414 A_continuous(kRightVelocity, kLeftVelocity) +=
415 VelocityAccelDiff(lng_vel) / 2.0;
416 A_continuous(kLeftVelocity, kRightVelocity) +=
417 VelocityAccelDiff(lng_vel) / 2.0;
418 A_continuous(kLeftVelocity, kLeftVelocity) +=
419 VelocityAccelDiff(lng_vel) / 2.0;
420 }
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800421 return A_continuous;
422 }
423
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800424 // Returns dX / dt given X and U. If ignore_accel is set, then we ignore the
425 // accelerometer-based components of U (this is solely used in testing).
426 State DiffEq(const State &X, const Input &U,
427 bool ignore_accel = false) const {
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800428 State Xdot = A_continuous_ * X + B_continuous_ * U;
429 // And then we need to add on the terms for the x/y change:
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800430 const Scalar theta = X(kTheta);
431 const Scalar lng_vel = CalcLongitudinalVelocity(X);
432 const Scalar lat_vel = X(kLateralVelocity);
433 const Scalar stheta = std::sin(theta);
434 const Scalar ctheta = std::cos(theta);
435 Xdot(kX) = ctheta * lng_vel - stheta * lat_vel;
436 Xdot(kY) = stheta * lng_vel + ctheta * lat_vel;
437
438 const Scalar yaw_rate = CalcYawRate(X);
439 const Scalar expected_lat_accel = lng_vel * yaw_rate;
440 const Scalar expected_lng_accel =
441 CalcLongitudinalVelocity(Xdot) - yaw_rate * lat_vel;
442 const Scalar lng_accel_offset =
443 U(kLongitudinalAccel) - expected_lng_accel;
444 constexpr double kAccelWeight = 1.0;
445 if (!ignore_accel) {
446 Xdot(kLeftVelocity) += kAccelWeight * lng_accel_offset;
447 Xdot(kRightVelocity) += kAccelWeight * lng_accel_offset;
448 Xdot(kLateralVelocity) += U(kLateralAccel) - expected_lat_accel;
449
450 Xdot(kRightVelocity) += VelocityAccel(lng_vel);
451 Xdot(kLeftVelocity) += VelocityAccel(lng_vel);
452 }
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800453 return Xdot;
454 }
455
456 void PredictImpl(const Input &U, std::chrono::nanoseconds dt, State *state,
457 StateSquare *P) {
458 StateSquare A_c = AForState(*state);
459 StateSquare A_d;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800460 StateSquare Q_d;
James Kuszmaulb2a2f352019-03-02 16:59:34 -0800461 controls::DiscretizeQAFast(Q_continuous_, A_c, dt, &Q_d, &A_d);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800462
463 *state = RungeKuttaU(
James Kuszmaul651fc3f2019-05-15 21:14:25 -0700464 [this](const State &X, const Input &U) { return DiffEq(X, U); }, *state,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800465 U, aos::time::DurationInSeconds(dt));
James Kuszmaulb2a2f352019-03-02 16:59:34 -0800466
467 StateSquare Ptemp = A_d * *P * A_d.transpose() + Q_d;
468 *P = Ptemp;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800469 }
470
471 void CorrectImpl(const Eigen::Matrix<Scalar, kNOutputs, kNOutputs> &R,
472 const Output &Z, const Output &expected_Z,
473 const Eigen::Matrix<Scalar, kNOutputs, kNStates> &H,
474 State *state, StateSquare *P) {
475 Output err = Z - expected_Z;
476 Eigen::Matrix<Scalar, kNStates, kNOutputs> PH = *P * H.transpose();
477 Eigen::Matrix<Scalar, kNOutputs, kNOutputs> S = H * PH + R;
478 Eigen::Matrix<Scalar, kNStates, kNOutputs> K = PH * S.inverse();
James Kuszmaulb2a2f352019-03-02 16:59:34 -0800479 *state += K * err;
480 StateSquare Ptemp = (StateSquare::Identity() - K * H) * *P;
481 *P = Ptemp;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800482 }
483
484 void ProcessObservation(Observation *obs, const std::chrono::nanoseconds dt,
485 State *state, StateSquare *P) {
486 *state = obs->X_hat;
487 *P = obs->P;
488 if (dt.count() != 0) {
489 PredictImpl(obs->U, dt, state, P);
490 }
491 if (!(obs->h && obs->dhdx)) {
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800492 CHECK(obs->make_h);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800493 obs->make_h(*state, *P, &obs->h, &obs->dhdx);
494 }
495 CorrectImpl(obs->R, obs->z, obs->h(*state, obs->U), obs->dhdx(*state),
496 state, P);
497 }
498
499 DrivetrainConfig<Scalar> dt_config_;
500 State X_hat_;
501 StateFeedbackHybridPlantCoefficients<2, 2, 2, Scalar>
502 velocity_drivetrain_coefficients_;
503 StateSquare A_continuous_;
504 StateSquare Q_continuous_;
505 StateSquare P_;
506 Eigen::Matrix<Scalar, kNOutputs, kNStates> H_encoders_and_gyro_;
507 Scalar encoder_noise_, gyro_noise_;
508 Eigen::Matrix<Scalar, kNStates, kNInputs> B_continuous_;
509
James Kuszmaul074429e2019-03-23 16:01:49 -0700510 bool have_zeroed_encoders_ = false;
511
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800512 aos::PriorityQueue<Observation, kSaveSamples, std::less<Observation>>
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800513 observations_;
514
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800515
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800516 friend class testing::HybridEkfTest;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800517 friend class y2019::control_loops::testing::ParameterizedLocalizerTest;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800518}; // class HybridEkf
519
520template <typename Scalar>
521void HybridEkf<Scalar>::Correct(
522 const Output &z, const Input *U,
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800523 std::function<void(const State &, const StateSquare &,
524 std::function<Output(const State &, const Input &)> *,
525 std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(
526 const State &)> *)> make_h,
527 std::function<Output(const State &, const Input &)> h,
528 std::function<Eigen::Matrix<Scalar, kNOutputs, kNStates>(const State &)>
529 dhdx, const Eigen::Matrix<Scalar, kNOutputs, kNOutputs> &R,
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800530 aos::monotonic_clock::time_point t) {
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800531 CHECK(!observations_.empty());
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800532 if (!observations_.full() && t < observations_.begin()->t) {
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800533 LOG(ERROR) << "Dropped an observation that was received before we "
534 "initialized.\n";
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800535 return;
536 }
537 auto cur_it =
538 observations_.PushFromBottom({t, t, State::Zero(), StateSquare::Zero(),
539 Input::Zero(), z, make_h, h, dhdx, R});
540 if (cur_it == observations_.end()) {
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800541 VLOG(1) << "Camera dropped off of end with time of "
542 << aos::time::DurationInSeconds(t.time_since_epoch())
543 << "s; earliest observation in "
544 "queue has time of "
545 << aos::time::DurationInSeconds(
546 observations_.begin()->t.time_since_epoch())
547 << "s.\n";
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800548 return;
549 }
550
551 // Now we populate any state information that depends on where the
552 // observation was inserted into the queue. X_hat and P must be populated
553 // from the values present in the observation *following* this one in
554 // the queue (note that the X_hat and P that we store in each observation
555 // is the values that they held after accounting for the previous
556 // measurement and before accounting for the time between the previous and
557 // current measurement). If we appended to the end of the queue, then
558 // we need to pull from X_hat_ and P_ specifically.
559 // Furthermore, for U:
560 // -If the observation was inserted at the end, then the user must've
561 // provided U and we use it.
562 // -Otherwise, only grab U if necessary.
563 auto next_it = cur_it;
564 ++next_it;
565 if (next_it == observations_.end()) {
566 cur_it->X_hat = X_hat_;
567 cur_it->P = P_;
568 // Note that if next_it == observations_.end(), then because we already
569 // checked for !observations_.empty(), we are guaranteed to have
570 // valid prev_it.
571 auto prev_it = cur_it;
572 --prev_it;
573 cur_it->prev_t = prev_it->t;
574 // TODO(james): Figure out a saner way of handling this.
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800575 CHECK(U != nullptr);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800576 cur_it->U = *U;
577 } else {
578 cur_it->X_hat = next_it->X_hat;
579 cur_it->P = next_it->P;
580 cur_it->prev_t = next_it->prev_t;
581 next_it->prev_t = cur_it->t;
582 cur_it->U = (U == nullptr) ? next_it->U : *U;
583 }
584 // Now we need to rerun the predict step from the previous to the new
585 // observation as well as every following correct/predict up to the current
586 // time.
587 while (true) {
588 // We use X_hat_ and P_ to store the intermediate states, and then
589 // once we reach the end they will all be up-to-date.
590 ProcessObservation(&*cur_it, cur_it->t - cur_it->prev_t, &X_hat_, &P_);
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800591 CHECK(X_hat_.allFinite());
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800592 if (next_it != observations_.end()) {
593 next_it->X_hat = X_hat_;
594 next_it->P = P_;
595 } else {
596 break;
597 }
598 ++cur_it;
599 ++next_it;
600 }
601}
602
603template <typename Scalar>
604void HybridEkf<Scalar>::InitializeMatrices() {
605 A_continuous_.setZero();
606 const Scalar diameter = 2.0 * dt_config_.robot_radius;
607 // Theta derivative
608 A_continuous_(kTheta, kLeftVelocity) = -1.0 / diameter;
609 A_continuous_(kTheta, kRightVelocity) = 1.0 / diameter;
610
611 // Encoder derivatives
612 A_continuous_(kLeftEncoder, kLeftVelocity) = 1.0;
James Kuszmaul074429e2019-03-23 16:01:49 -0700613 A_continuous_(kLeftEncoder, kAngularError) = 1.0;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800614 A_continuous_(kLeftEncoder, kLongitudinalVelocityOffset) = -1.0;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800615 A_continuous_(kRightEncoder, kRightVelocity) = 1.0;
James Kuszmaul074429e2019-03-23 16:01:49 -0700616 A_continuous_(kRightEncoder, kAngularError) = -1.0;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800617 A_continuous_(kRightEncoder, kLongitudinalVelocityOffset) = -1.0;
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800618
619 // Pull velocity derivatives from velocity matrices.
620 // Note that this looks really awkward (doesn't use
621 // Eigen blocks) because someone decided that the full
622 // drivetrain Kalman Filter should half a weird convention.
623 // TODO(james): Support shifting drivetrains with changing A_continuous
624 const auto &vel_coefs = velocity_drivetrain_coefficients_;
625 A_continuous_(kLeftVelocity, kLeftVelocity) = vel_coefs.A_continuous(0, 0);
626 A_continuous_(kLeftVelocity, kRightVelocity) = vel_coefs.A_continuous(0, 1);
627 A_continuous_(kRightVelocity, kLeftVelocity) = vel_coefs.A_continuous(1, 0);
628 A_continuous_(kRightVelocity, kRightVelocity) = vel_coefs.A_continuous(1, 1);
629
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800630 A_continuous_(kLongitudinalVelocityOffset, kLongitudinalVelocityOffset) =
631 -1.0 / kVelocityOffsetTimeConstant;
632 A_continuous_(kLateralVelocity, kLateralVelocity) =
633 -1.0 / kLateralVelocityTimeConstant;
634
635 // We currently ignore all voltage-related modelling terms.
636 // TODO(james): Decide what to do about these terms. They don't really matter
637 // too much when we have accelerometer readings available.
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800638 B_continuous_.setZero();
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800639 B_continuous_.template block<1, 2>(kLeftVelocity, kLeftVoltage) =
640 vel_coefs.B_continuous.row(0);
641 B_continuous_.template block<1, 2>(kRightVelocity, kLeftVoltage) =
642 vel_coefs.B_continuous.row(1);
643 A_continuous_.template block<kNStates, 2>(0, kLeftVoltageError) =
644 B_continuous_.template block<kNStates, 2>(0, kLeftVoltage);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800645
646 Q_continuous_.setZero();
647 // TODO(james): Improve estimates of process noise--e.g., X/Y noise can
James Kuszmaul1057ce82019-02-09 17:58:24 -0800648 // probably be reduced when we are stopped because you rarely jump randomly.
649 // Or maybe it's more appropriate to scale wheelspeed noise with wheelspeed,
650 // since the wheels aren't likely to slip much stopped.
James Kuszmaula5632fe2019-03-23 20:28:33 -0700651 Q_continuous_(kX, kX) = 0.002;
652 Q_continuous_(kY, kY) = 0.002;
James Kuszmaul7f1a4082019-04-14 10:50:44 -0700653 Q_continuous_(kTheta, kTheta) = 0.0001;
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800654 Q_continuous_(kLeftEncoder, kLeftEncoder) = std::pow(0.15, 2.0);
655 Q_continuous_(kRightEncoder, kRightEncoder) = std::pow(0.15, 2.0);
656 Q_continuous_(kLeftVelocity, kLeftVelocity) = std::pow(0.5, 2.0);
657 Q_continuous_(kRightVelocity, kRightVelocity) = std::pow(0.5, 2.0);
658 Q_continuous_(kLeftVoltageError, kLeftVoltageError) = std::pow(10.0, 2.0);
659 Q_continuous_(kRightVoltageError, kRightVoltageError) = std::pow(10.0, 2.0);
660 Q_continuous_(kAngularError, kAngularError) = std::pow(2.0, 2.0);
661 // This noise value largely governs whether we will trust the encoders or
662 // accelerometer more for estimating the robot position.
James Kuszmaul5398fae2020-02-17 16:44:03 -0800663 // Note that this also affects how we interpret camera measurements,
664 // particularly when using a heading/distance/skew measurement--if the
665 // noise on these numbers is particularly high, then we can end up with weird
666 // dynamics where a camera update both shifts our X/Y position and adjusts our
667 // velocity estimates substantially, causing the camera updates to create
668 // "momentum" and if we don't trust the encoders enough, then we have no way of
669 // determining that the velocity updates are bogus. This also interacts with
670 // kVelocityOffsetTimeConstant.
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800671 Q_continuous_(kLongitudinalVelocityOffset, kLongitudinalVelocityOffset) =
672 std::pow(1.1, 2.0);
673 Q_continuous_(kLateralVelocity, kLateralVelocity) = std::pow(0.1, 2.0);
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800674
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800675 H_encoders_and_gyro_.setZero();
676 // Encoders are stored directly in the state matrix, so are a minor
677 // transform away.
678 H_encoders_and_gyro_(0, kLeftEncoder) = 1.0;
679 H_encoders_and_gyro_(1, kRightEncoder) = 1.0;
680 // Gyro rate is just the difference between right/left side speeds:
681 H_encoders_and_gyro_(2, kLeftVelocity) = -1.0 / diameter;
682 H_encoders_and_gyro_(2, kRightVelocity) = 1.0 / diameter;
683
James Kuszmaul3c5b4d32020-02-11 17:22:14 -0800684 encoder_noise_ = 5e-9;
685 gyro_noise_ = 1e-13;
Austin Schuh9fe68f72019-08-10 19:32:03 -0700686
687 X_hat_.setZero();
688 P_.setZero();
James Kuszmaul2ed7b3c2019-02-09 18:26:19 -0800689}
690
691} // namespace drivetrain
692} // namespace control_loops
693} // namespace frc971
694
695#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_HYBRID_EKF_H_