blob: 3c68e5901250be5de110c33346258b4fc93ce2a2 [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"
5// TODO(james): Things to do:
6// -Approach still seems fundamentally sound.
7// -Really need to work on cost/residual function.
8// -Particularly for handling stopping.
9// -Extra hysteresis
10
11namespace frc971::controls {
12
13namespace {
14constexpr double kG = 9.80665;
15constexpr std::chrono::microseconds kNominalDt(500);
16
17template <int N>
18Eigen::Matrix<double, N, 1> MakeState(std::vector<double> values) {
19 CHECK_EQ(static_cast<size_t>(N), values.size());
20 Eigen::Matrix<double, N, 1> vector;
21 for (int ii = 0; ii < N; ++ii) {
22 vector(ii, 0) = values[ii];
23 }
24 return vector;
25}
James Kuszmaul29c59522022-02-12 16:44:26 -080026} // namespace
27
28ModelBasedLocalizer::ModelBasedLocalizer(
29 const control_loops::drivetrain::DrivetrainConfig<double> &dt_config)
30 : dt_config_(dt_config),
31 velocity_drivetrain_coefficients_(
32 dt_config.make_hybrid_drivetrain_velocity_loop()
33 .plant()
34 .coefficients()),
35 down_estimator_(dt_config) {
James Kuszmaul93825a02022-02-13 16:50:33 -080036 CHECK_EQ(branches_.capacity(), static_cast<size_t>(std::chrono::seconds(1) /
37 kNominalDt / kBranchPeriod));
James Kuszmaul29c59522022-02-12 16:44:26 -080038 if (dt_config_.is_simulated) {
39 down_estimator_.assume_perfect_gravity();
40 }
41 A_continuous_accel_.setZero();
42 A_continuous_model_.setZero();
43 B_continuous_accel_.setZero();
44 B_continuous_model_.setZero();
45
46 A_continuous_accel_(kX, kVelocityX) = 1.0;
47 A_continuous_accel_(kY, kVelocityY) = 1.0;
48
49 const double diameter = 2.0 * dt_config_.robot_radius;
50
51 A_continuous_model_(kTheta, kLeftVelocity) = -1.0 / diameter;
52 A_continuous_model_(kTheta, kRightVelocity) = 1.0 / diameter;
53 A_continuous_model_(kLeftEncoder, kLeftVelocity) = 1.0;
54 A_continuous_model_(kRightEncoder, kRightVelocity) = 1.0;
55 const auto &vel_coefs = velocity_drivetrain_coefficients_;
56 A_continuous_model_(kLeftVelocity, kLeftVelocity) =
57 vel_coefs.A_continuous(0, 0);
58 A_continuous_model_(kLeftVelocity, kRightVelocity) =
59 vel_coefs.A_continuous(0, 1);
60 A_continuous_model_(kRightVelocity, kLeftVelocity) =
61 vel_coefs.A_continuous(1, 0);
62 A_continuous_model_(kRightVelocity, kRightVelocity) =
63 vel_coefs.A_continuous(1, 1);
64
65 A_continuous_model_(kLeftVelocity, kLeftVoltageError) =
66 1 * vel_coefs.B_continuous(0, 0);
67 A_continuous_model_(kLeftVelocity, kRightVoltageError) =
68 1 * vel_coefs.B_continuous(0, 1);
69 A_continuous_model_(kRightVelocity, kLeftVoltageError) =
70 1 * vel_coefs.B_continuous(1, 0);
71 A_continuous_model_(kRightVelocity, kRightVoltageError) =
72 1 * vel_coefs.B_continuous(1, 1);
73
74 B_continuous_model_.block<1, 2>(kLeftVelocity, kLeftVoltage) =
75 vel_coefs.B_continuous.row(0);
76 B_continuous_model_.block<1, 2>(kRightVelocity, kLeftVoltage) =
77 vel_coefs.B_continuous.row(1);
78
79 B_continuous_accel_(kVelocityX, kAccelX) = 1.0;
80 B_continuous_accel_(kVelocityY, kAccelY) = 1.0;
81 B_continuous_accel_(kTheta, kThetaRate) = 1.0;
82
83 Q_continuous_model_.setZero();
84 Q_continuous_model_.diagonal() << 1e-4, 1e-4, 1e-4, 1e-2, 1e-0, 1e-0, 1e-2,
85 1e-0, 1e-0;
86
87 P_model_ = Q_continuous_model_ * aos::time::DurationInSeconds(kNominalDt);
88}
89
90Eigen::Matrix<double, ModelBasedLocalizer::kNModelStates,
91 ModelBasedLocalizer::kNModelStates>
92ModelBasedLocalizer::AModel(
93 const ModelBasedLocalizer::ModelState &state) const {
94 Eigen::Matrix<double, kNModelStates, kNModelStates> A = A_continuous_model_;
95 const double theta = state(kTheta);
96 const double stheta = std::sin(theta);
97 const double ctheta = std::cos(theta);
98 const double velocity = (state(kLeftVelocity) + state(kRightVelocity)) / 2.0;
99 A(kX, kTheta) = -stheta * velocity;
100 A(kX, kLeftVelocity) = ctheta / 2.0;
101 A(kX, kRightVelocity) = ctheta / 2.0;
102 A(kY, kTheta) = ctheta * velocity;
103 A(kY, kLeftVelocity) = stheta / 2.0;
104 A(kY, kRightVelocity) = stheta / 2.0;
105 return A;
106}
107
108Eigen::Matrix<double, ModelBasedLocalizer::kNAccelStates,
109 ModelBasedLocalizer::kNAccelStates>
110ModelBasedLocalizer::AAccel() const {
111 return A_continuous_accel_;
112}
113
114ModelBasedLocalizer::ModelState ModelBasedLocalizer::DiffModel(
115 const ModelBasedLocalizer::ModelState &state,
116 const ModelBasedLocalizer::ModelInput &U) const {
117 ModelState x_dot = AModel(state) * state + B_continuous_model_ * U;
118 const double theta = state(kTheta);
119 const double stheta = std::sin(theta);
120 const double ctheta = std::cos(theta);
121 const double velocity = (state(kLeftVelocity) + state(kRightVelocity)) / 2.0;
122 x_dot(kX) = ctheta * velocity;
123 x_dot(kY) = stheta * velocity;
124 return x_dot;
125}
126
127ModelBasedLocalizer::AccelState ModelBasedLocalizer::DiffAccel(
128 const ModelBasedLocalizer::AccelState &state,
129 const ModelBasedLocalizer::AccelInput &U) const {
130 return AAccel() * state + B_continuous_accel_ * U;
131}
132
133ModelBasedLocalizer::ModelState ModelBasedLocalizer::UpdateModel(
134 const ModelBasedLocalizer::ModelState &model,
135 const ModelBasedLocalizer::ModelInput &input,
136 const aos::monotonic_clock::duration dt) const {
137 return control_loops::RungeKutta(
138 std::bind(&ModelBasedLocalizer::DiffModel, this, std::placeholders::_1,
139 input),
140 model, aos::time::DurationInSeconds(dt));
141}
142
143ModelBasedLocalizer::AccelState ModelBasedLocalizer::UpdateAccel(
144 const ModelBasedLocalizer::AccelState &accel,
145 const ModelBasedLocalizer::AccelInput &input,
146 const aos::monotonic_clock::duration dt) const {
147 return control_loops::RungeKutta(
148 std::bind(&ModelBasedLocalizer::DiffAccel, this, std::placeholders::_1,
149 input),
150 accel, aos::time::DurationInSeconds(dt));
151}
152
153ModelBasedLocalizer::AccelState ModelBasedLocalizer::AccelStateForModelState(
154 const ModelBasedLocalizer::ModelState &state) const {
155 const double robot_speed =
156 (state(kLeftVelocity) + state(kRightVelocity)) / 2.0;
157 const double velocity_x = std::cos(state(kTheta)) * robot_speed;
158 const double velocity_y = std::sin(state(kTheta)) * robot_speed;
159 return (AccelState() << state(0), state(1), state(2), velocity_x, velocity_y)
160 .finished();
161}
162
163ModelBasedLocalizer::ModelState ModelBasedLocalizer::ModelStateForAccelState(
164 const ModelBasedLocalizer::AccelState &state,
165 const Eigen::Vector2d &encoders, const double yaw_rate) const {
166 const double robot_speed = state(kVelocityX) * std::cos(state(kTheta)) +
167 state(kVelocityY) * std::sin(state(kTheta));
168 const double radius = dt_config_.robot_radius;
169 const double left_velocity = robot_speed - yaw_rate * radius;
170 const double right_velocity = robot_speed + yaw_rate * radius;
171 return (ModelState() << state(0), state(1), state(2), encoders(0),
172 left_velocity, 0.0, encoders(1), right_velocity, 0.0)
173 .finished();
174}
175
176double ModelBasedLocalizer::ModelDivergence(
177 const ModelBasedLocalizer::CombinedState &state,
178 const ModelBasedLocalizer::AccelInput &accel_inputs,
179 const Eigen::Vector2d &filtered_accel,
180 const ModelBasedLocalizer::ModelInput &model_inputs) {
181 // Convert the model state into the acceleration-based state-space and check
182 // the distance between the two (should really be a weighted norm, but all the
183 // numbers are on ~the same scale).
184 VLOG(2) << "divergence: "
185 << (state.accel_state - AccelStateForModelState(state.model_state))
186 .transpose();
187 const AccelState diff_accel = DiffAccel(state.accel_state, accel_inputs);
188 const ModelState diff_model = DiffModel(state.model_state, model_inputs);
189 const double model_lng_velocity =
190 (state.model_state(kLeftVelocity) + state.model_state(kRightVelocity)) /
191 2.0;
192 const double model_lng_accel =
193 (diff_model(kLeftVelocity) + diff_model(kRightVelocity)) / 2.0;
194 const Eigen::Vector2d robot_frame_accel(
195 model_lng_accel, diff_model(kTheta) * model_lng_velocity);
196 const Eigen::Vector2d model_accel =
197 Eigen::AngleAxisd(state.model_state(kTheta), Eigen::Vector3d::UnitZ())
198 .toRotationMatrix()
199 .block<2, 2>(0, 0) *
200 robot_frame_accel;
201 const double accel_diff = (model_accel - filtered_accel).norm();
202 const double theta_rate_diff =
203 std::abs(diff_accel(kTheta) - diff_model(kTheta));
204
205 const Eigen::Vector2d accel_vel = state.accel_state.bottomRows<2>();
206 const Eigen::Vector2d model_vel =
207 AccelStateForModelState(state.model_state).bottomRows<2>();
208 velocity_residual_ = (accel_vel - model_vel).norm() /
209 (1.0 + accel_vel.norm() + model_vel.norm());
210 theta_rate_residual_ = theta_rate_diff;
211 accel_residual_ = accel_diff / 4.0;
212 return velocity_residual_ + theta_rate_residual_ + accel_residual_;
213}
214
215void ModelBasedLocalizer::HandleImu(aos::monotonic_clock::time_point t,
216 const Eigen::Vector3d &gyro,
217 const Eigen::Vector3d &accel,
218 const Eigen::Vector2d encoders,
219 const Eigen::Vector2d voltage) {
220 VLOG(2) << t;
221 if (t_ == aos::monotonic_clock::min_time) {
222 t_ = t;
223 }
224 if (t_ + 2 * kNominalDt < t) {
225 t_ = t;
226 ++clock_resets_;
227 }
228 const aos::monotonic_clock::duration dt = t - t_;
229 t_ = t;
230 down_estimator_.Predict(gyro, accel, dt);
231 // TODO(james): Should we prefer this or use the down-estimator corrected
232 // version?
233 const double yaw_rate = (dt_config_.imu_transform * gyro)(2);
234 const double diameter = 2.0 * dt_config_.robot_radius;
235
236 const Eigen::AngleAxis<double> orientation(
237 Eigen::AngleAxis<double>(xytheta()(kTheta), Eigen::Vector3d::UnitZ()) *
238 down_estimator_.X_hat());
239
240 const Eigen::Vector3d absolute_accel =
241 orientation * dt_config_.imu_transform * kG * accel;
242 abs_accel_ = absolute_accel;
243 const Eigen::Vector3d absolute_gyro =
244 orientation * dt_config_.imu_transform * gyro;
245 (void)absolute_gyro;
246
247 VLOG(2) << "abs accel " << absolute_accel.transpose();
248 VLOG(2) << "abs gyro " << absolute_gyro.transpose();
249 VLOG(2) << "dt " << aos::time::DurationInSeconds(dt);
250
251 // Update all the branched states.
252 const AccelInput accel_input(absolute_accel.x(), absolute_accel.y(),
253 yaw_rate);
254 const ModelInput model_input(voltage);
255
256 const Eigen::Matrix<double, kNModelStates, kNModelStates> A_continuous =
257 AModel(current_state_.model_state);
258
259 Eigen::Matrix<double, kNModelStates, kNModelStates> A_discrete;
260 Eigen::Matrix<double, kNModelStates, kNModelStates> Q_discrete;
261
262 DiscretizeQAFast(Q_continuous_model_, A_continuous, dt, &Q_discrete,
263 &A_discrete);
264
265 P_model_ = A_discrete * P_model_ * A_discrete.transpose() + Q_discrete;
266
267 Eigen::Matrix<double, kNModelOutputs, kNModelStates> H;
268 Eigen::Matrix<double, kNModelOutputs, kNModelOutputs> R;
269 {
270 H.setZero();
271 R.setZero();
272 H(0, kLeftEncoder) = 1.0;
273 H(1, kRightEncoder) = 1.0;
274 H(2, kRightVelocity) = 1.0 / diameter;
275 H(2, kLeftVelocity) = -1.0 / diameter;
276
277 R.diagonal() << 1e-9, 1e-9, 1e-13;
278 }
279
280 const Eigen::Matrix<double, kNModelOutputs, 1> Z(encoders(0), encoders(1),
281 yaw_rate);
282
283 if (branches_.empty()) {
284 VLOG(2) << "Initializing";
285 current_state_.model_state.setZero();
286 current_state_.accel_state.setZero();
287 current_state_.model_state(kLeftEncoder) = encoders(0);
288 current_state_.model_state(kRightEncoder) = encoders(1);
289 current_state_.branch_time = t;
290 branches_.Push(current_state_);
291 }
292
293 const Eigen::Matrix<double, kNModelStates, kNModelOutputs> K =
294 P_model_ * H.transpose() * (H * P_model_ * H.transpose() + R).inverse();
295 P_model_ = (Eigen::Matrix<double, kNModelStates, kNModelStates>::Identity() -
296 K * H) *
297 P_model_;
298 VLOG(2) << "K\n" << K;
299 VLOG(2) << "Z\n" << Z.transpose();
300
301 for (CombinedState &state : branches_) {
302 state.accel_state = UpdateAccel(state.accel_state, accel_input, dt);
303 if (down_estimator_.consecutive_still() > 100.0) {
304 state.accel_state(kVelocityX) *= 0.9;
305 state.accel_state(kVelocityY) *= 0.9;
306 }
307 state.model_state = UpdateModel(state.model_state, model_input, dt);
308 state.model_state += K * (Z - H * state.model_state);
309 }
310
311 VLOG(2) << "oildest accel " << branches_[0].accel_state.transpose();
312 VLOG(2) << "oildest accel diff "
313 << DiffAccel(branches_[0].accel_state, accel_input).transpose();
314 VLOG(2) << "oildest model " << branches_[0].model_state.transpose();
315
316 // Determine whether to switch modes--if we are currently in model-based mode,
317 // swap to accel-based if the two states have divergeed meaningfully in the
318 // oldest branch. If we are currently in accel-based, then swap back to model
319 // if the oldest model branch matches has matched the
320 filtered_residual_accel_ +=
321 0.01 * (accel_input.topRows<2>() - filtered_residual_accel_);
322 const double model_divergence =
323 branches_.full() ? ModelDivergence(branches_[0], accel_input,
324 filtered_residual_accel_, model_input)
325 : 0.0;
326 filtered_residual_ +=
327 (1.0 - std::exp(-aos::time::DurationInSeconds(kNominalDt) / 0.0095)) *
328 (model_divergence - filtered_residual_);
329 constexpr double kUseAccelThreshold = 0.4;
330 constexpr double kUseModelThreshold = 0.2;
331 constexpr size_t kShareStates = kNModelStates;
332 static_assert(kUseModelThreshold < kUseAccelThreshold);
333 if (using_model_) {
334 if (filtered_residual_ > kUseAccelThreshold) {
335 hysteresis_count_++;
336 } else {
337 hysteresis_count_ = 0;
338 }
339 if (hysteresis_count_ > 0) {
340 using_model_ = false;
341 // Grab the accel-based state from back when we started diverging.
342 // TODO(james): This creates a problematic selection bias, because
343 // we will tend to bias towards deliberately out-of-tune measurements.
344 current_state_.accel_state = branches_[0].accel_state;
345 current_state_.model_state = branches_[0].model_state;
346 current_state_.model_state = ModelStateForAccelState(
347 current_state_.accel_state, encoders, yaw_rate);
348 } else {
349 VLOG(2) << "Normal branching";
350 current_state_.model_state = branches_[branches_.size() - 1].model_state;
351 current_state_.accel_state =
352 AccelStateForModelState(current_state_.model_state);
353 current_state_.branch_time = t;
354 }
355 hysteresis_count_ = 0;
356 } else {
357 if (filtered_residual_ < kUseModelThreshold) {
358 hysteresis_count_++;
359 } else {
360 hysteresis_count_ = 0;
361 }
362 if (hysteresis_count_ > 100) {
363 using_model_ = true;
364 // Grab the model-based state from back when we stopped diverging.
365 current_state_.model_state.topRows<kShareStates>() =
366 ModelStateForAccelState(branches_[0].accel_state, encoders, yaw_rate)
367 .topRows<kShareStates>();
368 current_state_.accel_state =
369 AccelStateForModelState(current_state_.model_state);
370 } else {
371 current_state_.accel_state = branches_[branches_.size() - 1].accel_state;
372 // TODO(james): Why was I leaving the encoders/wheel velocities in place?
373 current_state_.model_state = branches_[branches_.size() - 1].model_state;
374 current_state_.model_state = ModelStateForAccelState(
375 current_state_.accel_state, encoders, yaw_rate);
376 current_state_.branch_time = t;
377 }
378 }
379
380 // Generate a new branch, with the accel state reset based on the model-based
381 // state (really, just getting rid of the lateral velocity).
382 CombinedState new_branch = current_state_;
383 //if (!keep_accel_state) {
384 if (using_model_) {
385 new_branch.accel_state = AccelStateForModelState(new_branch.model_state);
386 }
387 new_branch.accumulated_divergence = 0.0;
388
James Kuszmaul93825a02022-02-13 16:50:33 -0800389 ++branch_counter_;
390 if (branch_counter_ % kBranchPeriod == 0) {
391 branches_.Push(new_branch);
392 branch_counter_ = 0;
393 }
James Kuszmaul29c59522022-02-12 16:44:26 -0800394
395 last_residual_ = model_divergence;
396
397 VLOG(2) << "Using " << (using_model_ ? "model" : "accel");
398 VLOG(2) << "Residual " << last_residual_;
399 VLOG(2) << "Filtered Residual " << filtered_residual_;
400 VLOG(2) << "buffer size " << branches_.size();
401 VLOG(2) << "Model state " << current_state_.model_state.transpose();
402 VLOG(2) << "Accel state " << current_state_.accel_state.transpose();
403 VLOG(2) << "Accel state for model "
404 << AccelStateForModelState(current_state_.model_state).transpose();
405 VLOG(2) << "Input acce " << accel.transpose();
406 VLOG(2) << "Input gyro " << gyro.transpose();
407 VLOG(2) << "Input voltage " << voltage.transpose();
408 VLOG(2) << "Input encoder " << encoders.transpose();
409 VLOG(2) << "yaw rate " << yaw_rate;
410
411 CHECK(std::isfinite(last_residual_));
412}
413
414void ModelBasedLocalizer::HandleReset(aos::monotonic_clock::time_point now,
415 const Eigen::Vector3d &xytheta) {
416 branches_.Reset();
417 t_ = now;
418 using_model_ = true;
419 current_state_.model_state << xytheta(0), xytheta(1), xytheta(2),
420 current_state_.model_state(kLeftEncoder), 0.0, 0.0,
421 current_state_.model_state(kRightEncoder), 0.0, 0.0;
422 current_state_.accel_state =
423 AccelStateForModelState(current_state_.model_state);
424 last_residual_ = 0.0;
425 filtered_residual_ = 0.0;
426 filtered_residual_accel_.setZero();
427 abs_accel_.setZero();
428}
429
430flatbuffers::Offset<AccelBasedState> ModelBasedLocalizer::BuildAccelState(
431 flatbuffers::FlatBufferBuilder *fbb, const AccelState &state) {
432 AccelBasedState::Builder accel_state_builder(*fbb);
433 accel_state_builder.add_x(state(kX));
434 accel_state_builder.add_y(state(kY));
435 accel_state_builder.add_theta(state(kTheta));
436 accel_state_builder.add_velocity_x(state(kVelocityX));
437 accel_state_builder.add_velocity_y(state(kVelocityY));
438 return accel_state_builder.Finish();
439}
440
441flatbuffers::Offset<ModelBasedState> ModelBasedLocalizer::BuildModelState(
442 flatbuffers::FlatBufferBuilder *fbb, const ModelState &state) {
443 ModelBasedState::Builder model_state_builder(*fbb);
444 model_state_builder.add_x(state(kX));
445 model_state_builder.add_y(state(kY));
446 model_state_builder.add_theta(state(kTheta));
447 model_state_builder.add_left_encoder(state(kLeftEncoder));
448 model_state_builder.add_left_velocity(state(kLeftVelocity));
449 model_state_builder.add_left_voltage_error(state(kLeftVoltageError));
450 model_state_builder.add_right_encoder(state(kRightEncoder));
451 model_state_builder.add_right_velocity(state(kRightVelocity));
452 model_state_builder.add_right_voltage_error(state(kRightVoltageError));
453 return model_state_builder.Finish();
454}
455
456flatbuffers::Offset<ModelBasedStatus> ModelBasedLocalizer::PopulateStatus(
457 flatbuffers::FlatBufferBuilder *fbb) {
458 const flatbuffers::Offset<control_loops::drivetrain::DownEstimatorState>
459 down_estimator_offset = down_estimator_.PopulateStatus(fbb, t_);
460
461 const CombinedState &state = current_state_;
462
463 const flatbuffers::Offset<ModelBasedState> model_state_offset =
464 BuildModelState(fbb, state.model_state);
465
466 const flatbuffers::Offset<AccelBasedState> accel_state_offset =
467 BuildAccelState(fbb, state.accel_state);
468
469 const flatbuffers::Offset<AccelBasedState> oldest_accel_state_offset =
470 branches_.empty() ? flatbuffers::Offset<AccelBasedState>()
471 : BuildAccelState(fbb, branches_[0].accel_state);
472
473 const flatbuffers::Offset<ModelBasedState> oldest_model_state_offset =
474 branches_.empty() ? flatbuffers::Offset<ModelBasedState>()
475 : BuildModelState(fbb, branches_[0].model_state);
476
477 ModelBasedStatus::Builder builder(*fbb);
478 builder.add_accel_state(accel_state_offset);
479 builder.add_oldest_accel_state(oldest_accel_state_offset);
480 builder.add_oldest_model_state(oldest_model_state_offset);
481 builder.add_model_state(model_state_offset);
482 builder.add_using_model(using_model_);
483 builder.add_residual(last_residual_);
484 builder.add_filtered_residual(filtered_residual_);
485 builder.add_velocity_residual(velocity_residual_);
486 builder.add_accel_residual(accel_residual_);
487 builder.add_theta_rate_residual(theta_rate_residual_);
488 builder.add_down_estimator(down_estimator_offset);
489 builder.add_x(xytheta()(0));
490 builder.add_y(xytheta()(1));
491 builder.add_theta(xytheta()(2));
492 builder.add_implied_accel_x(abs_accel_(0));
493 builder.add_implied_accel_y(abs_accel_(1));
494 builder.add_implied_accel_z(abs_accel_(2));
495 builder.add_clock_resets(clock_resets_);
496 return builder.Finish();
497}
498
499EventLoopLocalizer::EventLoopLocalizer(
500 aos::EventLoop *event_loop,
501 const control_loops::drivetrain::DrivetrainConfig<double> &dt_config)
502 : event_loop_(event_loop),
503 model_based_(dt_config),
504 status_sender_(event_loop_->MakeSender<LocalizerStatus>("/localizer")),
505 output_sender_(event_loop_->MakeSender<LocalizerOutput>("/localizer")),
James Kuszmaul29c59522022-02-12 16:44:26 -0800506 output_fetcher_(
507 event_loop_->MakeFetcher<frc971::control_loops::drivetrain::Output>(
508 "/drivetrain")) {
509 event_loop_->MakeWatcher(
510 "/drivetrain",
511 [this](
512 const frc971::control_loops::drivetrain::LocalizerControl &control) {
513 const double theta = control.keep_current_theta()
514 ? model_based_.xytheta()(2)
515 : control.theta();
516 model_based_.HandleReset(event_loop_->monotonic_now(),
517 {control.x(), control.y(), theta});
518 });
519 event_loop_->MakeWatcher(
520 "/localizer", [this](const frc971::IMUValuesBatch &values) {
521 CHECK(values.has_readings());
James Kuszmaul29c59522022-02-12 16:44:26 -0800522 output_fetcher_.Fetch();
523 for (const IMUValues *value : *values.readings()) {
524 zeroer_.InsertAndProcessMeasurement(*value);
525 if (zeroer_.Zeroed()) {
James Kuszmaule5f67dd2022-02-12 20:08:29 -0800526 if (output_fetcher_.get() != nullptr) {
527 const bool disabled =
528 output_fetcher_.context().monotonic_event_time +
529 std::chrono::milliseconds(10) <
530 event_loop_->context().monotonic_event_time;
531 model_based_.HandleImu(
532 aos::monotonic_clock::time_point(std::chrono::nanoseconds(
533 value->monotonic_timestamp_ns())),
534 zeroer_.ZeroedGyro(), zeroer_.ZeroedAccel(),
535 {value->left_encoder(), value->right_encoder()},
536 disabled ? Eigen::Vector2d::Zero()
537 : Eigen::Vector2d{output_fetcher_->left_voltage(),
538 output_fetcher_->right_voltage()});
539 }
James Kuszmaul29c59522022-02-12 16:44:26 -0800540 }
541 {
542 auto builder = status_sender_.MakeBuilder();
543 const flatbuffers::Offset<ModelBasedStatus> model_based_status =
544 model_based_.PopulateStatus(builder.fbb());
545 LocalizerStatus::Builder status_builder =
546 builder.MakeBuilder<LocalizerStatus>();
547 status_builder.add_model_based(model_based_status);
548 status_builder.add_zeroed(zeroer_.Zeroed());
549 status_builder.add_faulted_zero(zeroer_.Faulted());
550 builder.CheckOk(builder.Send(status_builder.Finish()));
551 }
552 if (last_output_send_ + std::chrono::milliseconds(5) <
553 event_loop_->context().monotonic_event_time) {
554 auto builder = output_sender_.MakeBuilder();
555 LocalizerOutput::Builder output_builder =
556 builder.MakeBuilder<LocalizerOutput>();
James Kuszmaul1798c072022-02-13 15:32:11 -0800557 // TODO(james): Should we bother to try to estimate time offsets for
558 // the pico?
559 output_builder.add_monotonic_timestamp_ns(
560 value->monotonic_timestamp_ns());
James Kuszmaul29c59522022-02-12 16:44:26 -0800561 output_builder.add_x(model_based_.xytheta()(0));
562 output_builder.add_y(model_based_.xytheta()(1));
563 output_builder.add_theta(model_based_.xytheta()(2));
564 builder.CheckOk(builder.Send(output_builder.Finish()));
565 last_output_send_ = event_loop_->monotonic_now();
566 }
567 }
568 });
569}
570
571} // namespace frc971::controls