blob: 0e8a7e57cd2c45d76c0fe2dbd6a1cfbd703ce13c [file] [log] [blame]
James Kuszmaul51fa1ae2022-02-26 00:49:57 -08001#include "y2022/localizer/localizer.h"
James Kuszmaul29c59522022-02-12 16:44:26 -08002
Austin Schuh99f7c6a2024-06-25 22:07:44 -07003#include "absl/flags/flag.h"
4
James Kuszmaulf6b69112022-03-12 21:34:39 -08005#include "aos/json_to_flatbuffer.h"
James Kuszmaul29c59522022-02-12 16:44:26 -08006#include "frc971/control_loops/c2d.h"
7#include "frc971/wpilib/imu_batch_generated.h"
James Kuszmaul5ed29dd2022-02-13 18:32:06 -08008#include "y2022/constants.h"
James Kuszmaul29c59522022-02-12 16:44:26 -08009
Austin Schuh99f7c6a2024-06-25 22:07:44 -070010ABSL_FLAG(bool, ignore_accelerometer, false,
11 "If set, ignores the accelerometer readings.");
James Kuszmaulce491e42022-03-12 21:02:10 -080012
James Kuszmaul29c59522022-02-12 16:44:26 -080013namespace frc971::controls {
14
15namespace {
16constexpr double kG = 9.80665;
James Kuszmaul9f2f53c2023-02-19 14:08:18 -080017static constexpr std::chrono::microseconds kNominalDt = ImuWatcher::kNominalDt;
James Kuszmaul8c4f6592022-02-26 15:49:30 -080018// Field position of the target (the 2022 target is conveniently in the middle
19// of the field....).
20constexpr double kVisionTargetX = 0.0;
21constexpr double kVisionTargetY = 0.0;
22
James Kuszmaulaa39d962022-03-06 14:54:28 -080023// Minimum confidence to require to use a target match.
James Kuszmaul1b918d82022-03-12 18:27:41 -080024constexpr double kMinTargetEstimateConfidence = 0.75;
James Kuszmaulaa39d962022-03-06 14:54:28 -080025
James Kuszmaul29c59522022-02-12 16:44:26 -080026template <int N>
27Eigen::Matrix<double, N, 1> MakeState(std::vector<double> values) {
28 CHECK_EQ(static_cast<size_t>(N), values.size());
29 Eigen::Matrix<double, N, 1> vector;
30 for (int ii = 0; ii < N; ++ii) {
31 vector(ii, 0) = values[ii];
32 }
33 return vector;
34}
James Kuszmaul29c59522022-02-12 16:44:26 -080035} // namespace
36
37ModelBasedLocalizer::ModelBasedLocalizer(
38 const control_loops::drivetrain::DrivetrainConfig<double> &dt_config)
39 : dt_config_(dt_config),
40 velocity_drivetrain_coefficients_(
41 dt_config.make_hybrid_drivetrain_velocity_loop()
42 .plant()
43 .coefficients()),
44 down_estimator_(dt_config) {
James Kuszmaul8c4f6592022-02-26 15:49:30 -080045 statistics_.rejection_counts.fill(0);
James Kuszmaulf6b69112022-03-12 21:34:39 -080046 CHECK_EQ(branches_.capacity(),
47 static_cast<size_t>(std::chrono::seconds(1) / kNominalDt /
48 kBranchPeriod));
James Kuszmaul29c59522022-02-12 16:44:26 -080049 if (dt_config_.is_simulated) {
50 down_estimator_.assume_perfect_gravity();
51 }
52 A_continuous_accel_.setZero();
53 A_continuous_model_.setZero();
54 B_continuous_accel_.setZero();
55 B_continuous_model_.setZero();
56
57 A_continuous_accel_(kX, kVelocityX) = 1.0;
58 A_continuous_accel_(kY, kVelocityY) = 1.0;
59
60 const double diameter = 2.0 * dt_config_.robot_radius;
61
62 A_continuous_model_(kTheta, kLeftVelocity) = -1.0 / diameter;
63 A_continuous_model_(kTheta, kRightVelocity) = 1.0 / diameter;
64 A_continuous_model_(kLeftEncoder, kLeftVelocity) = 1.0;
65 A_continuous_model_(kRightEncoder, kRightVelocity) = 1.0;
66 const auto &vel_coefs = velocity_drivetrain_coefficients_;
67 A_continuous_model_(kLeftVelocity, kLeftVelocity) =
68 vel_coefs.A_continuous(0, 0);
69 A_continuous_model_(kLeftVelocity, kRightVelocity) =
70 vel_coefs.A_continuous(0, 1);
71 A_continuous_model_(kRightVelocity, kLeftVelocity) =
72 vel_coefs.A_continuous(1, 0);
73 A_continuous_model_(kRightVelocity, kRightVelocity) =
74 vel_coefs.A_continuous(1, 1);
75
76 A_continuous_model_(kLeftVelocity, kLeftVoltageError) =
77 1 * vel_coefs.B_continuous(0, 0);
78 A_continuous_model_(kLeftVelocity, kRightVoltageError) =
79 1 * vel_coefs.B_continuous(0, 1);
80 A_continuous_model_(kRightVelocity, kLeftVoltageError) =
81 1 * vel_coefs.B_continuous(1, 0);
82 A_continuous_model_(kRightVelocity, kRightVoltageError) =
83 1 * vel_coefs.B_continuous(1, 1);
84
85 B_continuous_model_.block<1, 2>(kLeftVelocity, kLeftVoltage) =
86 vel_coefs.B_continuous.row(0);
87 B_continuous_model_.block<1, 2>(kRightVelocity, kLeftVoltage) =
88 vel_coefs.B_continuous.row(1);
89
90 B_continuous_accel_(kVelocityX, kAccelX) = 1.0;
91 B_continuous_accel_(kVelocityY, kAccelY) = 1.0;
92 B_continuous_accel_(kTheta, kThetaRate) = 1.0;
93
94 Q_continuous_model_.setZero();
James Kuszmaul8c4f6592022-02-26 15:49:30 -080095 Q_continuous_model_.diagonal() << 1e-2, 1e-2, 1e-8, 1e-2, 1e-0, 1e-0, 1e-2,
James Kuszmaul29c59522022-02-12 16:44:26 -080096 1e-0, 1e-0;
97
James Kuszmaul8c4f6592022-02-26 15:49:30 -080098 Q_continuous_accel_.setZero();
99 Q_continuous_accel_.diagonal() << 1e-2, 1e-2, 1e-20, 1e-4, 1e-4;
100
James Kuszmaul29c59522022-02-12 16:44:26 -0800101 P_model_ = Q_continuous_model_ * aos::time::DurationInSeconds(kNominalDt);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800102
103 // We can precalculate the discretizations of the accel model because it is
104 // actually LTI.
105
106 DiscretizeQAFast(Q_continuous_accel_, A_continuous_accel_, kNominalDt,
107 &Q_discrete_accel_, &A_discrete_accel_);
108 P_accel_ = Q_discrete_accel_;
Milind Upadhyayd67e9cf2022-03-13 13:56:57 -0700109
110 led_outputs_.fill(LedOutput::ON);
James Kuszmaul29c59522022-02-12 16:44:26 -0800111}
112
113Eigen::Matrix<double, ModelBasedLocalizer::kNModelStates,
114 ModelBasedLocalizer::kNModelStates>
115ModelBasedLocalizer::AModel(
116 const ModelBasedLocalizer::ModelState &state) const {
117 Eigen::Matrix<double, kNModelStates, kNModelStates> A = A_continuous_model_;
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 A(kX, kTheta) = -stheta * velocity;
123 A(kX, kLeftVelocity) = ctheta / 2.0;
124 A(kX, kRightVelocity) = ctheta / 2.0;
125 A(kY, kTheta) = ctheta * velocity;
126 A(kY, kLeftVelocity) = stheta / 2.0;
127 A(kY, kRightVelocity) = stheta / 2.0;
128 return A;
129}
130
131Eigen::Matrix<double, ModelBasedLocalizer::kNAccelStates,
132 ModelBasedLocalizer::kNAccelStates>
133ModelBasedLocalizer::AAccel() const {
134 return A_continuous_accel_;
135}
136
137ModelBasedLocalizer::ModelState ModelBasedLocalizer::DiffModel(
138 const ModelBasedLocalizer::ModelState &state,
139 const ModelBasedLocalizer::ModelInput &U) const {
140 ModelState x_dot = AModel(state) * state + B_continuous_model_ * U;
141 const double theta = state(kTheta);
142 const double stheta = std::sin(theta);
143 const double ctheta = std::cos(theta);
144 const double velocity = (state(kLeftVelocity) + state(kRightVelocity)) / 2.0;
145 x_dot(kX) = ctheta * velocity;
146 x_dot(kY) = stheta * velocity;
147 return x_dot;
148}
149
150ModelBasedLocalizer::AccelState ModelBasedLocalizer::DiffAccel(
151 const ModelBasedLocalizer::AccelState &state,
152 const ModelBasedLocalizer::AccelInput &U) const {
153 return AAccel() * state + B_continuous_accel_ * U;
154}
155
156ModelBasedLocalizer::ModelState ModelBasedLocalizer::UpdateModel(
157 const ModelBasedLocalizer::ModelState &model,
158 const ModelBasedLocalizer::ModelInput &input,
159 const aos::monotonic_clock::duration dt) const {
160 return control_loops::RungeKutta(
161 std::bind(&ModelBasedLocalizer::DiffModel, this, std::placeholders::_1,
162 input),
163 model, aos::time::DurationInSeconds(dt));
164}
165
166ModelBasedLocalizer::AccelState ModelBasedLocalizer::UpdateAccel(
167 const ModelBasedLocalizer::AccelState &accel,
168 const ModelBasedLocalizer::AccelInput &input,
169 const aos::monotonic_clock::duration dt) const {
170 return control_loops::RungeKutta(
171 std::bind(&ModelBasedLocalizer::DiffAccel, this, std::placeholders::_1,
172 input),
173 accel, aos::time::DurationInSeconds(dt));
174}
175
176ModelBasedLocalizer::AccelState ModelBasedLocalizer::AccelStateForModelState(
177 const ModelBasedLocalizer::ModelState &state) const {
178 const double robot_speed =
179 (state(kLeftVelocity) + state(kRightVelocity)) / 2.0;
James Kuszmaulf6b69112022-03-12 21:34:39 -0800180 const double lat_speed = (AModel(state) * state)(kTheta)*long_offset_;
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800181 const double velocity_x = std::cos(state(kTheta)) * robot_speed -
182 std::sin(state(kTheta)) * lat_speed;
183 const double velocity_y = std::sin(state(kTheta)) * robot_speed +
184 std::cos(state(kTheta)) * lat_speed;
James Kuszmaul29c59522022-02-12 16:44:26 -0800185 return (AccelState() << state(0), state(1), state(2), velocity_x, velocity_y)
186 .finished();
187}
188
189ModelBasedLocalizer::ModelState ModelBasedLocalizer::ModelStateForAccelState(
190 const ModelBasedLocalizer::AccelState &state,
191 const Eigen::Vector2d &encoders, const double yaw_rate) const {
192 const double robot_speed = state(kVelocityX) * std::cos(state(kTheta)) +
193 state(kVelocityY) * std::sin(state(kTheta));
194 const double radius = dt_config_.robot_radius;
195 const double left_velocity = robot_speed - yaw_rate * radius;
196 const double right_velocity = robot_speed + yaw_rate * radius;
197 return (ModelState() << state(0), state(1), state(2), encoders(0),
198 left_velocity, 0.0, encoders(1), right_velocity, 0.0)
199 .finished();
200}
201
202double ModelBasedLocalizer::ModelDivergence(
203 const ModelBasedLocalizer::CombinedState &state,
204 const ModelBasedLocalizer::AccelInput &accel_inputs,
205 const Eigen::Vector2d &filtered_accel,
206 const ModelBasedLocalizer::ModelInput &model_inputs) {
207 // Convert the model state into the acceleration-based state-space and check
208 // the distance between the two (should really be a weighted norm, but all the
209 // numbers are on ~the same scale).
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800210 // TODO(james): Maybe weight lateral velocity divergence different than
211 // longitudinal? Seems like we tend to get false-positives currently when in
212 // sharp turns.
213 // TODO(james): For off-center gyros, maybe reduce noise when turning?
James Kuszmaul29c59522022-02-12 16:44:26 -0800214 VLOG(2) << "divergence: "
215 << (state.accel_state - AccelStateForModelState(state.model_state))
216 .transpose();
217 const AccelState diff_accel = DiffAccel(state.accel_state, accel_inputs);
218 const ModelState diff_model = DiffModel(state.model_state, model_inputs);
219 const double model_lng_velocity =
220 (state.model_state(kLeftVelocity) + state.model_state(kRightVelocity)) /
221 2.0;
222 const double model_lng_accel =
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800223 (diff_model(kLeftVelocity) + diff_model(kRightVelocity)) / 2.0 -
224 diff_model(kTheta) * diff_model(kTheta) * long_offset_;
225 const double model_lat_accel = diff_model(kTheta) * model_lng_velocity;
226 const Eigen::Vector2d robot_frame_accel(model_lng_accel, model_lat_accel);
James Kuszmaul29c59522022-02-12 16:44:26 -0800227 const Eigen::Vector2d model_accel =
228 Eigen::AngleAxisd(state.model_state(kTheta), Eigen::Vector3d::UnitZ())
229 .toRotationMatrix()
230 .block<2, 2>(0, 0) *
231 robot_frame_accel;
232 const double accel_diff = (model_accel - filtered_accel).norm();
233 const double theta_rate_diff =
234 std::abs(diff_accel(kTheta) - diff_model(kTheta));
235
236 const Eigen::Vector2d accel_vel = state.accel_state.bottomRows<2>();
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800237 Eigen::Vector2d model_vel =
James Kuszmaul29c59522022-02-12 16:44:26 -0800238 AccelStateForModelState(state.model_state).bottomRows<2>();
239 velocity_residual_ = (accel_vel - model_vel).norm() /
240 (1.0 + accel_vel.norm() + model_vel.norm());
241 theta_rate_residual_ = theta_rate_diff;
242 accel_residual_ = accel_diff / 4.0;
243 return velocity_residual_ + theta_rate_residual_ + accel_residual_;
244}
245
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800246void ModelBasedLocalizer::UpdateState(
247 CombinedState *state,
248 const Eigen::Matrix<double, kNModelStates, kNModelOutputs> &K,
249 const Eigen::Matrix<double, kNModelOutputs, 1> &Z,
250 const Eigen::Matrix<double, kNModelOutputs, kNModelStates> &H,
251 const AccelInput &accel_input, const ModelInput &model_input,
252 aos::monotonic_clock::duration dt) {
253 state->accel_state = UpdateAccel(state->accel_state, accel_input, dt);
254 if (down_estimator_.consecutive_still() > 500.0) {
255 state->accel_state(kVelocityX) *= 0.9;
256 state->accel_state(kVelocityY) *= 0.9;
257 }
258 state->model_state = UpdateModel(state->model_state, model_input, dt);
259 state->model_state += K * (Z - H * state->model_state);
260}
261
James Kuszmaul5a5a7832022-03-16 23:15:08 -0700262void ModelBasedLocalizer::HandleImu(
263 aos::monotonic_clock::time_point t, const Eigen::Vector3d &gyro,
264 const Eigen::Vector3d &accel, const std::optional<Eigen::Vector2d> encoders,
265 const Eigen::Vector2d voltage) {
James Kuszmaul29c59522022-02-12 16:44:26 -0800266 VLOG(2) << t;
267 if (t_ == aos::monotonic_clock::min_time) {
268 t_ = t;
269 }
James Kuszmaul5f27d8b2022-03-17 09:08:26 -0700270 if (t_ + 10 * kNominalDt < t) {
James Kuszmaul29c59522022-02-12 16:44:26 -0800271 t_ = t;
272 ++clock_resets_;
273 }
274 const aos::monotonic_clock::duration dt = t - t_;
275 t_ = t;
276 down_estimator_.Predict(gyro, accel, dt);
277 // TODO(james): Should we prefer this or use the down-estimator corrected
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800278 // version? Using the down estimator is more principled, but does create more
279 // opportunities for subtle biases.
James Kuszmaul29c59522022-02-12 16:44:26 -0800280 const double yaw_rate = (dt_config_.imu_transform * gyro)(2);
281 const double diameter = 2.0 * dt_config_.robot_radius;
282
283 const Eigen::AngleAxis<double> orientation(
284 Eigen::AngleAxis<double>(xytheta()(kTheta), Eigen::Vector3d::UnitZ()) *
285 down_estimator_.X_hat());
James Kuszmaul10d3fd42022-02-25 21:57:36 -0800286 last_orientation_ = orientation;
James Kuszmaul29c59522022-02-12 16:44:26 -0800287
288 const Eigen::Vector3d absolute_accel =
289 orientation * dt_config_.imu_transform * kG * accel;
290 abs_accel_ = absolute_accel;
James Kuszmaul29c59522022-02-12 16:44:26 -0800291
292 VLOG(2) << "abs accel " << absolute_accel.transpose();
James Kuszmaul29c59522022-02-12 16:44:26 -0800293 VLOG(2) << "dt " << aos::time::DurationInSeconds(dt);
294
295 // Update all the branched states.
296 const AccelInput accel_input(absolute_accel.x(), absolute_accel.y(),
297 yaw_rate);
298 const ModelInput model_input(voltage);
299
300 const Eigen::Matrix<double, kNModelStates, kNModelStates> A_continuous =
301 AModel(current_state_.model_state);
302
303 Eigen::Matrix<double, kNModelStates, kNModelStates> A_discrete;
304 Eigen::Matrix<double, kNModelStates, kNModelStates> Q_discrete;
305
306 DiscretizeQAFast(Q_continuous_model_, A_continuous, dt, &Q_discrete,
307 &A_discrete);
308
309 P_model_ = A_discrete * P_model_ * A_discrete.transpose() + Q_discrete;
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800310 P_accel_ = A_discrete_accel_ * P_accel_ * A_discrete_accel_.transpose() +
311 Q_discrete_accel_;
James Kuszmaul29c59522022-02-12 16:44:26 -0800312
313 Eigen::Matrix<double, kNModelOutputs, kNModelStates> H;
314 Eigen::Matrix<double, kNModelOutputs, kNModelOutputs> R;
315 {
316 H.setZero();
317 R.setZero();
318 H(0, kLeftEncoder) = 1.0;
319 H(1, kRightEncoder) = 1.0;
320 H(2, kRightVelocity) = 1.0 / diameter;
321 H(2, kLeftVelocity) = -1.0 / diameter;
322
323 R.diagonal() << 1e-9, 1e-9, 1e-13;
324 }
325
James Kuszmaul5a5a7832022-03-16 23:15:08 -0700326 const Eigen::Matrix<double, kNModelOutputs, 1> Z =
327 encoders.has_value()
328 ? Eigen::Vector3d(encoders.value()(0), encoders.value()(1), yaw_rate)
329 : Eigen::Vector3d(current_state_.model_state(kLeftEncoder),
330 current_state_.model_state(kRightEncoder),
331 yaw_rate);
James Kuszmaul29c59522022-02-12 16:44:26 -0800332
333 if (branches_.empty()) {
334 VLOG(2) << "Initializing";
James Kuszmaul5a5a7832022-03-16 23:15:08 -0700335 current_state_.model_state(kLeftEncoder) = Z(0);
336 current_state_.model_state(kRightEncoder) = Z(1);
James Kuszmaul29c59522022-02-12 16:44:26 -0800337 current_state_.branch_time = t;
338 branches_.Push(current_state_);
339 }
340
341 const Eigen::Matrix<double, kNModelStates, kNModelOutputs> K =
342 P_model_ * H.transpose() * (H * P_model_ * H.transpose() + R).inverse();
343 P_model_ = (Eigen::Matrix<double, kNModelStates, kNModelStates>::Identity() -
344 K * H) *
345 P_model_;
346 VLOG(2) << "K\n" << K;
347 VLOG(2) << "Z\n" << Z.transpose();
348
349 for (CombinedState &state : branches_) {
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800350 UpdateState(&state, K, Z, H, accel_input, model_input, dt);
James Kuszmaul29c59522022-02-12 16:44:26 -0800351 }
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800352 UpdateState(&current_state_, K, Z, H, accel_input, model_input, dt);
James Kuszmaul29c59522022-02-12 16:44:26 -0800353
354 VLOG(2) << "oildest accel " << branches_[0].accel_state.transpose();
355 VLOG(2) << "oildest accel diff "
356 << DiffAccel(branches_[0].accel_state, accel_input).transpose();
357 VLOG(2) << "oildest model " << branches_[0].model_state.transpose();
358
359 // Determine whether to switch modes--if we are currently in model-based mode,
360 // swap to accel-based if the two states have divergeed meaningfully in the
361 // oldest branch. If we are currently in accel-based, then swap back to model
362 // if the oldest model branch matches has matched the
363 filtered_residual_accel_ +=
364 0.01 * (accel_input.topRows<2>() - filtered_residual_accel_);
365 const double model_divergence =
366 branches_.full() ? ModelDivergence(branches_[0], accel_input,
367 filtered_residual_accel_, model_input)
368 : 0.0;
369 filtered_residual_ +=
370 (1.0 - std::exp(-aos::time::DurationInSeconds(kNominalDt) / 0.0095)) *
371 (model_divergence - filtered_residual_);
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800372 // TODO(james): Tune this more. Currently set to generally trust the model,
373 // perhaps a bit too much.
374 // When the residual exceeds the accel threshold, we start using the inertials
375 // alone; when it drops back below the model threshold, we go back to being
376 // model-based.
377 constexpr double kUseAccelThreshold = 2.0;
378 constexpr double kUseModelThreshold = 0.5;
James Kuszmaul29c59522022-02-12 16:44:26 -0800379 constexpr size_t kShareStates = kNModelStates;
380 static_assert(kUseModelThreshold < kUseAccelThreshold);
381 if (using_model_) {
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700382 if (!absl::GetFlag(FLAGS_ignore_accelerometer) &&
James Kuszmaulce491e42022-03-12 21:02:10 -0800383 filtered_residual_ > kUseAccelThreshold) {
James Kuszmaul29c59522022-02-12 16:44:26 -0800384 hysteresis_count_++;
385 } else {
386 hysteresis_count_ = 0;
387 }
388 if (hysteresis_count_ > 0) {
389 using_model_ = false;
390 // Grab the accel-based state from back when we started diverging.
391 // TODO(james): This creates a problematic selection bias, because
392 // we will tend to bias towards deliberately out-of-tune measurements.
393 current_state_.accel_state = branches_[0].accel_state;
394 current_state_.model_state = branches_[0].model_state;
395 current_state_.model_state = ModelStateForAccelState(
James Kuszmaul5a5a7832022-03-16 23:15:08 -0700396 current_state_.accel_state, Z.topRows<2>(), yaw_rate);
James Kuszmaul29c59522022-02-12 16:44:26 -0800397 } else {
398 VLOG(2) << "Normal branching";
James Kuszmaul29c59522022-02-12 16:44:26 -0800399 current_state_.accel_state =
400 AccelStateForModelState(current_state_.model_state);
401 current_state_.branch_time = t;
402 }
403 hysteresis_count_ = 0;
404 } else {
405 if (filtered_residual_ < kUseModelThreshold) {
406 hysteresis_count_++;
407 } else {
408 hysteresis_count_ = 0;
409 }
410 if (hysteresis_count_ > 100) {
411 using_model_ = true;
412 // Grab the model-based state from back when we stopped diverging.
413 current_state_.model_state.topRows<kShareStates>() =
James Kuszmaul5a5a7832022-03-16 23:15:08 -0700414 ModelStateForAccelState(branches_[0].accel_state, Z.topRows<2>(),
415 yaw_rate)
James Kuszmaul29c59522022-02-12 16:44:26 -0800416 .topRows<kShareStates>();
417 current_state_.accel_state =
418 AccelStateForModelState(current_state_.model_state);
419 } else {
James Kuszmaul29c59522022-02-12 16:44:26 -0800420 // TODO(james): Why was I leaving the encoders/wheel velocities in place?
James Kuszmaul29c59522022-02-12 16:44:26 -0800421 current_state_.model_state = ModelStateForAccelState(
James Kuszmaul5a5a7832022-03-16 23:15:08 -0700422 current_state_.accel_state, Z.topRows<2>(), yaw_rate);
James Kuszmaul29c59522022-02-12 16:44:26 -0800423 current_state_.branch_time = t;
424 }
425 }
426
427 // Generate a new branch, with the accel state reset based on the model-based
428 // state (really, just getting rid of the lateral velocity).
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800429 // By resetting the accel state in the new branch, this tries to minimize the
430 // odds of runaway lateral velocities. This doesn't help with runaway
431 // longitudinal velocities, however.
James Kuszmaul29c59522022-02-12 16:44:26 -0800432 CombinedState new_branch = current_state_;
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800433 new_branch.accel_state = AccelStateForModelState(new_branch.model_state);
James Kuszmaul29c59522022-02-12 16:44:26 -0800434 new_branch.accumulated_divergence = 0.0;
435
James Kuszmaul93825a02022-02-13 16:50:33 -0800436 ++branch_counter_;
437 if (branch_counter_ % kBranchPeriod == 0) {
438 branches_.Push(new_branch);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800439 old_positions_.Push(OldPosition{t, xytheta(), latest_turret_position_,
440 latest_turret_velocity_});
James Kuszmaul93825a02022-02-13 16:50:33 -0800441 branch_counter_ = 0;
442 }
James Kuszmaul29c59522022-02-12 16:44:26 -0800443
444 last_residual_ = model_divergence;
445
446 VLOG(2) << "Using " << (using_model_ ? "model" : "accel");
447 VLOG(2) << "Residual " << last_residual_;
448 VLOG(2) << "Filtered Residual " << filtered_residual_;
449 VLOG(2) << "buffer size " << branches_.size();
450 VLOG(2) << "Model state " << current_state_.model_state.transpose();
451 VLOG(2) << "Accel state " << current_state_.accel_state.transpose();
452 VLOG(2) << "Accel state for model "
James Kuszmaulf6b69112022-03-12 21:34:39 -0800453 << AccelStateForModelState(current_state_.model_state).transpose();
James Kuszmaul29c59522022-02-12 16:44:26 -0800454 VLOG(2) << "Input acce " << accel.transpose();
455 VLOG(2) << "Input gyro " << gyro.transpose();
456 VLOG(2) << "Input voltage " << voltage.transpose();
James Kuszmaul5a5a7832022-03-16 23:15:08 -0700457 VLOG(2) << "Input encoder " << Z.topRows<2>().transpose();
James Kuszmaul29c59522022-02-12 16:44:26 -0800458 VLOG(2) << "yaw rate " << yaw_rate;
459
460 CHECK(std::isfinite(last_residual_));
461}
462
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800463const ModelBasedLocalizer::OldPosition ModelBasedLocalizer::GetStateForTime(
464 aos::monotonic_clock::time_point time) {
465 if (old_positions_.empty()) {
466 return OldPosition{};
467 }
468
469 aos::monotonic_clock::duration lowest_time_error =
470 aos::monotonic_clock::duration::max();
471 const OldPosition *best_match = nullptr;
472 for (const OldPosition &sample : old_positions_) {
473 const aos::monotonic_clock::duration time_error =
474 std::chrono::abs(sample.sample_time - time);
475 if (time_error < lowest_time_error) {
476 lowest_time_error = time_error;
477 best_match = &sample;
478 }
479 }
480 return *best_match;
481}
482
483namespace {
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800484
485// Node names of the pis to listen for cameras from.
Milind Upadhyayd67e9cf2022-03-13 13:56:57 -0700486constexpr std::array<std::string_view, ModelBasedLocalizer::kNumPis> kPisToUse{
487 "pi1", "pi2", "pi3", "pi4"};
James Kuszmaulf6b69112022-03-12 21:34:39 -0800488} // namespace
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800489
490const Eigen::Matrix<double, 4, 4> ModelBasedLocalizer::CameraTransform(
491 const OldPosition &state,
492 const frc971::vision::calibration::CameraCalibration *calibration,
493 std::optional<RejectionReason> *rejection_reason) const {
Austin Schuh6bdcc372024-06-27 14:49:11 -0700494 CHECK(rejection_reason != nullptr);
495 CHECK(calibration != nullptr);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800496 // Per the CameraCalibration specification, we can actually determine whether
497 // the camera is the turret camera just from the presence of the
498 // turret_extrinsics member.
499 const bool is_turret = calibration->has_turret_extrinsics();
500 // Ignore readings when the turret is spinning too fast, on the assumption
501 // that the odds of screwing up the time compensation are higher.
502 // Note that the current number here is chosen pretty arbitrarily--1 rad / sec
503 // seems reasonable, but may be unnecessarily low or high.
504 constexpr double kMaxTurretVelocity = 1.0;
505 if (is_turret && std::abs(state.turret_velocity) > kMaxTurretVelocity &&
506 !rejection_reason->has_value()) {
507 *rejection_reason = RejectionReason::TURRET_TOO_FAST;
508 }
509 CHECK(calibration->has_fixed_extrinsics());
510 const Eigen::Matrix<double, 4, 4> fixed_extrinsics =
James Kuszmaule3df1ed2023-02-20 16:21:17 -0800511 control_loops::drivetrain::FlatbufferToTransformationMatrix(
512 *calibration->fixed_extrinsics());
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800513
514 // Calculate the pose of the camera relative to the robot origin.
515 Eigen::Matrix<double, 4, 4> H_robot_camera = fixed_extrinsics;
516 if (is_turret) {
517 H_robot_camera =
518 H_robot_camera *
519 frc971::control_loops::TransformationMatrixForYaw<double>(
520 state.turret_position) *
James Kuszmaule3df1ed2023-02-20 16:21:17 -0800521 control_loops::drivetrain::FlatbufferToTransformationMatrix(
522 *calibration->turret_extrinsics());
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800523 }
524 return H_robot_camera;
525}
526
527const std::optional<Eigen::Vector2d>
528ModelBasedLocalizer::CameraMeasuredRobotPosition(
529 const OldPosition &state, const y2022::vision::TargetEstimate *target,
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800530 std::optional<RejectionReason> *rejection_reason,
531 Eigen::Matrix<double, 4, 4> *H_field_camera_measured) const {
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800532 if (!target->has_camera_calibration()) {
533 *rejection_reason = RejectionReason::NO_CALIBRATION;
534 return std::nullopt;
535 }
536 const Eigen::Matrix<double, 4, 4> H_robot_camera =
537 CameraTransform(state, target->camera_calibration(), rejection_reason);
538 const control_loops::Pose robot_pose(
539 {state.xytheta(0), state.xytheta(1), 0.0}, state.xytheta(2));
540 const Eigen::Matrix<double, 4, 4> H_field_robot =
541 robot_pose.AsTransformationMatrix();
542 // Current estimated pose of the camera in the global frame.
543 // Note that this is all really just an elaborate way of extracting the
544 // current estimated camera yaw, and nothing else.
545 const Eigen::Matrix<double, 4, 4> H_field_camera =
546 H_field_robot * H_robot_camera;
547 // Grab the implied yaw of the camera (the +Z axis is coming out of the front
548 // of the cameras).
549 const Eigen::Vector3d rotated_camera_z =
550 H_field_camera.block<3, 3>(0, 0) * Eigen::Vector3d(0, 0, 1);
551 const double camera_yaw =
552 std::atan2(rotated_camera_z.y(), rotated_camera_z.x());
553 // All right, now we need to use the heading and distance from the
554 // TargetEstimate, plus the yaw embedded in the camera_pose, to determine what
555 // the implied X/Y position of the robot is. To do this, we calculate the
556 // heading/distance from the target to the robot. The distance is easy, since
557 // that's the same as the distance from the robot to the target. The heading
558 // isn't too hard, but is obnoxious to think about, since the heading from the
559 // target to the robot is distinct from the heading from the robot to the
560 // target.
561
562 // Just to walk through examples to confirm that the below calculation is
563 // correct:
564 // * If yaw = 0, and angle_to_target = 0, we are at 180 deg relative to the
565 // target.
566 // * If yaw = 90 deg, and angle_to_target = 0, we are at -90 deg relative to
567 // the target.
568 // * If yaw = 0, and angle_to_target = 90 deg, we are at -90 deg relative to
569 // the target.
570 const double heading_from_target =
571 aos::math::NormalizeAngle(M_PI + camera_yaw + target->angle_to_target());
572 const double distance_from_target = target->distance();
573 // Extract the implied camera position on the field.
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800574 *H_field_camera_measured = H_field_camera;
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800575 // TODO(james): Are we going to need to evict the roll/pitch components of the
576 // camera extrinsics this year as well?
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800577 (*H_field_camera_measured)(0, 3) =
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800578 distance_from_target * std::cos(heading_from_target) + kVisionTargetX;
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800579 (*H_field_camera_measured)(1, 3) =
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800580 distance_from_target * std::sin(heading_from_target) + kVisionTargetY;
581 const Eigen::Matrix<double, 4, 4> H_field_robot_measured =
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800582 *H_field_camera_measured * H_robot_camera.inverse();
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800583 return H_field_robot_measured.block<2, 1>(0, 3);
584}
585
586void ModelBasedLocalizer::HandleImageMatch(
587 aos::monotonic_clock::time_point sample_time,
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800588 const y2022::vision::TargetEstimate *target, int camera_index) {
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800589 std::optional<RejectionReason> rejection_reason;
590
James Kuszmaulaa39d962022-03-06 14:54:28 -0800591 if (target->confidence() < kMinTargetEstimateConfidence) {
592 rejection_reason = RejectionReason::LOW_CONFIDENCE;
593 TallyRejection(rejection_reason.value());
594 return;
595 }
596
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800597 const OldPosition &state = GetStateForTime(sample_time);
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800598 Eigen::Matrix<double, 4, 4> H_field_camera_measured;
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800599 const std::optional<Eigen::Vector2d> measured_robot_position =
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800600 CameraMeasuredRobotPosition(state, target, &rejection_reason,
601 &H_field_camera_measured);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800602 // Technically, rejection_reason should always be set if
603 // measured_robot_position is nullopt, but in the future we may have more
604 // recoverable rejection reasons that we wish to allow to propagate further
605 // into the process.
606 if (!measured_robot_position || rejection_reason.has_value()) {
607 CHECK(rejection_reason.has_value());
608 TallyRejection(rejection_reason.value());
609 return;
610 }
611
612 // Next, go through and do the actual Kalman corrections for the x/y
613 // measurement, for both the accel state and the model-based state.
614 const Eigen::Matrix<double, kNModelStates, kNModelStates> A_continuous_model =
615 AModel(current_state_.model_state);
616
617 Eigen::Matrix<double, kNModelStates, kNModelStates> A_discrete_model;
618 Eigen::Matrix<double, kNModelStates, kNModelStates> Q_discrete_model;
619
620 DiscretizeQAFast(Q_continuous_model_, A_continuous_model, kNominalDt,
621 &Q_discrete_model, &A_discrete_model);
622
623 Eigen::Matrix<double, 2, kNModelStates> H_model;
624 H_model.setZero();
625 Eigen::Matrix<double, 2, kNAccelStates> H_accel;
626 H_accel.setZero();
627 Eigen::Matrix<double, 2, 2> R;
628 R.setZero();
629 H_model(0, kX) = 1.0;
630 H_model(1, kY) = 1.0;
631 H_accel(0, kX) = 1.0;
632 H_accel(1, kY) = 1.0;
James Kuszmaul20014542022-04-06 21:35:44 -0700633 if (aggressive_corrections_) {
634 R.diagonal() << 1e-2, 1e-2;
635 } else {
636 R.diagonal() << 1e-0, 1e-0;
637 }
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800638
639 const Eigen::Matrix<double, kNModelStates, 2> K_model =
640 P_model_ * H_model.transpose() *
641 (H_model * P_model_ * H_model.transpose() + R).inverse();
642 const Eigen::Matrix<double, kNAccelStates, 2> K_accel =
643 P_accel_ * H_accel.transpose() *
644 (H_accel * P_accel_ * H_accel.transpose() + R).inverse();
645 P_model_ = (Eigen::Matrix<double, kNModelStates, kNModelStates>::Identity() -
646 K_model * H_model) *
647 P_model_;
648 P_accel_ = (Eigen::Matrix<double, kNAccelStates, kNAccelStates>::Identity() -
649 K_accel * H_accel) *
650 P_accel_;
651 // And now we have to correct *everything* on all the branches:
652 for (CombinedState &state : branches_) {
653 state.model_state += K_model * (measured_robot_position.value() -
James Kuszmaulf6b69112022-03-12 21:34:39 -0800654 H_model * state.model_state);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800655 state.accel_state += K_accel * (measured_robot_position.value() -
James Kuszmaulf6b69112022-03-12 21:34:39 -0800656 H_accel * state.accel_state);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800657 }
658 current_state_.model_state +=
659 K_model *
660 (measured_robot_position.value() - H_model * current_state_.model_state);
661 current_state_.accel_state +=
662 K_accel *
663 (measured_robot_position.value() - H_accel * current_state_.accel_state);
664
665 statistics_.total_accepted++;
666 statistics_.total_candidates++;
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800667
668 const Eigen::Vector3d camera_z_in_field =
669 H_field_camera_measured.block<3, 3>(0, 0) * Eigen::Vector3d::UnitZ();
670 const double camera_yaw =
671 std::atan2(camera_z_in_field.y(), camera_z_in_field.x());
672
Milind Upadhyayd67e9cf2022-03-13 13:56:57 -0700673 // TODO(milind): actually control this
674 led_outputs_[camera_index] = LedOutput::ON;
675
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800676 TargetEstimateDebugT debug;
677 debug.camera = static_cast<uint8_t>(camera_index);
678 debug.camera_x = H_field_camera_measured(0, 3);
679 debug.camera_y = H_field_camera_measured(1, 3);
680 debug.camera_theta = camera_yaw;
681 debug.implied_robot_x = measured_robot_position.value().x();
682 debug.implied_robot_y = measured_robot_position.value().y();
683 debug.implied_robot_theta = xytheta()(2);
684 debug.implied_turret_goal =
685 aos::math::NormalizeAngle(camera_yaw + target->angle_to_target());
686 debug.accepted = true;
687 debug.image_age_sec = aos::time::DurationInSeconds(t_ - sample_time);
James Kuszmaul2b2f8772022-03-12 15:25:35 -0800688 CHECK_LT(image_debugs_.size(), kDebugBufferSize);
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800689 image_debugs_.push_back(debug);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800690}
691
692void ModelBasedLocalizer::HandleTurret(
693 aos::monotonic_clock::time_point sample_time, double turret_position,
694 double turret_velocity) {
695 last_turret_update_ = sample_time;
696 latest_turret_position_ = turret_position;
697 latest_turret_velocity_ = turret_velocity;
698}
699
James Kuszmaul29c59522022-02-12 16:44:26 -0800700void ModelBasedLocalizer::HandleReset(aos::monotonic_clock::time_point now,
701 const Eigen::Vector3d &xytheta) {
702 branches_.Reset();
James Kuszmaulf6b69112022-03-12 21:34:39 -0800703 t_ = now;
James Kuszmaul29c59522022-02-12 16:44:26 -0800704 using_model_ = true;
705 current_state_.model_state << xytheta(0), xytheta(1), xytheta(2),
706 current_state_.model_state(kLeftEncoder), 0.0, 0.0,
707 current_state_.model_state(kRightEncoder), 0.0, 0.0;
708 current_state_.accel_state =
709 AccelStateForModelState(current_state_.model_state);
710 last_residual_ = 0.0;
711 filtered_residual_ = 0.0;
712 filtered_residual_accel_.setZero();
713 abs_accel_.setZero();
714}
715
716flatbuffers::Offset<AccelBasedState> ModelBasedLocalizer::BuildAccelState(
717 flatbuffers::FlatBufferBuilder *fbb, const AccelState &state) {
718 AccelBasedState::Builder accel_state_builder(*fbb);
719 accel_state_builder.add_x(state(kX));
720 accel_state_builder.add_y(state(kY));
721 accel_state_builder.add_theta(state(kTheta));
722 accel_state_builder.add_velocity_x(state(kVelocityX));
723 accel_state_builder.add_velocity_y(state(kVelocityY));
724 return accel_state_builder.Finish();
725}
726
727flatbuffers::Offset<ModelBasedState> ModelBasedLocalizer::BuildModelState(
728 flatbuffers::FlatBufferBuilder *fbb, const ModelState &state) {
729 ModelBasedState::Builder model_state_builder(*fbb);
730 model_state_builder.add_x(state(kX));
731 model_state_builder.add_y(state(kY));
732 model_state_builder.add_theta(state(kTheta));
733 model_state_builder.add_left_encoder(state(kLeftEncoder));
734 model_state_builder.add_left_velocity(state(kLeftVelocity));
735 model_state_builder.add_left_voltage_error(state(kLeftVoltageError));
736 model_state_builder.add_right_encoder(state(kRightEncoder));
737 model_state_builder.add_right_velocity(state(kRightVelocity));
738 model_state_builder.add_right_voltage_error(state(kRightVoltageError));
739 return model_state_builder.Finish();
740}
741
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800742flatbuffers::Offset<CumulativeStatistics>
743ModelBasedLocalizer::PopulateStatistics(flatbuffers::FlatBufferBuilder *fbb) {
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800744 const auto rejections_offset = fbb->CreateVector(
745 statistics_.rejection_counts.data(), statistics_.rejection_counts.size());
746
747 CumulativeStatistics::Builder stats_builder(*fbb);
748 stats_builder.add_total_accepted(statistics_.total_accepted);
749 stats_builder.add_total_candidates(statistics_.total_candidates);
750 stats_builder.add_rejection_reason_count(rejections_offset);
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800751 return stats_builder.Finish();
752}
753
754flatbuffers::Offset<ModelBasedStatus> ModelBasedLocalizer::PopulateStatus(
755 flatbuffers::FlatBufferBuilder *fbb) {
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800756 const flatbuffers::Offset<CumulativeStatistics> stats_offset =
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800757 PopulateStatistics(fbb);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800758
James Kuszmaul29c59522022-02-12 16:44:26 -0800759 const flatbuffers::Offset<control_loops::drivetrain::DownEstimatorState>
760 down_estimator_offset = down_estimator_.PopulateStatus(fbb, t_);
761
762 const CombinedState &state = current_state_;
763
764 const flatbuffers::Offset<ModelBasedState> model_state_offset =
James Kuszmaulf6b69112022-03-12 21:34:39 -0800765 BuildModelState(fbb, state.model_state);
James Kuszmaul29c59522022-02-12 16:44:26 -0800766
767 const flatbuffers::Offset<AccelBasedState> accel_state_offset =
768 BuildAccelState(fbb, state.accel_state);
769
770 const flatbuffers::Offset<AccelBasedState> oldest_accel_state_offset =
771 branches_.empty() ? flatbuffers::Offset<AccelBasedState>()
772 : BuildAccelState(fbb, branches_[0].accel_state);
773
774 const flatbuffers::Offset<ModelBasedState> oldest_model_state_offset =
775 branches_.empty() ? flatbuffers::Offset<ModelBasedState>()
776 : BuildModelState(fbb, branches_[0].model_state);
777
778 ModelBasedStatus::Builder builder(*fbb);
779 builder.add_accel_state(accel_state_offset);
780 builder.add_oldest_accel_state(oldest_accel_state_offset);
781 builder.add_oldest_model_state(oldest_model_state_offset);
782 builder.add_model_state(model_state_offset);
783 builder.add_using_model(using_model_);
784 builder.add_residual(last_residual_);
785 builder.add_filtered_residual(filtered_residual_);
786 builder.add_velocity_residual(velocity_residual_);
787 builder.add_accel_residual(accel_residual_);
788 builder.add_theta_rate_residual(theta_rate_residual_);
789 builder.add_down_estimator(down_estimator_offset);
790 builder.add_x(xytheta()(0));
791 builder.add_y(xytheta()(1));
792 builder.add_theta(xytheta()(2));
793 builder.add_implied_accel_x(abs_accel_(0));
794 builder.add_implied_accel_y(abs_accel_(1));
795 builder.add_implied_accel_z(abs_accel_(2));
796 builder.add_clock_resets(clock_resets_);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800797 builder.add_statistics(stats_offset);
James Kuszmaul29c59522022-02-12 16:44:26 -0800798 return builder.Finish();
799}
800
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800801flatbuffers::Offset<LocalizerVisualization>
802ModelBasedLocalizer::PopulateVisualization(
803 flatbuffers::FlatBufferBuilder *fbb) {
804 const flatbuffers::Offset<CumulativeStatistics> stats_offset =
805 PopulateStatistics(fbb);
806
807 aos::SizedArray<flatbuffers::Offset<TargetEstimateDebug>, kDebugBufferSize>
808 debug_offsets;
809
James Kuszmaulf6b69112022-03-12 21:34:39 -0800810 for (const TargetEstimateDebugT &debug : image_debugs_) {
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800811 debug_offsets.push_back(PackTargetEstimateDebug(debug, fbb));
812 }
813
814 image_debugs_.clear();
815
816 const flatbuffers::Offset<
817 flatbuffers::Vector<flatbuffers::Offset<TargetEstimateDebug>>>
818 debug_offset =
819 fbb->CreateVector(debug_offsets.data(), debug_offsets.size());
820
821 LocalizerVisualization::Builder builder(*fbb);
822 builder.add_statistics(stats_offset);
823 builder.add_targets(debug_offset);
824 return builder.Finish();
825}
826
827void ModelBasedLocalizer::TallyRejection(const RejectionReason reason) {
828 statistics_.total_candidates++;
829 statistics_.rejection_counts[static_cast<size_t>(reason)]++;
830 TargetEstimateDebugT debug;
831 debug.accepted = false;
832 debug.rejection_reason = reason;
James Kuszmaul2b2f8772022-03-12 15:25:35 -0800833 CHECK_LT(image_debugs_.size(), kDebugBufferSize);
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800834 image_debugs_.push_back(debug);
835}
836
837flatbuffers::Offset<TargetEstimateDebug>
838ModelBasedLocalizer::PackTargetEstimateDebug(
839 const TargetEstimateDebugT &debug, flatbuffers::FlatBufferBuilder *fbb) {
840 if (!debug.accepted) {
841 TargetEstimateDebug::Builder builder(*fbb);
842 builder.add_accepted(debug.accepted);
843 builder.add_rejection_reason(debug.rejection_reason);
844 return builder.Finish();
845 } else {
846 flatbuffers::Offset<TargetEstimateDebug> offset =
847 TargetEstimateDebug::Pack(*fbb, &debug);
848 flatbuffers::GetMutableTemporaryPointer(*fbb, offset)
849 ->clear_rejection_reason();
850 return offset;
851 }
852}
853
James Kuszmaul29c59522022-02-12 16:44:26 -0800854EventLoopLocalizer::EventLoopLocalizer(
855 aos::EventLoop *event_loop,
856 const control_loops::drivetrain::DrivetrainConfig<double> &dt_config)
857 : event_loop_(event_loop),
858 model_based_(dt_config),
859 status_sender_(event_loop_->MakeSender<LocalizerStatus>("/localizer")),
860 output_sender_(event_loop_->MakeSender<LocalizerOutput>("/localizer")),
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800861 visualization_sender_(
862 event_loop_->MakeSender<LocalizerVisualization>("/localizer")),
James Kuszmaulf6b69112022-03-12 21:34:39 -0800863 superstructure_fetcher_(
864 event_loop_
865 ->MakeFetcher<y2022::control_loops::superstructure::Status>(
866 "/superstructure")),
James Kuszmaul9f2f53c2023-02-19 14:08:18 -0800867 imu_watcher_(event_loop, dt_config,
868 y2022::constants::Values::DrivetrainEncoderToMeters(1),
869 [this](aos::monotonic_clock::time_point sample_time_pico,
870 aos::monotonic_clock::time_point sample_time_pi,
871 std::optional<Eigen::Vector2d> encoders,
872 Eigen::Vector3d gyro, Eigen::Vector3d accel) {
873 HandleImu(sample_time_pico, sample_time_pi, encoders, gyro,
874 accel);
James Kuszmaul9a1733a2023-02-19 16:51:47 -0800875 }),
876 utils_(event_loop) {
James Kuszmaula391dde2022-03-17 00:03:30 -0700877 event_loop->SetRuntimeRealtimePriority(10);
James Kuszmaul29c59522022-02-12 16:44:26 -0800878 event_loop_->MakeWatcher(
879 "/drivetrain",
880 [this](
881 const frc971::control_loops::drivetrain::LocalizerControl &control) {
882 const double theta = control.keep_current_theta()
883 ? model_based_.xytheta()(2)
884 : control.theta();
885 model_based_.HandleReset(event_loop_->monotonic_now(),
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800886 {control.x(), control.y(), theta});
James Kuszmaul29c59522022-02-12 16:44:26 -0800887 });
James Kuszmaul2b2f8772022-03-12 15:25:35 -0800888 aos::TimerHandler *superstructure_timer = event_loop_->AddTimer([this]() {
889 if (superstructure_fetcher_.Fetch()) {
890 const y2022::control_loops::superstructure::Status &status =
891 *superstructure_fetcher_.get();
892 if (!status.has_turret()) {
893 return;
894 }
895 CHECK(status.has_turret());
896 model_based_.HandleTurret(
897 superstructure_fetcher_.context().monotonic_event_time,
898 status.turret()->position(), status.turret()->velocity());
899 }
900 });
901 event_loop_->OnRun([this, superstructure_timer]() {
Philipp Schradera6712522023-07-05 20:25:11 -0700902 superstructure_timer->Schedule(event_loop_->monotonic_now(),
903 std::chrono::milliseconds(20));
James Kuszmaul2b2f8772022-03-12 15:25:35 -0800904 });
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800905
James Kuszmaulf6b69112022-03-12 21:34:39 -0800906 for (size_t camera_index = 0; camera_index < kPisToUse.size();
907 ++camera_index) {
James Kuszmaul2b2f8772022-03-12 15:25:35 -0800908 CHECK_LT(camera_index, target_estimate_fetchers_.size());
909 target_estimate_fetchers_[camera_index] =
910 event_loop_->MakeFetcher<y2022::vision::TargetEstimate>(
911 absl::StrCat("/", kPisToUse[camera_index], "/camera"));
912 }
James Kuszmaulf6b69112022-03-12 21:34:39 -0800913 aos::TimerHandler *estimate_timer = event_loop_->AddTimer([this]() {
Philipp Schrader790cb542023-07-05 21:06:52 -0700914 const bool maybe_in_auto = utils_.MaybeInAutonomous();
915 model_based_.set_use_aggressive_image_corrections(!maybe_in_auto);
916 for (size_t camera_index = 0; camera_index < kPisToUse.size();
917 ++camera_index) {
918 if (model_based_.NumQueuedImageDebugs() ==
919 ModelBasedLocalizer::kDebugBufferSize ||
920 (last_visualization_send_ + kMinVisualizationPeriod <
921 event_loop_->monotonic_now())) {
922 auto builder = visualization_sender_.MakeBuilder();
923 visualization_sender_.CheckOk(
924 builder.Send(model_based_.PopulateVisualization(builder.fbb())));
925 }
926 if (target_estimate_fetchers_[camera_index].Fetch()) {
927 const std::optional<aos::monotonic_clock::duration> monotonic_offset =
928 utils_.ClockOffset(kPisToUse[camera_index]);
929 if (!monotonic_offset.has_value()) {
930 model_based_.TallyRejection(
931 RejectionReason::MESSAGE_BRIDGE_DISCONNECTED);
932 continue;
James Kuszmaul2b2f8772022-03-12 15:25:35 -0800933 }
Philipp Schrader790cb542023-07-05 21:06:52 -0700934 // TODO(james): Get timestamp from message contents.
935 aos::monotonic_clock::time_point capture_time(
936 target_estimate_fetchers_[camera_index]
937 .context()
938 .monotonic_remote_time -
939 monotonic_offset.value());
940 if (capture_time > target_estimate_fetchers_[camera_index]
941 .context()
942 .monotonic_event_time) {
943 model_based_.TallyRejection(RejectionReason::IMAGE_FROM_FUTURE);
944 continue;
James Kuszmaulf6b69112022-03-12 21:34:39 -0800945 }
Philipp Schrader790cb542023-07-05 21:06:52 -0700946 capture_time -= imu_watcher_.pico_offset_error();
947 model_based_.HandleImageMatch(
948 capture_time, target_estimate_fetchers_[camera_index].get(),
949 camera_index);
950 }
James Kuszmaulf6b69112022-03-12 21:34:39 -0800951 }
952 });
James Kuszmaul2b2f8772022-03-12 15:25:35 -0800953 event_loop_->OnRun([this, estimate_timer]() {
Philipp Schradera6712522023-07-05 20:25:11 -0700954 estimate_timer->Schedule(event_loop_->monotonic_now(),
955 std::chrono::milliseconds(100));
James Kuszmaul2b2f8772022-03-12 15:25:35 -0800956 });
James Kuszmaul9f2f53c2023-02-19 14:08:18 -0800957}
James Kuszmaul5f27d8b2022-03-17 09:08:26 -0700958
James Kuszmaul9f2f53c2023-02-19 14:08:18 -0800959void EventLoopLocalizer::HandleImu(
960 aos::monotonic_clock::time_point sample_time_pico,
961 aos::monotonic_clock::time_point sample_time_pi,
962 std::optional<Eigen::Vector2d> encoders, Eigen::Vector3d gyro,
963 Eigen::Vector3d accel) {
James Kuszmaul9a1733a2023-02-19 16:51:47 -0800964 model_based_.HandleImu(
965 sample_time_pico, gyro, accel, encoders,
966 utils_.VoltageOrZero(event_loop_->context().monotonic_event_time));
967
James Kuszmaul9f2f53c2023-02-19 14:08:18 -0800968 {
969 auto builder = status_sender_.MakeBuilder();
970 const flatbuffers::Offset<ModelBasedStatus> model_based_status =
971 model_based_.PopulateStatus(builder.fbb());
972 const flatbuffers::Offset<control_loops::drivetrain::ImuZeroerState>
973 zeroer_status = imu_watcher_.zeroer().PopulateStatus(builder.fbb());
974 const flatbuffers::Offset<ImuFailures> imu_failures =
975 imu_watcher_.PopulateImuFailures(builder.fbb());
976 LocalizerStatus::Builder status_builder =
977 builder.MakeBuilder<LocalizerStatus>();
978 status_builder.add_model_based(model_based_status);
979 status_builder.add_zeroed(imu_watcher_.zeroer().Zeroed());
980 status_builder.add_faulted_zero(imu_watcher_.zeroer().Faulted());
981 status_builder.add_zeroing(zeroer_status);
982 status_builder.add_imu_failures(imu_failures);
983 if (encoders.has_value()) {
984 status_builder.add_left_encoder(encoders.value()(0));
985 status_builder.add_right_encoder(encoders.value()(1));
986 }
987 if (imu_watcher_.pico_offset().has_value()) {
988 status_builder.add_pico_offset_ns(
989 imu_watcher_.pico_offset().value().count());
990 status_builder.add_pico_offset_error_ns(
991 imu_watcher_.pico_offset_error().count());
992 }
993 builder.CheckOk(builder.Send(status_builder.Finish()));
994 }
995 if (last_output_send_ + std::chrono::milliseconds(5) <
996 event_loop_->context().monotonic_event_time) {
997 auto builder = output_sender_.MakeBuilder();
Milind Upadhyayd67e9cf2022-03-13 13:56:57 -0700998
James Kuszmaul9f2f53c2023-02-19 14:08:18 -0800999 const auto led_outputs_offset = builder.fbb()->CreateVector(
1000 model_based_.led_outputs().data(), model_based_.led_outputs().size());
Milind Upadhyayd67e9cf2022-03-13 13:56:57 -07001001
James Kuszmaul9f2f53c2023-02-19 14:08:18 -08001002 LocalizerOutput::Builder output_builder =
1003 builder.MakeBuilder<LocalizerOutput>();
1004 output_builder.add_monotonic_timestamp_ns(
1005 std::chrono::duration_cast<std::chrono::nanoseconds>(
1006 sample_time_pi.time_since_epoch())
1007 .count());
1008 output_builder.add_x(model_based_.xytheta()(0));
1009 output_builder.add_y(model_based_.xytheta()(1));
1010 output_builder.add_theta(model_based_.xytheta()(2));
1011 output_builder.add_zeroed(imu_watcher_.zeroer().Zeroed());
1012 output_builder.add_image_accepted_count(model_based_.total_accepted());
1013 const Eigen::Quaterniond &orientation = model_based_.orientation();
1014 Quaternion quaternion;
1015 quaternion.mutate_x(orientation.x());
1016 quaternion.mutate_y(orientation.y());
1017 quaternion.mutate_z(orientation.z());
1018 quaternion.mutate_w(orientation.w());
1019 output_builder.add_orientation(&quaternion);
1020 output_builder.add_led_outputs(led_outputs_offset);
1021 builder.CheckOk(builder.Send(output_builder.Finish()));
1022 last_output_send_ = event_loop_->monotonic_now();
1023 }
James Kuszmaul29c59522022-02-12 16:44:26 -08001024}
1025
James Kuszmaul29c59522022-02-12 16:44:26 -08001026} // namespace frc971::controls