blob: 5cbee51ad1c047a514b452004a9a3247699cc330 [file] [log] [blame]
James Kuszmaul29c59522022-02-12 16:44:26 -08001#include "y2022/control_loops/localizer/localizer.h"
2
3#include "frc971/control_loops/c2d.h"
4#include "frc971/wpilib/imu_batch_generated.h"
James Kuszmaul5ed29dd2022-02-13 18:32:06 -08005#include "y2022/constants.h"
James Kuszmaul29c59522022-02-12 16:44:26 -08006
7namespace frc971::controls {
8
9namespace {
10constexpr double kG = 9.80665;
11constexpr std::chrono::microseconds kNominalDt(500);
12
13template <int N>
14Eigen::Matrix<double, N, 1> MakeState(std::vector<double> values) {
15 CHECK_EQ(static_cast<size_t>(N), values.size());
16 Eigen::Matrix<double, N, 1> vector;
17 for (int ii = 0; ii < N; ++ii) {
18 vector(ii, 0) = values[ii];
19 }
20 return vector;
21}
James Kuszmaul29c59522022-02-12 16:44:26 -080022} // namespace
23
24ModelBasedLocalizer::ModelBasedLocalizer(
25 const control_loops::drivetrain::DrivetrainConfig<double> &dt_config)
26 : dt_config_(dt_config),
27 velocity_drivetrain_coefficients_(
28 dt_config.make_hybrid_drivetrain_velocity_loop()
29 .plant()
30 .coefficients()),
31 down_estimator_(dt_config) {
James Kuszmaul93825a02022-02-13 16:50:33 -080032 CHECK_EQ(branches_.capacity(), static_cast<size_t>(std::chrono::seconds(1) /
33 kNominalDt / kBranchPeriod));
James Kuszmaul29c59522022-02-12 16:44:26 -080034 if (dt_config_.is_simulated) {
35 down_estimator_.assume_perfect_gravity();
36 }
37 A_continuous_accel_.setZero();
38 A_continuous_model_.setZero();
39 B_continuous_accel_.setZero();
40 B_continuous_model_.setZero();
41
42 A_continuous_accel_(kX, kVelocityX) = 1.0;
43 A_continuous_accel_(kY, kVelocityY) = 1.0;
44
45 const double diameter = 2.0 * dt_config_.robot_radius;
46
47 A_continuous_model_(kTheta, kLeftVelocity) = -1.0 / diameter;
48 A_continuous_model_(kTheta, kRightVelocity) = 1.0 / diameter;
49 A_continuous_model_(kLeftEncoder, kLeftVelocity) = 1.0;
50 A_continuous_model_(kRightEncoder, kRightVelocity) = 1.0;
51 const auto &vel_coefs = velocity_drivetrain_coefficients_;
52 A_continuous_model_(kLeftVelocity, kLeftVelocity) =
53 vel_coefs.A_continuous(0, 0);
54 A_continuous_model_(kLeftVelocity, kRightVelocity) =
55 vel_coefs.A_continuous(0, 1);
56 A_continuous_model_(kRightVelocity, kLeftVelocity) =
57 vel_coefs.A_continuous(1, 0);
58 A_continuous_model_(kRightVelocity, kRightVelocity) =
59 vel_coefs.A_continuous(1, 1);
60
61 A_continuous_model_(kLeftVelocity, kLeftVoltageError) =
62 1 * vel_coefs.B_continuous(0, 0);
63 A_continuous_model_(kLeftVelocity, kRightVoltageError) =
64 1 * vel_coefs.B_continuous(0, 1);
65 A_continuous_model_(kRightVelocity, kLeftVoltageError) =
66 1 * vel_coefs.B_continuous(1, 0);
67 A_continuous_model_(kRightVelocity, kRightVoltageError) =
68 1 * vel_coefs.B_continuous(1, 1);
69
70 B_continuous_model_.block<1, 2>(kLeftVelocity, kLeftVoltage) =
71 vel_coefs.B_continuous.row(0);
72 B_continuous_model_.block<1, 2>(kRightVelocity, kLeftVoltage) =
73 vel_coefs.B_continuous.row(1);
74
75 B_continuous_accel_(kVelocityX, kAccelX) = 1.0;
76 B_continuous_accel_(kVelocityY, kAccelY) = 1.0;
77 B_continuous_accel_(kTheta, kThetaRate) = 1.0;
78
79 Q_continuous_model_.setZero();
80 Q_continuous_model_.diagonal() << 1e-4, 1e-4, 1e-4, 1e-2, 1e-0, 1e-0, 1e-2,
81 1e-0, 1e-0;
82
83 P_model_ = Q_continuous_model_ * aos::time::DurationInSeconds(kNominalDt);
84}
85
86Eigen::Matrix<double, ModelBasedLocalizer::kNModelStates,
87 ModelBasedLocalizer::kNModelStates>
88ModelBasedLocalizer::AModel(
89 const ModelBasedLocalizer::ModelState &state) const {
90 Eigen::Matrix<double, kNModelStates, kNModelStates> A = A_continuous_model_;
91 const double theta = state(kTheta);
92 const double stheta = std::sin(theta);
93 const double ctheta = std::cos(theta);
94 const double velocity = (state(kLeftVelocity) + state(kRightVelocity)) / 2.0;
95 A(kX, kTheta) = -stheta * velocity;
96 A(kX, kLeftVelocity) = ctheta / 2.0;
97 A(kX, kRightVelocity) = ctheta / 2.0;
98 A(kY, kTheta) = ctheta * velocity;
99 A(kY, kLeftVelocity) = stheta / 2.0;
100 A(kY, kRightVelocity) = stheta / 2.0;
101 return A;
102}
103
104Eigen::Matrix<double, ModelBasedLocalizer::kNAccelStates,
105 ModelBasedLocalizer::kNAccelStates>
106ModelBasedLocalizer::AAccel() const {
107 return A_continuous_accel_;
108}
109
110ModelBasedLocalizer::ModelState ModelBasedLocalizer::DiffModel(
111 const ModelBasedLocalizer::ModelState &state,
112 const ModelBasedLocalizer::ModelInput &U) const {
113 ModelState x_dot = AModel(state) * state + B_continuous_model_ * U;
114 const double theta = state(kTheta);
115 const double stheta = std::sin(theta);
116 const double ctheta = std::cos(theta);
117 const double velocity = (state(kLeftVelocity) + state(kRightVelocity)) / 2.0;
118 x_dot(kX) = ctheta * velocity;
119 x_dot(kY) = stheta * velocity;
120 return x_dot;
121}
122
123ModelBasedLocalizer::AccelState ModelBasedLocalizer::DiffAccel(
124 const ModelBasedLocalizer::AccelState &state,
125 const ModelBasedLocalizer::AccelInput &U) const {
126 return AAccel() * state + B_continuous_accel_ * U;
127}
128
129ModelBasedLocalizer::ModelState ModelBasedLocalizer::UpdateModel(
130 const ModelBasedLocalizer::ModelState &model,
131 const ModelBasedLocalizer::ModelInput &input,
132 const aos::monotonic_clock::duration dt) const {
133 return control_loops::RungeKutta(
134 std::bind(&ModelBasedLocalizer::DiffModel, this, std::placeholders::_1,
135 input),
136 model, aos::time::DurationInSeconds(dt));
137}
138
139ModelBasedLocalizer::AccelState ModelBasedLocalizer::UpdateAccel(
140 const ModelBasedLocalizer::AccelState &accel,
141 const ModelBasedLocalizer::AccelInput &input,
142 const aos::monotonic_clock::duration dt) const {
143 return control_loops::RungeKutta(
144 std::bind(&ModelBasedLocalizer::DiffAccel, this, std::placeholders::_1,
145 input),
146 accel, aos::time::DurationInSeconds(dt));
147}
148
149ModelBasedLocalizer::AccelState ModelBasedLocalizer::AccelStateForModelState(
150 const ModelBasedLocalizer::ModelState &state) const {
151 const double robot_speed =
152 (state(kLeftVelocity) + state(kRightVelocity)) / 2.0;
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800153 const double lat_speed = (AModel(state) * state)(kTheta) * long_offset_;
154 const double velocity_x = std::cos(state(kTheta)) * robot_speed -
155 std::sin(state(kTheta)) * lat_speed;
156 const double velocity_y = std::sin(state(kTheta)) * robot_speed +
157 std::cos(state(kTheta)) * lat_speed;
James Kuszmaul29c59522022-02-12 16:44:26 -0800158 return (AccelState() << state(0), state(1), state(2), velocity_x, velocity_y)
159 .finished();
160}
161
162ModelBasedLocalizer::ModelState ModelBasedLocalizer::ModelStateForAccelState(
163 const ModelBasedLocalizer::AccelState &state,
164 const Eigen::Vector2d &encoders, const double yaw_rate) const {
165 const double robot_speed = state(kVelocityX) * std::cos(state(kTheta)) +
166 state(kVelocityY) * std::sin(state(kTheta));
167 const double radius = dt_config_.robot_radius;
168 const double left_velocity = robot_speed - yaw_rate * radius;
169 const double right_velocity = robot_speed + yaw_rate * radius;
170 return (ModelState() << state(0), state(1), state(2), encoders(0),
171 left_velocity, 0.0, encoders(1), right_velocity, 0.0)
172 .finished();
173}
174
175double ModelBasedLocalizer::ModelDivergence(
176 const ModelBasedLocalizer::CombinedState &state,
177 const ModelBasedLocalizer::AccelInput &accel_inputs,
178 const Eigen::Vector2d &filtered_accel,
179 const ModelBasedLocalizer::ModelInput &model_inputs) {
180 // Convert the model state into the acceleration-based state-space and check
181 // the distance between the two (should really be a weighted norm, but all the
182 // numbers are on ~the same scale).
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800183 // TODO(james): Maybe weight lateral velocity divergence different than
184 // longitudinal? Seems like we tend to get false-positives currently when in
185 // sharp turns.
186 // TODO(james): For off-center gyros, maybe reduce noise when turning?
James Kuszmaul29c59522022-02-12 16:44:26 -0800187 VLOG(2) << "divergence: "
188 << (state.accel_state - AccelStateForModelState(state.model_state))
189 .transpose();
190 const AccelState diff_accel = DiffAccel(state.accel_state, accel_inputs);
191 const ModelState diff_model = DiffModel(state.model_state, model_inputs);
192 const double model_lng_velocity =
193 (state.model_state(kLeftVelocity) + state.model_state(kRightVelocity)) /
194 2.0;
195 const double model_lng_accel =
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800196 (diff_model(kLeftVelocity) + diff_model(kRightVelocity)) / 2.0 -
197 diff_model(kTheta) * diff_model(kTheta) * long_offset_;
198 const double model_lat_accel = diff_model(kTheta) * model_lng_velocity;
199 const Eigen::Vector2d robot_frame_accel(model_lng_accel, model_lat_accel);
James Kuszmaul29c59522022-02-12 16:44:26 -0800200 const Eigen::Vector2d model_accel =
201 Eigen::AngleAxisd(state.model_state(kTheta), Eigen::Vector3d::UnitZ())
202 .toRotationMatrix()
203 .block<2, 2>(0, 0) *
204 robot_frame_accel;
205 const double accel_diff = (model_accel - filtered_accel).norm();
206 const double theta_rate_diff =
207 std::abs(diff_accel(kTheta) - diff_model(kTheta));
208
209 const Eigen::Vector2d accel_vel = state.accel_state.bottomRows<2>();
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800210 Eigen::Vector2d model_vel =
James Kuszmaul29c59522022-02-12 16:44:26 -0800211 AccelStateForModelState(state.model_state).bottomRows<2>();
212 velocity_residual_ = (accel_vel - model_vel).norm() /
213 (1.0 + accel_vel.norm() + model_vel.norm());
214 theta_rate_residual_ = theta_rate_diff;
215 accel_residual_ = accel_diff / 4.0;
216 return velocity_residual_ + theta_rate_residual_ + accel_residual_;
217}
218
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800219void ModelBasedLocalizer::UpdateState(
220 CombinedState *state,
221 const Eigen::Matrix<double, kNModelStates, kNModelOutputs> &K,
222 const Eigen::Matrix<double, kNModelOutputs, 1> &Z,
223 const Eigen::Matrix<double, kNModelOutputs, kNModelStates> &H,
224 const AccelInput &accel_input, const ModelInput &model_input,
225 aos::monotonic_clock::duration dt) {
226 state->accel_state = UpdateAccel(state->accel_state, accel_input, dt);
227 if (down_estimator_.consecutive_still() > 500.0) {
228 state->accel_state(kVelocityX) *= 0.9;
229 state->accel_state(kVelocityY) *= 0.9;
230 }
231 state->model_state = UpdateModel(state->model_state, model_input, dt);
232 state->model_state += K * (Z - H * state->model_state);
233}
234
James Kuszmaul29c59522022-02-12 16:44:26 -0800235void ModelBasedLocalizer::HandleImu(aos::monotonic_clock::time_point t,
236 const Eigen::Vector3d &gyro,
237 const Eigen::Vector3d &accel,
238 const Eigen::Vector2d encoders,
239 const Eigen::Vector2d voltage) {
240 VLOG(2) << t;
241 if (t_ == aos::monotonic_clock::min_time) {
242 t_ = t;
243 }
244 if (t_ + 2 * kNominalDt < t) {
245 t_ = t;
246 ++clock_resets_;
247 }
248 const aos::monotonic_clock::duration dt = t - t_;
249 t_ = t;
250 down_estimator_.Predict(gyro, accel, dt);
251 // TODO(james): Should we prefer this or use the down-estimator corrected
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800252 // version? Using the down estimator is more principled, but does create more
253 // opportunities for subtle biases.
James Kuszmaul29c59522022-02-12 16:44:26 -0800254 const double yaw_rate = (dt_config_.imu_transform * gyro)(2);
255 const double diameter = 2.0 * dt_config_.robot_radius;
256
257 const Eigen::AngleAxis<double> orientation(
258 Eigen::AngleAxis<double>(xytheta()(kTheta), Eigen::Vector3d::UnitZ()) *
259 down_estimator_.X_hat());
260
261 const Eigen::Vector3d absolute_accel =
262 orientation * dt_config_.imu_transform * kG * accel;
263 abs_accel_ = absolute_accel;
James Kuszmaul29c59522022-02-12 16:44:26 -0800264
265 VLOG(2) << "abs accel " << absolute_accel.transpose();
James Kuszmaul29c59522022-02-12 16:44:26 -0800266 VLOG(2) << "dt " << aos::time::DurationInSeconds(dt);
267
268 // Update all the branched states.
269 const AccelInput accel_input(absolute_accel.x(), absolute_accel.y(),
270 yaw_rate);
271 const ModelInput model_input(voltage);
272
273 const Eigen::Matrix<double, kNModelStates, kNModelStates> A_continuous =
274 AModel(current_state_.model_state);
275
276 Eigen::Matrix<double, kNModelStates, kNModelStates> A_discrete;
277 Eigen::Matrix<double, kNModelStates, kNModelStates> Q_discrete;
278
279 DiscretizeQAFast(Q_continuous_model_, A_continuous, dt, &Q_discrete,
280 &A_discrete);
281
282 P_model_ = A_discrete * P_model_ * A_discrete.transpose() + Q_discrete;
283
284 Eigen::Matrix<double, kNModelOutputs, kNModelStates> H;
285 Eigen::Matrix<double, kNModelOutputs, kNModelOutputs> R;
286 {
287 H.setZero();
288 R.setZero();
289 H(0, kLeftEncoder) = 1.0;
290 H(1, kRightEncoder) = 1.0;
291 H(2, kRightVelocity) = 1.0 / diameter;
292 H(2, kLeftVelocity) = -1.0 / diameter;
293
294 R.diagonal() << 1e-9, 1e-9, 1e-13;
295 }
296
297 const Eigen::Matrix<double, kNModelOutputs, 1> Z(encoders(0), encoders(1),
298 yaw_rate);
299
300 if (branches_.empty()) {
301 VLOG(2) << "Initializing";
302 current_state_.model_state.setZero();
303 current_state_.accel_state.setZero();
304 current_state_.model_state(kLeftEncoder) = encoders(0);
305 current_state_.model_state(kRightEncoder) = encoders(1);
306 current_state_.branch_time = t;
307 branches_.Push(current_state_);
308 }
309
310 const Eigen::Matrix<double, kNModelStates, kNModelOutputs> K =
311 P_model_ * H.transpose() * (H * P_model_ * H.transpose() + R).inverse();
312 P_model_ = (Eigen::Matrix<double, kNModelStates, kNModelStates>::Identity() -
313 K * H) *
314 P_model_;
315 VLOG(2) << "K\n" << K;
316 VLOG(2) << "Z\n" << Z.transpose();
317
318 for (CombinedState &state : branches_) {
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800319 UpdateState(&state, K, Z, H, accel_input, model_input, dt);
James Kuszmaul29c59522022-02-12 16:44:26 -0800320 }
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800321 UpdateState(&current_state_, K, Z, H, accel_input, model_input, dt);
James Kuszmaul29c59522022-02-12 16:44:26 -0800322
323 VLOG(2) << "oildest accel " << branches_[0].accel_state.transpose();
324 VLOG(2) << "oildest accel diff "
325 << DiffAccel(branches_[0].accel_state, accel_input).transpose();
326 VLOG(2) << "oildest model " << branches_[0].model_state.transpose();
327
328 // Determine whether to switch modes--if we are currently in model-based mode,
329 // swap to accel-based if the two states have divergeed meaningfully in the
330 // oldest branch. If we are currently in accel-based, then swap back to model
331 // if the oldest model branch matches has matched the
332 filtered_residual_accel_ +=
333 0.01 * (accel_input.topRows<2>() - filtered_residual_accel_);
334 const double model_divergence =
335 branches_.full() ? ModelDivergence(branches_[0], accel_input,
336 filtered_residual_accel_, model_input)
337 : 0.0;
338 filtered_residual_ +=
339 (1.0 - std::exp(-aos::time::DurationInSeconds(kNominalDt) / 0.0095)) *
340 (model_divergence - filtered_residual_);
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800341 // TODO(james): Tune this more. Currently set to generally trust the model,
342 // perhaps a bit too much.
343 // When the residual exceeds the accel threshold, we start using the inertials
344 // alone; when it drops back below the model threshold, we go back to being
345 // model-based.
346 constexpr double kUseAccelThreshold = 2.0;
347 constexpr double kUseModelThreshold = 0.5;
James Kuszmaul29c59522022-02-12 16:44:26 -0800348 constexpr size_t kShareStates = kNModelStates;
349 static_assert(kUseModelThreshold < kUseAccelThreshold);
350 if (using_model_) {
351 if (filtered_residual_ > kUseAccelThreshold) {
352 hysteresis_count_++;
353 } else {
354 hysteresis_count_ = 0;
355 }
356 if (hysteresis_count_ > 0) {
357 using_model_ = false;
358 // Grab the accel-based state from back when we started diverging.
359 // TODO(james): This creates a problematic selection bias, because
360 // we will tend to bias towards deliberately out-of-tune measurements.
361 current_state_.accel_state = branches_[0].accel_state;
362 current_state_.model_state = branches_[0].model_state;
363 current_state_.model_state = ModelStateForAccelState(
364 current_state_.accel_state, encoders, yaw_rate);
365 } else {
366 VLOG(2) << "Normal branching";
James Kuszmaul29c59522022-02-12 16:44:26 -0800367 current_state_.accel_state =
368 AccelStateForModelState(current_state_.model_state);
369 current_state_.branch_time = t;
370 }
371 hysteresis_count_ = 0;
372 } else {
373 if (filtered_residual_ < kUseModelThreshold) {
374 hysteresis_count_++;
375 } else {
376 hysteresis_count_ = 0;
377 }
378 if (hysteresis_count_ > 100) {
379 using_model_ = true;
380 // Grab the model-based state from back when we stopped diverging.
381 current_state_.model_state.topRows<kShareStates>() =
382 ModelStateForAccelState(branches_[0].accel_state, encoders, yaw_rate)
383 .topRows<kShareStates>();
384 current_state_.accel_state =
385 AccelStateForModelState(current_state_.model_state);
386 } else {
James Kuszmaul29c59522022-02-12 16:44:26 -0800387 // TODO(james): Why was I leaving the encoders/wheel velocities in place?
James Kuszmaul29c59522022-02-12 16:44:26 -0800388 current_state_.model_state = ModelStateForAccelState(
389 current_state_.accel_state, encoders, yaw_rate);
390 current_state_.branch_time = t;
391 }
392 }
393
394 // Generate a new branch, with the accel state reset based on the model-based
395 // state (really, just getting rid of the lateral velocity).
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800396 // By resetting the accel state in the new branch, this tries to minimize the
397 // odds of runaway lateral velocities. This doesn't help with runaway
398 // longitudinal velocities, however.
James Kuszmaul29c59522022-02-12 16:44:26 -0800399 CombinedState new_branch = current_state_;
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800400 new_branch.accel_state = AccelStateForModelState(new_branch.model_state);
James Kuszmaul29c59522022-02-12 16:44:26 -0800401 new_branch.accumulated_divergence = 0.0;
402
James Kuszmaul93825a02022-02-13 16:50:33 -0800403 ++branch_counter_;
404 if (branch_counter_ % kBranchPeriod == 0) {
405 branches_.Push(new_branch);
406 branch_counter_ = 0;
407 }
James Kuszmaul29c59522022-02-12 16:44:26 -0800408
409 last_residual_ = model_divergence;
410
411 VLOG(2) << "Using " << (using_model_ ? "model" : "accel");
412 VLOG(2) << "Residual " << last_residual_;
413 VLOG(2) << "Filtered Residual " << filtered_residual_;
414 VLOG(2) << "buffer size " << branches_.size();
415 VLOG(2) << "Model state " << current_state_.model_state.transpose();
416 VLOG(2) << "Accel state " << current_state_.accel_state.transpose();
417 VLOG(2) << "Accel state for model "
418 << AccelStateForModelState(current_state_.model_state).transpose();
419 VLOG(2) << "Input acce " << accel.transpose();
420 VLOG(2) << "Input gyro " << gyro.transpose();
421 VLOG(2) << "Input voltage " << voltage.transpose();
422 VLOG(2) << "Input encoder " << encoders.transpose();
423 VLOG(2) << "yaw rate " << yaw_rate;
424
425 CHECK(std::isfinite(last_residual_));
426}
427
428void ModelBasedLocalizer::HandleReset(aos::monotonic_clock::time_point now,
429 const Eigen::Vector3d &xytheta) {
430 branches_.Reset();
431 t_ = now;
432 using_model_ = true;
433 current_state_.model_state << xytheta(0), xytheta(1), xytheta(2),
434 current_state_.model_state(kLeftEncoder), 0.0, 0.0,
435 current_state_.model_state(kRightEncoder), 0.0, 0.0;
436 current_state_.accel_state =
437 AccelStateForModelState(current_state_.model_state);
438 last_residual_ = 0.0;
439 filtered_residual_ = 0.0;
440 filtered_residual_accel_.setZero();
441 abs_accel_.setZero();
442}
443
444flatbuffers::Offset<AccelBasedState> ModelBasedLocalizer::BuildAccelState(
445 flatbuffers::FlatBufferBuilder *fbb, const AccelState &state) {
446 AccelBasedState::Builder accel_state_builder(*fbb);
447 accel_state_builder.add_x(state(kX));
448 accel_state_builder.add_y(state(kY));
449 accel_state_builder.add_theta(state(kTheta));
450 accel_state_builder.add_velocity_x(state(kVelocityX));
451 accel_state_builder.add_velocity_y(state(kVelocityY));
452 return accel_state_builder.Finish();
453}
454
455flatbuffers::Offset<ModelBasedState> ModelBasedLocalizer::BuildModelState(
456 flatbuffers::FlatBufferBuilder *fbb, const ModelState &state) {
457 ModelBasedState::Builder model_state_builder(*fbb);
458 model_state_builder.add_x(state(kX));
459 model_state_builder.add_y(state(kY));
460 model_state_builder.add_theta(state(kTheta));
461 model_state_builder.add_left_encoder(state(kLeftEncoder));
462 model_state_builder.add_left_velocity(state(kLeftVelocity));
463 model_state_builder.add_left_voltage_error(state(kLeftVoltageError));
464 model_state_builder.add_right_encoder(state(kRightEncoder));
465 model_state_builder.add_right_velocity(state(kRightVelocity));
466 model_state_builder.add_right_voltage_error(state(kRightVoltageError));
467 return model_state_builder.Finish();
468}
469
470flatbuffers::Offset<ModelBasedStatus> ModelBasedLocalizer::PopulateStatus(
471 flatbuffers::FlatBufferBuilder *fbb) {
472 const flatbuffers::Offset<control_loops::drivetrain::DownEstimatorState>
473 down_estimator_offset = down_estimator_.PopulateStatus(fbb, t_);
474
475 const CombinedState &state = current_state_;
476
477 const flatbuffers::Offset<ModelBasedState> model_state_offset =
478 BuildModelState(fbb, state.model_state);
479
480 const flatbuffers::Offset<AccelBasedState> accel_state_offset =
481 BuildAccelState(fbb, state.accel_state);
482
483 const flatbuffers::Offset<AccelBasedState> oldest_accel_state_offset =
484 branches_.empty() ? flatbuffers::Offset<AccelBasedState>()
485 : BuildAccelState(fbb, branches_[0].accel_state);
486
487 const flatbuffers::Offset<ModelBasedState> oldest_model_state_offset =
488 branches_.empty() ? flatbuffers::Offset<ModelBasedState>()
489 : BuildModelState(fbb, branches_[0].model_state);
490
491 ModelBasedStatus::Builder builder(*fbb);
492 builder.add_accel_state(accel_state_offset);
493 builder.add_oldest_accel_state(oldest_accel_state_offset);
494 builder.add_oldest_model_state(oldest_model_state_offset);
495 builder.add_model_state(model_state_offset);
496 builder.add_using_model(using_model_);
497 builder.add_residual(last_residual_);
498 builder.add_filtered_residual(filtered_residual_);
499 builder.add_velocity_residual(velocity_residual_);
500 builder.add_accel_residual(accel_residual_);
501 builder.add_theta_rate_residual(theta_rate_residual_);
502 builder.add_down_estimator(down_estimator_offset);
503 builder.add_x(xytheta()(0));
504 builder.add_y(xytheta()(1));
505 builder.add_theta(xytheta()(2));
506 builder.add_implied_accel_x(abs_accel_(0));
507 builder.add_implied_accel_y(abs_accel_(1));
508 builder.add_implied_accel_z(abs_accel_(2));
509 builder.add_clock_resets(clock_resets_);
510 return builder.Finish();
511}
512
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800513namespace {
514// Period at which the encoder readings from the IMU board wrap.
515static double DrivetrainWrapPeriod() {
516 return y2022::constants::Values::DrivetrainEncoderToMeters(1 << 16);
517}
518}
519
James Kuszmaul29c59522022-02-12 16:44:26 -0800520EventLoopLocalizer::EventLoopLocalizer(
521 aos::EventLoop *event_loop,
522 const control_loops::drivetrain::DrivetrainConfig<double> &dt_config)
523 : event_loop_(event_loop),
524 model_based_(dt_config),
525 status_sender_(event_loop_->MakeSender<LocalizerStatus>("/localizer")),
526 output_sender_(event_loop_->MakeSender<LocalizerOutput>("/localizer")),
James Kuszmaul29c59522022-02-12 16:44:26 -0800527 output_fetcher_(
528 event_loop_->MakeFetcher<frc971::control_loops::drivetrain::Output>(
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800529 "/drivetrain")),
530 left_encoder_(-DrivetrainWrapPeriod() / 2.0, DrivetrainWrapPeriod()),
531 right_encoder_(-DrivetrainWrapPeriod() / 2.0, DrivetrainWrapPeriod()) {
James Kuszmaul29c59522022-02-12 16:44:26 -0800532 event_loop_->MakeWatcher(
533 "/drivetrain",
534 [this](
535 const frc971::control_loops::drivetrain::LocalizerControl &control) {
536 const double theta = control.keep_current_theta()
537 ? model_based_.xytheta()(2)
538 : control.theta();
539 model_based_.HandleReset(event_loop_->monotonic_now(),
540 {control.x(), control.y(), theta});
541 });
542 event_loop_->MakeWatcher(
543 "/localizer", [this](const frc971::IMUValuesBatch &values) {
544 CHECK(values.has_readings());
James Kuszmaul29c59522022-02-12 16:44:26 -0800545 output_fetcher_.Fetch();
546 for (const IMUValues *value : *values.readings()) {
547 zeroer_.InsertAndProcessMeasurement(*value);
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800548 const Eigen::Vector2d encoders{
549 left_encoder_.Unwrap(value->left_encoder()),
550 right_encoder_.Unwrap(value->right_encoder())};
James Kuszmaul29c59522022-02-12 16:44:26 -0800551 if (zeroer_.Zeroed()) {
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800552 const aos::monotonic_clock::time_point pico_timestamp{
553 std::chrono::microseconds(value->pico_timestamp_us())};
554 // TODO(james): If we get large enough drift off of the pico,
555 // actually do something about it.
556 if (!pico_offset_.has_value()) {
557 pico_offset_ =
558 event_loop_->context().monotonic_event_time - pico_timestamp;
559 last_pico_timestamp_ = pico_timestamp;
James Kuszmaule5f67dd2022-02-12 20:08:29 -0800560 }
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800561 if (pico_timestamp < last_pico_timestamp_) {
562 pico_offset_.value() += std::chrono::microseconds(1ULL << 32);
563 }
564 const aos::monotonic_clock::time_point sample_timestamp =
565 pico_offset_.value() + pico_timestamp;
566 pico_offset_error_ =
567 event_loop_->context().monotonic_event_time - sample_timestamp;
568 const bool disabled =
569 (output_fetcher_.get() == nullptr) ||
570 (output_fetcher_.context().monotonic_event_time +
571 std::chrono::milliseconds(10) <
572 event_loop_->context().monotonic_event_time);
573 model_based_.HandleImu(
574 sample_timestamp,
575 zeroer_.ZeroedGyro(), zeroer_.ZeroedAccel(), encoders,
576 disabled ? Eigen::Vector2d::Zero()
577 : Eigen::Vector2d{output_fetcher_->left_voltage(),
578 output_fetcher_->right_voltage()});
579 last_pico_timestamp_ = pico_timestamp;
James Kuszmaul29c59522022-02-12 16:44:26 -0800580 }
581 {
582 auto builder = status_sender_.MakeBuilder();
583 const flatbuffers::Offset<ModelBasedStatus> model_based_status =
584 model_based_.PopulateStatus(builder.fbb());
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800585 const flatbuffers::Offset<control_loops::drivetrain::ImuZeroerState>
586 zeroer_status = zeroer_.PopulateStatus(builder.fbb());
James Kuszmaul29c59522022-02-12 16:44:26 -0800587 LocalizerStatus::Builder status_builder =
588 builder.MakeBuilder<LocalizerStatus>();
589 status_builder.add_model_based(model_based_status);
590 status_builder.add_zeroed(zeroer_.Zeroed());
591 status_builder.add_faulted_zero(zeroer_.Faulted());
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800592 status_builder.add_zeroing(zeroer_status);
593 status_builder.add_left_encoder(encoders(0));
594 status_builder.add_right_encoder(encoders(1));
595 if (pico_offset_.has_value()) {
596 status_builder.add_pico_offset_ns(pico_offset_.value().count());
597 status_builder.add_pico_offset_error_ns(
598 pico_offset_error_.count());
599 }
James Kuszmaul29c59522022-02-12 16:44:26 -0800600 builder.CheckOk(builder.Send(status_builder.Finish()));
601 }
602 if (last_output_send_ + std::chrono::milliseconds(5) <
603 event_loop_->context().monotonic_event_time) {
604 auto builder = output_sender_.MakeBuilder();
605 LocalizerOutput::Builder output_builder =
606 builder.MakeBuilder<LocalizerOutput>();
James Kuszmaul1798c072022-02-13 15:32:11 -0800607 // TODO(james): Should we bother to try to estimate time offsets for
608 // the pico?
609 output_builder.add_monotonic_timestamp_ns(
610 value->monotonic_timestamp_ns());
James Kuszmaul29c59522022-02-12 16:44:26 -0800611 output_builder.add_x(model_based_.xytheta()(0));
612 output_builder.add_y(model_based_.xytheta()(1));
613 output_builder.add_theta(model_based_.xytheta()(2));
614 builder.CheckOk(builder.Send(output_builder.Finish()));
615 last_output_send_ = event_loop_->monotonic_now();
616 }
617 }
618 });
619}
620
621} // namespace frc971::controls