blob: 783d36875b7217126cb9c091ffad4211030008a3 [file] [log] [blame]
James Kuszmaul51fa1ae2022-02-26 00:49:57 -08001#include "y2022/localizer/localizer.h"
James Kuszmaul29c59522022-02-12 16:44:26 -08002
James Kuszmaulf6b69112022-03-12 21:34:39 -08003#include "aos/json_to_flatbuffer.h"
James Kuszmaul29c59522022-02-12 16:44:26 -08004#include "frc971/control_loops/c2d.h"
5#include "frc971/wpilib/imu_batch_generated.h"
James Kuszmaul5ed29dd2022-02-13 18:32:06 -08006#include "y2022/constants.h"
James Kuszmaul29c59522022-02-12 16:44:26 -08007
James Kuszmaulce491e42022-03-12 21:02:10 -08008DEFINE_bool(ignore_accelerometer, false,
9 "If set, ignores the accelerometer readings.");
10
James Kuszmaul29c59522022-02-12 16:44:26 -080011namespace frc971::controls {
12
13namespace {
14constexpr double kG = 9.80665;
15constexpr std::chrono::microseconds kNominalDt(500);
16
James Kuszmaul8c4f6592022-02-26 15:49:30 -080017// Field position of the target (the 2022 target is conveniently in the middle
18// of the field....).
19constexpr double kVisionTargetX = 0.0;
20constexpr double kVisionTargetY = 0.0;
21
James Kuszmaulaa39d962022-03-06 14:54:28 -080022// Minimum confidence to require to use a target match.
James Kuszmaul1b918d82022-03-12 18:27:41 -080023constexpr double kMinTargetEstimateConfidence = 0.75;
James Kuszmaulaa39d962022-03-06 14:54:28 -080024
James Kuszmaul29c59522022-02-12 16:44:26 -080025template <int N>
26Eigen::Matrix<double, N, 1> MakeState(std::vector<double> values) {
27 CHECK_EQ(static_cast<size_t>(N), values.size());
28 Eigen::Matrix<double, N, 1> vector;
29 for (int ii = 0; ii < N; ++ii) {
30 vector(ii, 0) = values[ii];
31 }
32 return vector;
33}
James Kuszmaul29c59522022-02-12 16:44:26 -080034} // namespace
35
36ModelBasedLocalizer::ModelBasedLocalizer(
37 const control_loops::drivetrain::DrivetrainConfig<double> &dt_config)
38 : dt_config_(dt_config),
39 velocity_drivetrain_coefficients_(
40 dt_config.make_hybrid_drivetrain_velocity_loop()
41 .plant()
42 .coefficients()),
43 down_estimator_(dt_config) {
James Kuszmaul8c4f6592022-02-26 15:49:30 -080044 statistics_.rejection_counts.fill(0);
James Kuszmaulf6b69112022-03-12 21:34:39 -080045 CHECK_EQ(branches_.capacity(),
46 static_cast<size_t>(std::chrono::seconds(1) / kNominalDt /
47 kBranchPeriod));
James Kuszmaul29c59522022-02-12 16:44:26 -080048 if (dt_config_.is_simulated) {
49 down_estimator_.assume_perfect_gravity();
50 }
51 A_continuous_accel_.setZero();
52 A_continuous_model_.setZero();
53 B_continuous_accel_.setZero();
54 B_continuous_model_.setZero();
55
56 A_continuous_accel_(kX, kVelocityX) = 1.0;
57 A_continuous_accel_(kY, kVelocityY) = 1.0;
58
59 const double diameter = 2.0 * dt_config_.robot_radius;
60
61 A_continuous_model_(kTheta, kLeftVelocity) = -1.0 / diameter;
62 A_continuous_model_(kTheta, kRightVelocity) = 1.0 / diameter;
63 A_continuous_model_(kLeftEncoder, kLeftVelocity) = 1.0;
64 A_continuous_model_(kRightEncoder, kRightVelocity) = 1.0;
65 const auto &vel_coefs = velocity_drivetrain_coefficients_;
66 A_continuous_model_(kLeftVelocity, kLeftVelocity) =
67 vel_coefs.A_continuous(0, 0);
68 A_continuous_model_(kLeftVelocity, kRightVelocity) =
69 vel_coefs.A_continuous(0, 1);
70 A_continuous_model_(kRightVelocity, kLeftVelocity) =
71 vel_coefs.A_continuous(1, 0);
72 A_continuous_model_(kRightVelocity, kRightVelocity) =
73 vel_coefs.A_continuous(1, 1);
74
75 A_continuous_model_(kLeftVelocity, kLeftVoltageError) =
76 1 * vel_coefs.B_continuous(0, 0);
77 A_continuous_model_(kLeftVelocity, kRightVoltageError) =
78 1 * vel_coefs.B_continuous(0, 1);
79 A_continuous_model_(kRightVelocity, kLeftVoltageError) =
80 1 * vel_coefs.B_continuous(1, 0);
81 A_continuous_model_(kRightVelocity, kRightVoltageError) =
82 1 * vel_coefs.B_continuous(1, 1);
83
84 B_continuous_model_.block<1, 2>(kLeftVelocity, kLeftVoltage) =
85 vel_coefs.B_continuous.row(0);
86 B_continuous_model_.block<1, 2>(kRightVelocity, kLeftVoltage) =
87 vel_coefs.B_continuous.row(1);
88
89 B_continuous_accel_(kVelocityX, kAccelX) = 1.0;
90 B_continuous_accel_(kVelocityY, kAccelY) = 1.0;
91 B_continuous_accel_(kTheta, kThetaRate) = 1.0;
92
93 Q_continuous_model_.setZero();
James Kuszmaul8c4f6592022-02-26 15:49:30 -080094 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 -080095 1e-0, 1e-0;
96
James Kuszmaul8c4f6592022-02-26 15:49:30 -080097 Q_continuous_accel_.setZero();
98 Q_continuous_accel_.diagonal() << 1e-2, 1e-2, 1e-20, 1e-4, 1e-4;
99
James Kuszmaul29c59522022-02-12 16:44:26 -0800100 P_model_ = Q_continuous_model_ * aos::time::DurationInSeconds(kNominalDt);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800101
102 // We can precalculate the discretizations of the accel model because it is
103 // actually LTI.
104
105 DiscretizeQAFast(Q_continuous_accel_, A_continuous_accel_, kNominalDt,
106 &Q_discrete_accel_, &A_discrete_accel_);
107 P_accel_ = Q_discrete_accel_;
Milind Upadhyayd67e9cf2022-03-13 13:56:57 -0700108
109 led_outputs_.fill(LedOutput::ON);
James Kuszmaul29c59522022-02-12 16:44:26 -0800110}
111
112Eigen::Matrix<double, ModelBasedLocalizer::kNModelStates,
113 ModelBasedLocalizer::kNModelStates>
114ModelBasedLocalizer::AModel(
115 const ModelBasedLocalizer::ModelState &state) const {
116 Eigen::Matrix<double, kNModelStates, kNModelStates> A = A_continuous_model_;
117 const double theta = state(kTheta);
118 const double stheta = std::sin(theta);
119 const double ctheta = std::cos(theta);
120 const double velocity = (state(kLeftVelocity) + state(kRightVelocity)) / 2.0;
121 A(kX, kTheta) = -stheta * velocity;
122 A(kX, kLeftVelocity) = ctheta / 2.0;
123 A(kX, kRightVelocity) = ctheta / 2.0;
124 A(kY, kTheta) = ctheta * velocity;
125 A(kY, kLeftVelocity) = stheta / 2.0;
126 A(kY, kRightVelocity) = stheta / 2.0;
127 return A;
128}
129
130Eigen::Matrix<double, ModelBasedLocalizer::kNAccelStates,
131 ModelBasedLocalizer::kNAccelStates>
132ModelBasedLocalizer::AAccel() const {
133 return A_continuous_accel_;
134}
135
136ModelBasedLocalizer::ModelState ModelBasedLocalizer::DiffModel(
137 const ModelBasedLocalizer::ModelState &state,
138 const ModelBasedLocalizer::ModelInput &U) const {
139 ModelState x_dot = AModel(state) * state + B_continuous_model_ * U;
140 const double theta = state(kTheta);
141 const double stheta = std::sin(theta);
142 const double ctheta = std::cos(theta);
143 const double velocity = (state(kLeftVelocity) + state(kRightVelocity)) / 2.0;
144 x_dot(kX) = ctheta * velocity;
145 x_dot(kY) = stheta * velocity;
146 return x_dot;
147}
148
149ModelBasedLocalizer::AccelState ModelBasedLocalizer::DiffAccel(
150 const ModelBasedLocalizer::AccelState &state,
151 const ModelBasedLocalizer::AccelInput &U) const {
152 return AAccel() * state + B_continuous_accel_ * U;
153}
154
155ModelBasedLocalizer::ModelState ModelBasedLocalizer::UpdateModel(
156 const ModelBasedLocalizer::ModelState &model,
157 const ModelBasedLocalizer::ModelInput &input,
158 const aos::monotonic_clock::duration dt) const {
159 return control_loops::RungeKutta(
160 std::bind(&ModelBasedLocalizer::DiffModel, this, std::placeholders::_1,
161 input),
162 model, aos::time::DurationInSeconds(dt));
163}
164
165ModelBasedLocalizer::AccelState ModelBasedLocalizer::UpdateAccel(
166 const ModelBasedLocalizer::AccelState &accel,
167 const ModelBasedLocalizer::AccelInput &input,
168 const aos::monotonic_clock::duration dt) const {
169 return control_loops::RungeKutta(
170 std::bind(&ModelBasedLocalizer::DiffAccel, this, std::placeholders::_1,
171 input),
172 accel, aos::time::DurationInSeconds(dt));
173}
174
175ModelBasedLocalizer::AccelState ModelBasedLocalizer::AccelStateForModelState(
176 const ModelBasedLocalizer::ModelState &state) const {
177 const double robot_speed =
178 (state(kLeftVelocity) + state(kRightVelocity)) / 2.0;
James Kuszmaulf6b69112022-03-12 21:34:39 -0800179 const double lat_speed = (AModel(state) * state)(kTheta)*long_offset_;
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800180 const double velocity_x = std::cos(state(kTheta)) * robot_speed -
181 std::sin(state(kTheta)) * lat_speed;
182 const double velocity_y = std::sin(state(kTheta)) * robot_speed +
183 std::cos(state(kTheta)) * lat_speed;
James Kuszmaul29c59522022-02-12 16:44:26 -0800184 return (AccelState() << state(0), state(1), state(2), velocity_x, velocity_y)
185 .finished();
186}
187
188ModelBasedLocalizer::ModelState ModelBasedLocalizer::ModelStateForAccelState(
189 const ModelBasedLocalizer::AccelState &state,
190 const Eigen::Vector2d &encoders, const double yaw_rate) const {
191 const double robot_speed = state(kVelocityX) * std::cos(state(kTheta)) +
192 state(kVelocityY) * std::sin(state(kTheta));
193 const double radius = dt_config_.robot_radius;
194 const double left_velocity = robot_speed - yaw_rate * radius;
195 const double right_velocity = robot_speed + yaw_rate * radius;
196 return (ModelState() << state(0), state(1), state(2), encoders(0),
197 left_velocity, 0.0, encoders(1), right_velocity, 0.0)
198 .finished();
199}
200
201double ModelBasedLocalizer::ModelDivergence(
202 const ModelBasedLocalizer::CombinedState &state,
203 const ModelBasedLocalizer::AccelInput &accel_inputs,
204 const Eigen::Vector2d &filtered_accel,
205 const ModelBasedLocalizer::ModelInput &model_inputs) {
206 // Convert the model state into the acceleration-based state-space and check
207 // the distance between the two (should really be a weighted norm, but all the
208 // numbers are on ~the same scale).
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800209 // TODO(james): Maybe weight lateral velocity divergence different than
210 // longitudinal? Seems like we tend to get false-positives currently when in
211 // sharp turns.
212 // TODO(james): For off-center gyros, maybe reduce noise when turning?
James Kuszmaul29c59522022-02-12 16:44:26 -0800213 VLOG(2) << "divergence: "
214 << (state.accel_state - AccelStateForModelState(state.model_state))
215 .transpose();
216 const AccelState diff_accel = DiffAccel(state.accel_state, accel_inputs);
217 const ModelState diff_model = DiffModel(state.model_state, model_inputs);
218 const double model_lng_velocity =
219 (state.model_state(kLeftVelocity) + state.model_state(kRightVelocity)) /
220 2.0;
221 const double model_lng_accel =
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800222 (diff_model(kLeftVelocity) + diff_model(kRightVelocity)) / 2.0 -
223 diff_model(kTheta) * diff_model(kTheta) * long_offset_;
224 const double model_lat_accel = diff_model(kTheta) * model_lng_velocity;
225 const Eigen::Vector2d robot_frame_accel(model_lng_accel, model_lat_accel);
James Kuszmaul29c59522022-02-12 16:44:26 -0800226 const Eigen::Vector2d model_accel =
227 Eigen::AngleAxisd(state.model_state(kTheta), Eigen::Vector3d::UnitZ())
228 .toRotationMatrix()
229 .block<2, 2>(0, 0) *
230 robot_frame_accel;
231 const double accel_diff = (model_accel - filtered_accel).norm();
232 const double theta_rate_diff =
233 std::abs(diff_accel(kTheta) - diff_model(kTheta));
234
235 const Eigen::Vector2d accel_vel = state.accel_state.bottomRows<2>();
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800236 Eigen::Vector2d model_vel =
James Kuszmaul29c59522022-02-12 16:44:26 -0800237 AccelStateForModelState(state.model_state).bottomRows<2>();
238 velocity_residual_ = (accel_vel - model_vel).norm() /
239 (1.0 + accel_vel.norm() + model_vel.norm());
240 theta_rate_residual_ = theta_rate_diff;
241 accel_residual_ = accel_diff / 4.0;
242 return velocity_residual_ + theta_rate_residual_ + accel_residual_;
243}
244
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800245void ModelBasedLocalizer::UpdateState(
246 CombinedState *state,
247 const Eigen::Matrix<double, kNModelStates, kNModelOutputs> &K,
248 const Eigen::Matrix<double, kNModelOutputs, 1> &Z,
249 const Eigen::Matrix<double, kNModelOutputs, kNModelStates> &H,
250 const AccelInput &accel_input, const ModelInput &model_input,
251 aos::monotonic_clock::duration dt) {
252 state->accel_state = UpdateAccel(state->accel_state, accel_input, dt);
253 if (down_estimator_.consecutive_still() > 500.0) {
254 state->accel_state(kVelocityX) *= 0.9;
255 state->accel_state(kVelocityY) *= 0.9;
256 }
257 state->model_state = UpdateModel(state->model_state, model_input, dt);
258 state->model_state += K * (Z - H * state->model_state);
259}
260
James Kuszmaul5a5a7832022-03-16 23:15:08 -0700261void ModelBasedLocalizer::HandleImu(
262 aos::monotonic_clock::time_point t, const Eigen::Vector3d &gyro,
263 const Eigen::Vector3d &accel, const std::optional<Eigen::Vector2d> encoders,
264 const Eigen::Vector2d voltage) {
James Kuszmaul29c59522022-02-12 16:44:26 -0800265 VLOG(2) << t;
266 if (t_ == aos::monotonic_clock::min_time) {
267 t_ = t;
268 }
James Kuszmaul5f27d8b2022-03-17 09:08:26 -0700269 if (t_ + 10 * kNominalDt < t) {
James Kuszmaul29c59522022-02-12 16:44:26 -0800270 t_ = t;
271 ++clock_resets_;
272 }
273 const aos::monotonic_clock::duration dt = t - t_;
274 t_ = t;
275 down_estimator_.Predict(gyro, accel, dt);
276 // TODO(james): Should we prefer this or use the down-estimator corrected
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800277 // version? Using the down estimator is more principled, but does create more
278 // opportunities for subtle biases.
James Kuszmaul29c59522022-02-12 16:44:26 -0800279 const double yaw_rate = (dt_config_.imu_transform * gyro)(2);
280 const double diameter = 2.0 * dt_config_.robot_radius;
281
282 const Eigen::AngleAxis<double> orientation(
283 Eigen::AngleAxis<double>(xytheta()(kTheta), Eigen::Vector3d::UnitZ()) *
284 down_estimator_.X_hat());
James Kuszmaul10d3fd42022-02-25 21:57:36 -0800285 last_orientation_ = orientation;
James Kuszmaul29c59522022-02-12 16:44:26 -0800286
287 const Eigen::Vector3d absolute_accel =
288 orientation * dt_config_.imu_transform * kG * accel;
289 abs_accel_ = absolute_accel;
James Kuszmaul29c59522022-02-12 16:44:26 -0800290
291 VLOG(2) << "abs accel " << absolute_accel.transpose();
James Kuszmaul29c59522022-02-12 16:44:26 -0800292 VLOG(2) << "dt " << aos::time::DurationInSeconds(dt);
293
294 // Update all the branched states.
295 const AccelInput accel_input(absolute_accel.x(), absolute_accel.y(),
296 yaw_rate);
297 const ModelInput model_input(voltage);
298
299 const Eigen::Matrix<double, kNModelStates, kNModelStates> A_continuous =
300 AModel(current_state_.model_state);
301
302 Eigen::Matrix<double, kNModelStates, kNModelStates> A_discrete;
303 Eigen::Matrix<double, kNModelStates, kNModelStates> Q_discrete;
304
305 DiscretizeQAFast(Q_continuous_model_, A_continuous, dt, &Q_discrete,
306 &A_discrete);
307
308 P_model_ = A_discrete * P_model_ * A_discrete.transpose() + Q_discrete;
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800309 P_accel_ = A_discrete_accel_ * P_accel_ * A_discrete_accel_.transpose() +
310 Q_discrete_accel_;
James Kuszmaul29c59522022-02-12 16:44:26 -0800311
312 Eigen::Matrix<double, kNModelOutputs, kNModelStates> H;
313 Eigen::Matrix<double, kNModelOutputs, kNModelOutputs> R;
314 {
315 H.setZero();
316 R.setZero();
317 H(0, kLeftEncoder) = 1.0;
318 H(1, kRightEncoder) = 1.0;
319 H(2, kRightVelocity) = 1.0 / diameter;
320 H(2, kLeftVelocity) = -1.0 / diameter;
321
322 R.diagonal() << 1e-9, 1e-9, 1e-13;
323 }
324
James Kuszmaul5a5a7832022-03-16 23:15:08 -0700325 const Eigen::Matrix<double, kNModelOutputs, 1> Z =
326 encoders.has_value()
327 ? Eigen::Vector3d(encoders.value()(0), encoders.value()(1), yaw_rate)
328 : Eigen::Vector3d(current_state_.model_state(kLeftEncoder),
329 current_state_.model_state(kRightEncoder),
330 yaw_rate);
James Kuszmaul29c59522022-02-12 16:44:26 -0800331
332 if (branches_.empty()) {
333 VLOG(2) << "Initializing";
James Kuszmaul5a5a7832022-03-16 23:15:08 -0700334 current_state_.model_state(kLeftEncoder) = Z(0);
335 current_state_.model_state(kRightEncoder) = Z(1);
James Kuszmaul29c59522022-02-12 16:44:26 -0800336 current_state_.branch_time = t;
337 branches_.Push(current_state_);
338 }
339
340 const Eigen::Matrix<double, kNModelStates, kNModelOutputs> K =
341 P_model_ * H.transpose() * (H * P_model_ * H.transpose() + R).inverse();
342 P_model_ = (Eigen::Matrix<double, kNModelStates, kNModelStates>::Identity() -
343 K * H) *
344 P_model_;
345 VLOG(2) << "K\n" << K;
346 VLOG(2) << "Z\n" << Z.transpose();
347
348 for (CombinedState &state : branches_) {
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800349 UpdateState(&state, K, Z, H, accel_input, model_input, dt);
James Kuszmaul29c59522022-02-12 16:44:26 -0800350 }
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800351 UpdateState(&current_state_, K, Z, H, accel_input, model_input, dt);
James Kuszmaul29c59522022-02-12 16:44:26 -0800352
353 VLOG(2) << "oildest accel " << branches_[0].accel_state.transpose();
354 VLOG(2) << "oildest accel diff "
355 << DiffAccel(branches_[0].accel_state, accel_input).transpose();
356 VLOG(2) << "oildest model " << branches_[0].model_state.transpose();
357
358 // Determine whether to switch modes--if we are currently in model-based mode,
359 // swap to accel-based if the two states have divergeed meaningfully in the
360 // oldest branch. If we are currently in accel-based, then swap back to model
361 // if the oldest model branch matches has matched the
362 filtered_residual_accel_ +=
363 0.01 * (accel_input.topRows<2>() - filtered_residual_accel_);
364 const double model_divergence =
365 branches_.full() ? ModelDivergence(branches_[0], accel_input,
366 filtered_residual_accel_, model_input)
367 : 0.0;
368 filtered_residual_ +=
369 (1.0 - std::exp(-aos::time::DurationInSeconds(kNominalDt) / 0.0095)) *
370 (model_divergence - filtered_residual_);
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800371 // TODO(james): Tune this more. Currently set to generally trust the model,
372 // perhaps a bit too much.
373 // When the residual exceeds the accel threshold, we start using the inertials
374 // alone; when it drops back below the model threshold, we go back to being
375 // model-based.
376 constexpr double kUseAccelThreshold = 2.0;
377 constexpr double kUseModelThreshold = 0.5;
James Kuszmaul29c59522022-02-12 16:44:26 -0800378 constexpr size_t kShareStates = kNModelStates;
379 static_assert(kUseModelThreshold < kUseAccelThreshold);
380 if (using_model_) {
James Kuszmaulce491e42022-03-12 21:02:10 -0800381 if (!FLAGS_ignore_accelerometer &&
382 filtered_residual_ > kUseAccelThreshold) {
James Kuszmaul29c59522022-02-12 16:44:26 -0800383 hysteresis_count_++;
384 } else {
385 hysteresis_count_ = 0;
386 }
387 if (hysteresis_count_ > 0) {
388 using_model_ = false;
389 // Grab the accel-based state from back when we started diverging.
390 // TODO(james): This creates a problematic selection bias, because
391 // we will tend to bias towards deliberately out-of-tune measurements.
392 current_state_.accel_state = branches_[0].accel_state;
393 current_state_.model_state = branches_[0].model_state;
394 current_state_.model_state = ModelStateForAccelState(
James Kuszmaul5a5a7832022-03-16 23:15:08 -0700395 current_state_.accel_state, Z.topRows<2>(), yaw_rate);
James Kuszmaul29c59522022-02-12 16:44:26 -0800396 } else {
397 VLOG(2) << "Normal branching";
James Kuszmaul29c59522022-02-12 16:44:26 -0800398 current_state_.accel_state =
399 AccelStateForModelState(current_state_.model_state);
400 current_state_.branch_time = t;
401 }
402 hysteresis_count_ = 0;
403 } else {
404 if (filtered_residual_ < kUseModelThreshold) {
405 hysteresis_count_++;
406 } else {
407 hysteresis_count_ = 0;
408 }
409 if (hysteresis_count_ > 100) {
410 using_model_ = true;
411 // Grab the model-based state from back when we stopped diverging.
412 current_state_.model_state.topRows<kShareStates>() =
James Kuszmaul5a5a7832022-03-16 23:15:08 -0700413 ModelStateForAccelState(branches_[0].accel_state, Z.topRows<2>(),
414 yaw_rate)
James Kuszmaul29c59522022-02-12 16:44:26 -0800415 .topRows<kShareStates>();
416 current_state_.accel_state =
417 AccelStateForModelState(current_state_.model_state);
418 } else {
James Kuszmaul29c59522022-02-12 16:44:26 -0800419 // TODO(james): Why was I leaving the encoders/wheel velocities in place?
James Kuszmaul29c59522022-02-12 16:44:26 -0800420 current_state_.model_state = ModelStateForAccelState(
James Kuszmaul5a5a7832022-03-16 23:15:08 -0700421 current_state_.accel_state, Z.topRows<2>(), yaw_rate);
James Kuszmaul29c59522022-02-12 16:44:26 -0800422 current_state_.branch_time = t;
423 }
424 }
425
426 // Generate a new branch, with the accel state reset based on the model-based
427 // state (really, just getting rid of the lateral velocity).
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800428 // By resetting the accel state in the new branch, this tries to minimize the
429 // odds of runaway lateral velocities. This doesn't help with runaway
430 // longitudinal velocities, however.
James Kuszmaul29c59522022-02-12 16:44:26 -0800431 CombinedState new_branch = current_state_;
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800432 new_branch.accel_state = AccelStateForModelState(new_branch.model_state);
James Kuszmaul29c59522022-02-12 16:44:26 -0800433 new_branch.accumulated_divergence = 0.0;
434
James Kuszmaul93825a02022-02-13 16:50:33 -0800435 ++branch_counter_;
436 if (branch_counter_ % kBranchPeriod == 0) {
437 branches_.Push(new_branch);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800438 old_positions_.Push(OldPosition{t, xytheta(), latest_turret_position_,
439 latest_turret_velocity_});
James Kuszmaul93825a02022-02-13 16:50:33 -0800440 branch_counter_ = 0;
441 }
James Kuszmaul29c59522022-02-12 16:44:26 -0800442
443 last_residual_ = model_divergence;
444
445 VLOG(2) << "Using " << (using_model_ ? "model" : "accel");
446 VLOG(2) << "Residual " << last_residual_;
447 VLOG(2) << "Filtered Residual " << filtered_residual_;
448 VLOG(2) << "buffer size " << branches_.size();
449 VLOG(2) << "Model state " << current_state_.model_state.transpose();
450 VLOG(2) << "Accel state " << current_state_.accel_state.transpose();
451 VLOG(2) << "Accel state for model "
James Kuszmaulf6b69112022-03-12 21:34:39 -0800452 << AccelStateForModelState(current_state_.model_state).transpose();
James Kuszmaul29c59522022-02-12 16:44:26 -0800453 VLOG(2) << "Input acce " << accel.transpose();
454 VLOG(2) << "Input gyro " << gyro.transpose();
455 VLOG(2) << "Input voltage " << voltage.transpose();
James Kuszmaul5a5a7832022-03-16 23:15:08 -0700456 VLOG(2) << "Input encoder " << Z.topRows<2>().transpose();
James Kuszmaul29c59522022-02-12 16:44:26 -0800457 VLOG(2) << "yaw rate " << yaw_rate;
458
459 CHECK(std::isfinite(last_residual_));
460}
461
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800462const ModelBasedLocalizer::OldPosition ModelBasedLocalizer::GetStateForTime(
463 aos::monotonic_clock::time_point time) {
464 if (old_positions_.empty()) {
465 return OldPosition{};
466 }
467
468 aos::monotonic_clock::duration lowest_time_error =
469 aos::monotonic_clock::duration::max();
470 const OldPosition *best_match = nullptr;
471 for (const OldPosition &sample : old_positions_) {
472 const aos::monotonic_clock::duration time_error =
473 std::chrono::abs(sample.sample_time - time);
474 if (time_error < lowest_time_error) {
475 lowest_time_error = time_error;
476 best_match = &sample;
477 }
478 }
479 return *best_match;
480}
481
482namespace {
483// Converts a flatbuffer TransformationMatrix to an Eigen matrix. Technically,
484// this should be able to do a single memcpy, but the extra verbosity here seems
485// appropriate.
486Eigen::Matrix<double, 4, 4> FlatbufferToTransformationMatrix(
487 const frc971::vision::calibration::TransformationMatrix &flatbuffer) {
488 CHECK_EQ(16u, CHECK_NOTNULL(flatbuffer.data())->size());
489 Eigen::Matrix<double, 4, 4> result;
490 result.setIdentity();
491 for (int row = 0; row < 4; ++row) {
492 for (int col = 0; col < 4; ++col) {
493 result(row, col) = (*flatbuffer.data())[row * 4 + col];
494 }
495 }
496 return result;
497}
498
499// Node names of the pis to listen for cameras from.
Milind Upadhyayd67e9cf2022-03-13 13:56:57 -0700500constexpr std::array<std::string_view, ModelBasedLocalizer::kNumPis> kPisToUse{
501 "pi1", "pi2", "pi3", "pi4"};
James Kuszmaulf6b69112022-03-12 21:34:39 -0800502} // namespace
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800503
504const Eigen::Matrix<double, 4, 4> ModelBasedLocalizer::CameraTransform(
505 const OldPosition &state,
506 const frc971::vision::calibration::CameraCalibration *calibration,
507 std::optional<RejectionReason> *rejection_reason) const {
508 CHECK_NOTNULL(rejection_reason);
509 CHECK_NOTNULL(calibration);
510 // Per the CameraCalibration specification, we can actually determine whether
511 // the camera is the turret camera just from the presence of the
512 // turret_extrinsics member.
513 const bool is_turret = calibration->has_turret_extrinsics();
514 // Ignore readings when the turret is spinning too fast, on the assumption
515 // that the odds of screwing up the time compensation are higher.
516 // Note that the current number here is chosen pretty arbitrarily--1 rad / sec
517 // seems reasonable, but may be unnecessarily low or high.
518 constexpr double kMaxTurretVelocity = 1.0;
519 if (is_turret && std::abs(state.turret_velocity) > kMaxTurretVelocity &&
520 !rejection_reason->has_value()) {
521 *rejection_reason = RejectionReason::TURRET_TOO_FAST;
522 }
523 CHECK(calibration->has_fixed_extrinsics());
524 const Eigen::Matrix<double, 4, 4> fixed_extrinsics =
525 FlatbufferToTransformationMatrix(*calibration->fixed_extrinsics());
526
527 // Calculate the pose of the camera relative to the robot origin.
528 Eigen::Matrix<double, 4, 4> H_robot_camera = fixed_extrinsics;
529 if (is_turret) {
530 H_robot_camera =
531 H_robot_camera *
532 frc971::control_loops::TransformationMatrixForYaw<double>(
533 state.turret_position) *
534 FlatbufferToTransformationMatrix(*calibration->turret_extrinsics());
535 }
536 return H_robot_camera;
537}
538
539const std::optional<Eigen::Vector2d>
540ModelBasedLocalizer::CameraMeasuredRobotPosition(
541 const OldPosition &state, const y2022::vision::TargetEstimate *target,
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800542 std::optional<RejectionReason> *rejection_reason,
543 Eigen::Matrix<double, 4, 4> *H_field_camera_measured) const {
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800544 if (!target->has_camera_calibration()) {
545 *rejection_reason = RejectionReason::NO_CALIBRATION;
546 return std::nullopt;
547 }
548 const Eigen::Matrix<double, 4, 4> H_robot_camera =
549 CameraTransform(state, target->camera_calibration(), rejection_reason);
550 const control_loops::Pose robot_pose(
551 {state.xytheta(0), state.xytheta(1), 0.0}, state.xytheta(2));
552 const Eigen::Matrix<double, 4, 4> H_field_robot =
553 robot_pose.AsTransformationMatrix();
554 // Current estimated pose of the camera in the global frame.
555 // Note that this is all really just an elaborate way of extracting the
556 // current estimated camera yaw, and nothing else.
557 const Eigen::Matrix<double, 4, 4> H_field_camera =
558 H_field_robot * H_robot_camera;
559 // Grab the implied yaw of the camera (the +Z axis is coming out of the front
560 // of the cameras).
561 const Eigen::Vector3d rotated_camera_z =
562 H_field_camera.block<3, 3>(0, 0) * Eigen::Vector3d(0, 0, 1);
563 const double camera_yaw =
564 std::atan2(rotated_camera_z.y(), rotated_camera_z.x());
565 // All right, now we need to use the heading and distance from the
566 // TargetEstimate, plus the yaw embedded in the camera_pose, to determine what
567 // the implied X/Y position of the robot is. To do this, we calculate the
568 // heading/distance from the target to the robot. The distance is easy, since
569 // that's the same as the distance from the robot to the target. The heading
570 // isn't too hard, but is obnoxious to think about, since the heading from the
571 // target to the robot is distinct from the heading from the robot to the
572 // target.
573
574 // Just to walk through examples to confirm that the below calculation is
575 // correct:
576 // * If yaw = 0, and angle_to_target = 0, we are at 180 deg relative to the
577 // target.
578 // * If yaw = 90 deg, and angle_to_target = 0, we are at -90 deg relative to
579 // the target.
580 // * If yaw = 0, and angle_to_target = 90 deg, we are at -90 deg relative to
581 // the target.
582 const double heading_from_target =
583 aos::math::NormalizeAngle(M_PI + camera_yaw + target->angle_to_target());
584 const double distance_from_target = target->distance();
585 // Extract the implied camera position on the field.
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800586 *H_field_camera_measured = H_field_camera;
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800587 // TODO(james): Are we going to need to evict the roll/pitch components of the
588 // camera extrinsics this year as well?
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800589 (*H_field_camera_measured)(0, 3) =
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800590 distance_from_target * std::cos(heading_from_target) + kVisionTargetX;
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800591 (*H_field_camera_measured)(1, 3) =
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800592 distance_from_target * std::sin(heading_from_target) + kVisionTargetY;
593 const Eigen::Matrix<double, 4, 4> H_field_robot_measured =
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800594 *H_field_camera_measured * H_robot_camera.inverse();
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800595 return H_field_robot_measured.block<2, 1>(0, 3);
596}
597
598void ModelBasedLocalizer::HandleImageMatch(
599 aos::monotonic_clock::time_point sample_time,
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800600 const y2022::vision::TargetEstimate *target, int camera_index) {
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800601 std::optional<RejectionReason> rejection_reason;
602
James Kuszmaulaa39d962022-03-06 14:54:28 -0800603 if (target->confidence() < kMinTargetEstimateConfidence) {
604 rejection_reason = RejectionReason::LOW_CONFIDENCE;
605 TallyRejection(rejection_reason.value());
606 return;
607 }
608
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800609 const OldPosition &state = GetStateForTime(sample_time);
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800610 Eigen::Matrix<double, 4, 4> H_field_camera_measured;
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800611 const std::optional<Eigen::Vector2d> measured_robot_position =
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800612 CameraMeasuredRobotPosition(state, target, &rejection_reason,
613 &H_field_camera_measured);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800614 // Technically, rejection_reason should always be set if
615 // measured_robot_position is nullopt, but in the future we may have more
616 // recoverable rejection reasons that we wish to allow to propagate further
617 // into the process.
618 if (!measured_robot_position || rejection_reason.has_value()) {
619 CHECK(rejection_reason.has_value());
620 TallyRejection(rejection_reason.value());
621 return;
622 }
623
624 // Next, go through and do the actual Kalman corrections for the x/y
625 // measurement, for both the accel state and the model-based state.
626 const Eigen::Matrix<double, kNModelStates, kNModelStates> A_continuous_model =
627 AModel(current_state_.model_state);
628
629 Eigen::Matrix<double, kNModelStates, kNModelStates> A_discrete_model;
630 Eigen::Matrix<double, kNModelStates, kNModelStates> Q_discrete_model;
631
632 DiscretizeQAFast(Q_continuous_model_, A_continuous_model, kNominalDt,
633 &Q_discrete_model, &A_discrete_model);
634
635 Eigen::Matrix<double, 2, kNModelStates> H_model;
636 H_model.setZero();
637 Eigen::Matrix<double, 2, kNAccelStates> H_accel;
638 H_accel.setZero();
639 Eigen::Matrix<double, 2, 2> R;
640 R.setZero();
641 H_model(0, kX) = 1.0;
642 H_model(1, kY) = 1.0;
643 H_accel(0, kX) = 1.0;
644 H_accel(1, kY) = 1.0;
Austin Schuh235e2d92022-04-06 17:04:39 -0700645 R.diagonal() << 1e-2, 1e-2;
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800646
647 const Eigen::Matrix<double, kNModelStates, 2> K_model =
648 P_model_ * H_model.transpose() *
649 (H_model * P_model_ * H_model.transpose() + R).inverse();
650 const Eigen::Matrix<double, kNAccelStates, 2> K_accel =
651 P_accel_ * H_accel.transpose() *
652 (H_accel * P_accel_ * H_accel.transpose() + R).inverse();
653 P_model_ = (Eigen::Matrix<double, kNModelStates, kNModelStates>::Identity() -
654 K_model * H_model) *
655 P_model_;
656 P_accel_ = (Eigen::Matrix<double, kNAccelStates, kNAccelStates>::Identity() -
657 K_accel * H_accel) *
658 P_accel_;
659 // And now we have to correct *everything* on all the branches:
660 for (CombinedState &state : branches_) {
661 state.model_state += K_model * (measured_robot_position.value() -
James Kuszmaulf6b69112022-03-12 21:34:39 -0800662 H_model * state.model_state);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800663 state.accel_state += K_accel * (measured_robot_position.value() -
James Kuszmaulf6b69112022-03-12 21:34:39 -0800664 H_accel * state.accel_state);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800665 }
666 current_state_.model_state +=
667 K_model *
668 (measured_robot_position.value() - H_model * current_state_.model_state);
669 current_state_.accel_state +=
670 K_accel *
671 (measured_robot_position.value() - H_accel * current_state_.accel_state);
672
673 statistics_.total_accepted++;
674 statistics_.total_candidates++;
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800675
676 const Eigen::Vector3d camera_z_in_field =
677 H_field_camera_measured.block<3, 3>(0, 0) * Eigen::Vector3d::UnitZ();
678 const double camera_yaw =
679 std::atan2(camera_z_in_field.y(), camera_z_in_field.x());
680
Milind Upadhyayd67e9cf2022-03-13 13:56:57 -0700681 // TODO(milind): actually control this
682 led_outputs_[camera_index] = LedOutput::ON;
683
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800684 TargetEstimateDebugT debug;
685 debug.camera = static_cast<uint8_t>(camera_index);
686 debug.camera_x = H_field_camera_measured(0, 3);
687 debug.camera_y = H_field_camera_measured(1, 3);
688 debug.camera_theta = camera_yaw;
689 debug.implied_robot_x = measured_robot_position.value().x();
690 debug.implied_robot_y = measured_robot_position.value().y();
691 debug.implied_robot_theta = xytheta()(2);
692 debug.implied_turret_goal =
693 aos::math::NormalizeAngle(camera_yaw + target->angle_to_target());
694 debug.accepted = true;
695 debug.image_age_sec = aos::time::DurationInSeconds(t_ - sample_time);
James Kuszmaul2b2f8772022-03-12 15:25:35 -0800696 CHECK_LT(image_debugs_.size(), kDebugBufferSize);
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800697 image_debugs_.push_back(debug);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800698}
699
700void ModelBasedLocalizer::HandleTurret(
701 aos::monotonic_clock::time_point sample_time, double turret_position,
702 double turret_velocity) {
703 last_turret_update_ = sample_time;
704 latest_turret_position_ = turret_position;
705 latest_turret_velocity_ = turret_velocity;
706}
707
James Kuszmaul29c59522022-02-12 16:44:26 -0800708void ModelBasedLocalizer::HandleReset(aos::monotonic_clock::time_point now,
709 const Eigen::Vector3d &xytheta) {
710 branches_.Reset();
James Kuszmaulf6b69112022-03-12 21:34:39 -0800711 t_ = now;
James Kuszmaul29c59522022-02-12 16:44:26 -0800712 using_model_ = true;
713 current_state_.model_state << xytheta(0), xytheta(1), xytheta(2),
714 current_state_.model_state(kLeftEncoder), 0.0, 0.0,
715 current_state_.model_state(kRightEncoder), 0.0, 0.0;
716 current_state_.accel_state =
717 AccelStateForModelState(current_state_.model_state);
718 last_residual_ = 0.0;
719 filtered_residual_ = 0.0;
720 filtered_residual_accel_.setZero();
721 abs_accel_.setZero();
722}
723
724flatbuffers::Offset<AccelBasedState> ModelBasedLocalizer::BuildAccelState(
725 flatbuffers::FlatBufferBuilder *fbb, const AccelState &state) {
726 AccelBasedState::Builder accel_state_builder(*fbb);
727 accel_state_builder.add_x(state(kX));
728 accel_state_builder.add_y(state(kY));
729 accel_state_builder.add_theta(state(kTheta));
730 accel_state_builder.add_velocity_x(state(kVelocityX));
731 accel_state_builder.add_velocity_y(state(kVelocityY));
732 return accel_state_builder.Finish();
733}
734
735flatbuffers::Offset<ModelBasedState> ModelBasedLocalizer::BuildModelState(
736 flatbuffers::FlatBufferBuilder *fbb, const ModelState &state) {
737 ModelBasedState::Builder model_state_builder(*fbb);
738 model_state_builder.add_x(state(kX));
739 model_state_builder.add_y(state(kY));
740 model_state_builder.add_theta(state(kTheta));
741 model_state_builder.add_left_encoder(state(kLeftEncoder));
742 model_state_builder.add_left_velocity(state(kLeftVelocity));
743 model_state_builder.add_left_voltage_error(state(kLeftVoltageError));
744 model_state_builder.add_right_encoder(state(kRightEncoder));
745 model_state_builder.add_right_velocity(state(kRightVelocity));
746 model_state_builder.add_right_voltage_error(state(kRightVoltageError));
747 return model_state_builder.Finish();
748}
749
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800750flatbuffers::Offset<CumulativeStatistics>
751ModelBasedLocalizer::PopulateStatistics(flatbuffers::FlatBufferBuilder *fbb) {
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800752 const auto rejections_offset = fbb->CreateVector(
753 statistics_.rejection_counts.data(), statistics_.rejection_counts.size());
754
755 CumulativeStatistics::Builder stats_builder(*fbb);
756 stats_builder.add_total_accepted(statistics_.total_accepted);
757 stats_builder.add_total_candidates(statistics_.total_candidates);
758 stats_builder.add_rejection_reason_count(rejections_offset);
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800759 return stats_builder.Finish();
760}
761
762flatbuffers::Offset<ModelBasedStatus> ModelBasedLocalizer::PopulateStatus(
763 flatbuffers::FlatBufferBuilder *fbb) {
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800764 const flatbuffers::Offset<CumulativeStatistics> stats_offset =
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800765 PopulateStatistics(fbb);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800766
James Kuszmaul29c59522022-02-12 16:44:26 -0800767 const flatbuffers::Offset<control_loops::drivetrain::DownEstimatorState>
768 down_estimator_offset = down_estimator_.PopulateStatus(fbb, t_);
769
770 const CombinedState &state = current_state_;
771
772 const flatbuffers::Offset<ModelBasedState> model_state_offset =
James Kuszmaulf6b69112022-03-12 21:34:39 -0800773 BuildModelState(fbb, state.model_state);
James Kuszmaul29c59522022-02-12 16:44:26 -0800774
775 const flatbuffers::Offset<AccelBasedState> accel_state_offset =
776 BuildAccelState(fbb, state.accel_state);
777
778 const flatbuffers::Offset<AccelBasedState> oldest_accel_state_offset =
779 branches_.empty() ? flatbuffers::Offset<AccelBasedState>()
780 : BuildAccelState(fbb, branches_[0].accel_state);
781
782 const flatbuffers::Offset<ModelBasedState> oldest_model_state_offset =
783 branches_.empty() ? flatbuffers::Offset<ModelBasedState>()
784 : BuildModelState(fbb, branches_[0].model_state);
785
786 ModelBasedStatus::Builder builder(*fbb);
787 builder.add_accel_state(accel_state_offset);
788 builder.add_oldest_accel_state(oldest_accel_state_offset);
789 builder.add_oldest_model_state(oldest_model_state_offset);
790 builder.add_model_state(model_state_offset);
791 builder.add_using_model(using_model_);
792 builder.add_residual(last_residual_);
793 builder.add_filtered_residual(filtered_residual_);
794 builder.add_velocity_residual(velocity_residual_);
795 builder.add_accel_residual(accel_residual_);
796 builder.add_theta_rate_residual(theta_rate_residual_);
797 builder.add_down_estimator(down_estimator_offset);
798 builder.add_x(xytheta()(0));
799 builder.add_y(xytheta()(1));
800 builder.add_theta(xytheta()(2));
801 builder.add_implied_accel_x(abs_accel_(0));
802 builder.add_implied_accel_y(abs_accel_(1));
803 builder.add_implied_accel_z(abs_accel_(2));
804 builder.add_clock_resets(clock_resets_);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800805 builder.add_statistics(stats_offset);
James Kuszmaul29c59522022-02-12 16:44:26 -0800806 return builder.Finish();
807}
808
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800809flatbuffers::Offset<LocalizerVisualization>
810ModelBasedLocalizer::PopulateVisualization(
811 flatbuffers::FlatBufferBuilder *fbb) {
812 const flatbuffers::Offset<CumulativeStatistics> stats_offset =
813 PopulateStatistics(fbb);
814
815 aos::SizedArray<flatbuffers::Offset<TargetEstimateDebug>, kDebugBufferSize>
816 debug_offsets;
817
James Kuszmaulf6b69112022-03-12 21:34:39 -0800818 for (const TargetEstimateDebugT &debug : image_debugs_) {
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800819 debug_offsets.push_back(PackTargetEstimateDebug(debug, fbb));
820 }
821
822 image_debugs_.clear();
823
824 const flatbuffers::Offset<
825 flatbuffers::Vector<flatbuffers::Offset<TargetEstimateDebug>>>
826 debug_offset =
827 fbb->CreateVector(debug_offsets.data(), debug_offsets.size());
828
829 LocalizerVisualization::Builder builder(*fbb);
830 builder.add_statistics(stats_offset);
831 builder.add_targets(debug_offset);
832 return builder.Finish();
833}
834
835void ModelBasedLocalizer::TallyRejection(const RejectionReason reason) {
836 statistics_.total_candidates++;
837 statistics_.rejection_counts[static_cast<size_t>(reason)]++;
838 TargetEstimateDebugT debug;
839 debug.accepted = false;
840 debug.rejection_reason = reason;
James Kuszmaul2b2f8772022-03-12 15:25:35 -0800841 CHECK_LT(image_debugs_.size(), kDebugBufferSize);
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800842 image_debugs_.push_back(debug);
843}
844
845flatbuffers::Offset<TargetEstimateDebug>
846ModelBasedLocalizer::PackTargetEstimateDebug(
847 const TargetEstimateDebugT &debug, flatbuffers::FlatBufferBuilder *fbb) {
848 if (!debug.accepted) {
849 TargetEstimateDebug::Builder builder(*fbb);
850 builder.add_accepted(debug.accepted);
851 builder.add_rejection_reason(debug.rejection_reason);
852 return builder.Finish();
853 } else {
854 flatbuffers::Offset<TargetEstimateDebug> offset =
855 TargetEstimateDebug::Pack(*fbb, &debug);
856 flatbuffers::GetMutableTemporaryPointer(*fbb, offset)
857 ->clear_rejection_reason();
858 return offset;
859 }
860}
861
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800862namespace {
863// Period at which the encoder readings from the IMU board wrap.
864static double DrivetrainWrapPeriod() {
865 return y2022::constants::Values::DrivetrainEncoderToMeters(1 << 16);
866}
James Kuszmaulf6b69112022-03-12 21:34:39 -0800867} // namespace
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800868
James Kuszmaul29c59522022-02-12 16:44:26 -0800869EventLoopLocalizer::EventLoopLocalizer(
870 aos::EventLoop *event_loop,
871 const control_loops::drivetrain::DrivetrainConfig<double> &dt_config)
872 : event_loop_(event_loop),
James Kuszmaul6d6e1302022-03-12 15:22:48 -0800873 dt_config_(dt_config),
James Kuszmaul29c59522022-02-12 16:44:26 -0800874 model_based_(dt_config),
875 status_sender_(event_loop_->MakeSender<LocalizerStatus>("/localizer")),
876 output_sender_(event_loop_->MakeSender<LocalizerOutput>("/localizer")),
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800877 visualization_sender_(
878 event_loop_->MakeSender<LocalizerVisualization>("/localizer")),
James Kuszmaul29c59522022-02-12 16:44:26 -0800879 output_fetcher_(
880 event_loop_->MakeFetcher<frc971::control_loops::drivetrain::Output>(
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800881 "/drivetrain")),
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800882 clock_offset_fetcher_(
883 event_loop_->MakeFetcher<aos::message_bridge::ServerStatistics>(
884 "/aos")),
James Kuszmaulf6b69112022-03-12 21:34:39 -0800885 superstructure_fetcher_(
886 event_loop_
887 ->MakeFetcher<y2022::control_loops::superstructure::Status>(
888 "/superstructure")),
James Kuszmaulfd254bb2022-03-13 21:08:15 -0700889 zeroer_(zeroing::ImuZeroer::FaultBehavior::kTemporary),
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800890 left_encoder_(-DrivetrainWrapPeriod() / 2.0, DrivetrainWrapPeriod()),
891 right_encoder_(-DrivetrainWrapPeriod() / 2.0, DrivetrainWrapPeriod()) {
James Kuszmaula391dde2022-03-17 00:03:30 -0700892 event_loop->SetRuntimeRealtimePriority(10);
James Kuszmaul29c59522022-02-12 16:44:26 -0800893 event_loop_->MakeWatcher(
894 "/drivetrain",
895 [this](
896 const frc971::control_loops::drivetrain::LocalizerControl &control) {
897 const double theta = control.keep_current_theta()
898 ? model_based_.xytheta()(2)
899 : control.theta();
900 model_based_.HandleReset(event_loop_->monotonic_now(),
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800901 {control.x(), control.y(), theta});
James Kuszmaul29c59522022-02-12 16:44:26 -0800902 });
James Kuszmaul2b2f8772022-03-12 15:25:35 -0800903 aos::TimerHandler *superstructure_timer = event_loop_->AddTimer([this]() {
904 if (superstructure_fetcher_.Fetch()) {
905 const y2022::control_loops::superstructure::Status &status =
906 *superstructure_fetcher_.get();
907 if (!status.has_turret()) {
908 return;
909 }
910 CHECK(status.has_turret());
911 model_based_.HandleTurret(
912 superstructure_fetcher_.context().monotonic_event_time,
913 status.turret()->position(), status.turret()->velocity());
914 }
915 });
916 event_loop_->OnRun([this, superstructure_timer]() {
917 superstructure_timer->Setup(event_loop_->monotonic_now(),
918 std::chrono::milliseconds(20));
919 });
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800920
James Kuszmaulf6b69112022-03-12 21:34:39 -0800921 for (size_t camera_index = 0; camera_index < kPisToUse.size();
922 ++camera_index) {
James Kuszmaul2b2f8772022-03-12 15:25:35 -0800923 CHECK_LT(camera_index, target_estimate_fetchers_.size());
924 target_estimate_fetchers_[camera_index] =
925 event_loop_->MakeFetcher<y2022::vision::TargetEstimate>(
926 absl::StrCat("/", kPisToUse[camera_index], "/camera"));
927 }
James Kuszmaulf6b69112022-03-12 21:34:39 -0800928 aos::TimerHandler *estimate_timer = event_loop_->AddTimer([this]() {
929 for (size_t camera_index = 0; camera_index < kPisToUse.size();
930 ++camera_index) {
931 if (model_based_.NumQueuedImageDebugs() ==
932 ModelBasedLocalizer::kDebugBufferSize ||
933 (last_visualization_send_ + kMinVisualizationPeriod <
934 event_loop_->monotonic_now())) {
935 auto builder = visualization_sender_.MakeBuilder();
936 visualization_sender_.CheckOk(
937 builder.Send(model_based_.PopulateVisualization(builder.fbb())));
938 }
939 if (target_estimate_fetchers_[camera_index].Fetch()) {
940 const std::optional<aos::monotonic_clock::duration> monotonic_offset =
941 ClockOffset(kPisToUse[camera_index]);
942 if (!monotonic_offset.has_value()) {
943 continue;
James Kuszmaul2b2f8772022-03-12 15:25:35 -0800944 }
James Kuszmaulf6b69112022-03-12 21:34:39 -0800945 // TODO(james): Get timestamp from message contents.
946 aos::monotonic_clock::time_point capture_time(
947 target_estimate_fetchers_[camera_index]
948 .context()
949 .monotonic_remote_time -
950 monotonic_offset.value());
951 if (capture_time > target_estimate_fetchers_[camera_index]
952 .context()
953 .monotonic_event_time) {
954 model_based_.TallyRejection(RejectionReason::IMAGE_FROM_FUTURE);
955 continue;
956 }
James Kuszmaul81138072022-04-03 15:30:00 -0700957 capture_time -= pico_offset_error_;
James Kuszmaulf6b69112022-03-12 21:34:39 -0800958 model_based_.HandleImageMatch(
959 capture_time, target_estimate_fetchers_[camera_index].get(),
960 camera_index);
961 }
962 }
963 });
James Kuszmaul2b2f8772022-03-12 15:25:35 -0800964 event_loop_->OnRun([this, estimate_timer]() {
965 estimate_timer->Setup(event_loop_->monotonic_now(),
966 std::chrono::milliseconds(100));
967 });
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800968 event_loop_->MakeWatcher(
James Kuszmaul29c59522022-02-12 16:44:26 -0800969 "/localizer", [this](const frc971::IMUValuesBatch &values) {
970 CHECK(values.has_readings());
James Kuszmaul29c59522022-02-12 16:44:26 -0800971 output_fetcher_.Fetch();
972 for (const IMUValues *value : *values.readings()) {
973 zeroer_.InsertAndProcessMeasurement(*value);
James Kuszmaul5f27d8b2022-03-17 09:08:26 -0700974 if (zeroer_.Faulted()) {
975 if (value->checksum_failed()) {
976 imu_fault_tracker_.pico_to_pi_checksum_mismatch++;
977 } else if (value->previous_reading_diag_stat()->checksum_mismatch()) {
978 imu_fault_tracker_.imu_to_pico_checksum_mismatch++;
979 } else {
980 imu_fault_tracker_.other_zeroing_faults++;
981 }
982 } else {
983 if (!first_valid_data_counter_.has_value()) {
984 first_valid_data_counter_ = value->data_counter();
985 }
986 }
987 if (first_valid_data_counter_.has_value()) {
988 total_imu_messages_received_++;
989 // Only update when we have good checksums, since the data counter
990 // could get corrupted.
991 if (!zeroer_.Faulted()) {
992 if (value->data_counter() < last_data_counter_) {
993 data_counter_offset_ += 1 << 16;
994 }
995 imu_fault_tracker_.missed_messages =
996 (1 + value->data_counter() + data_counter_offset_ -
997 first_valid_data_counter_.value()) -
998 total_imu_messages_received_;
999 last_data_counter_ = value->data_counter();
1000 }
1001 }
James Kuszmaul5a5a7832022-03-16 23:15:08 -07001002 const std::optional<Eigen::Vector2d> encoders =
1003 zeroer_.Faulted()
1004 ? std::nullopt
1005 : std::make_optional(Eigen::Vector2d{
1006 left_encoder_.Unwrap(value->left_encoder()),
1007 right_encoder_.Unwrap(value->right_encoder())});
James Kuszmaul6d6e1302022-03-12 15:22:48 -08001008 {
James Kuszmaul5f27d8b2022-03-17 09:08:26 -07001009 // If we can't trust the imu reading, just naively increment the
1010 // pico timestamp.
1011 const aos::monotonic_clock::time_point pico_timestamp =
1012 zeroer_.Faulted()
1013 ? (last_pico_timestamp_.has_value()
1014 ? last_pico_timestamp_.value() + kNominalDt
1015 : aos::monotonic_clock::epoch())
1016 : aos::monotonic_clock::time_point(
1017 std::chrono::microseconds(
1018 value->pico_timestamp_us()));
James Kuszmaul5ed29dd2022-02-13 18:32:06 -08001019 // TODO(james): If we get large enough drift off of the pico,
1020 // actually do something about it.
1021 if (!pico_offset_.has_value()) {
1022 pico_offset_ =
1023 event_loop_->context().monotonic_event_time - pico_timestamp;
1024 last_pico_timestamp_ = pico_timestamp;
James Kuszmaule5f67dd2022-02-12 20:08:29 -08001025 }
James Kuszmaul5ed29dd2022-02-13 18:32:06 -08001026 if (pico_timestamp < last_pico_timestamp_) {
1027 pico_offset_.value() += std::chrono::microseconds(1ULL << 32);
1028 }
1029 const aos::monotonic_clock::time_point sample_timestamp =
1030 pico_offset_.value() + pico_timestamp;
1031 pico_offset_error_ =
1032 event_loop_->context().monotonic_event_time - sample_timestamp;
1033 const bool disabled =
1034 (output_fetcher_.get() == nullptr) ||
1035 (output_fetcher_.context().monotonic_event_time +
1036 std::chrono::milliseconds(10) <
1037 event_loop_->context().monotonic_event_time);
James Kuszmaul6d6e1302022-03-12 15:22:48 -08001038 const bool zeroed = zeroer_.Zeroed();
James Kuszmaul5f27d8b2022-03-17 09:08:26 -07001039 // For gyros, use the most recent gyro reading if we aren't zeroed,
1040 // to avoid missing integration cycles.
James Kuszmaul5ed29dd2022-02-13 18:32:06 -08001041 model_based_.HandleImu(
James Kuszmaul6d6e1302022-03-12 15:22:48 -08001042 sample_timestamp,
James Kuszmaul5f27d8b2022-03-17 09:08:26 -07001043 zeroed ? zeroer_.ZeroedGyro().value() : last_gyro_,
James Kuszmaul6d6e1302022-03-12 15:22:48 -08001044 zeroed ? zeroer_.ZeroedAccel().value()
1045 : dt_config_.imu_transform.transpose() *
1046 Eigen::Vector3d::UnitZ(),
James Kuszmaulf6b69112022-03-12 21:34:39 -08001047 encoders,
James Kuszmaul5ed29dd2022-02-13 18:32:06 -08001048 disabled ? Eigen::Vector2d::Zero()
1049 : Eigen::Vector2d{output_fetcher_->left_voltage(),
1050 output_fetcher_->right_voltage()});
1051 last_pico_timestamp_ = pico_timestamp;
James Kuszmaul5f27d8b2022-03-17 09:08:26 -07001052
1053 if (zeroed) {
1054 last_gyro_ = zeroer_.ZeroedGyro().value();
1055 }
James Kuszmaul29c59522022-02-12 16:44:26 -08001056 }
1057 {
1058 auto builder = status_sender_.MakeBuilder();
1059 const flatbuffers::Offset<ModelBasedStatus> model_based_status =
1060 model_based_.PopulateStatus(builder.fbb());
James Kuszmaul5ed29dd2022-02-13 18:32:06 -08001061 const flatbuffers::Offset<control_loops::drivetrain::ImuZeroerState>
1062 zeroer_status = zeroer_.PopulateStatus(builder.fbb());
James Kuszmaul5f27d8b2022-03-17 09:08:26 -07001063 const flatbuffers::Offset<ImuFailures> imu_failures =
1064 ImuFailures::Pack(*builder.fbb(), &imu_fault_tracker_);
James Kuszmaul29c59522022-02-12 16:44:26 -08001065 LocalizerStatus::Builder status_builder =
1066 builder.MakeBuilder<LocalizerStatus>();
1067 status_builder.add_model_based(model_based_status);
1068 status_builder.add_zeroed(zeroer_.Zeroed());
1069 status_builder.add_faulted_zero(zeroer_.Faulted());
James Kuszmaul5ed29dd2022-02-13 18:32:06 -08001070 status_builder.add_zeroing(zeroer_status);
James Kuszmaul5f27d8b2022-03-17 09:08:26 -07001071 status_builder.add_imu_failures(imu_failures);
James Kuszmaul5a5a7832022-03-16 23:15:08 -07001072 if (encoders.has_value()) {
1073 status_builder.add_left_encoder(encoders.value()(0));
1074 status_builder.add_right_encoder(encoders.value()(1));
1075 }
James Kuszmaul5ed29dd2022-02-13 18:32:06 -08001076 if (pico_offset_.has_value()) {
1077 status_builder.add_pico_offset_ns(pico_offset_.value().count());
1078 status_builder.add_pico_offset_error_ns(
1079 pico_offset_error_.count());
1080 }
James Kuszmaul29c59522022-02-12 16:44:26 -08001081 builder.CheckOk(builder.Send(status_builder.Finish()));
1082 }
1083 if (last_output_send_ + std::chrono::milliseconds(5) <
1084 event_loop_->context().monotonic_event_time) {
1085 auto builder = output_sender_.MakeBuilder();
Milind Upadhyayd67e9cf2022-03-13 13:56:57 -07001086
1087 const auto led_outputs_offset =
1088 builder.fbb()->CreateVector(model_based_.led_outputs().data(),
1089 model_based_.led_outputs().size());
1090
James Kuszmaul29c59522022-02-12 16:44:26 -08001091 LocalizerOutput::Builder output_builder =
1092 builder.MakeBuilder<LocalizerOutput>();
James Kuszmaul1798c072022-02-13 15:32:11 -08001093 // TODO(james): Should we bother to try to estimate time offsets for
1094 // the pico?
1095 output_builder.add_monotonic_timestamp_ns(
1096 value->monotonic_timestamp_ns());
James Kuszmaul29c59522022-02-12 16:44:26 -08001097 output_builder.add_x(model_based_.xytheta()(0));
1098 output_builder.add_y(model_based_.xytheta()(1));
1099 output_builder.add_theta(model_based_.xytheta()(2));
James Kuszmaulf3ef9e12022-03-05 17:13:00 -08001100 output_builder.add_zeroed(zeroer_.Zeroed());
James Kuszmaul10d3fd42022-02-25 21:57:36 -08001101 const Eigen::Quaterniond &orientation = model_based_.orientation();
1102 Quaternion quaternion;
1103 quaternion.mutate_x(orientation.x());
1104 quaternion.mutate_y(orientation.y());
1105 quaternion.mutate_z(orientation.z());
1106 quaternion.mutate_w(orientation.w());
1107 output_builder.add_orientation(&quaternion);
Milind Upadhyayd67e9cf2022-03-13 13:56:57 -07001108 output_builder.add_led_outputs(led_outputs_offset);
James Kuszmaul29c59522022-02-12 16:44:26 -08001109 builder.CheckOk(builder.Send(output_builder.Finish()));
1110 last_output_send_ = event_loop_->monotonic_now();
1111 }
1112 }
1113 });
1114}
1115
James Kuszmaul8c4f6592022-02-26 15:49:30 -08001116std::optional<aos::monotonic_clock::duration> EventLoopLocalizer::ClockOffset(
1117 std::string_view pi) {
1118 std::optional<aos::monotonic_clock::duration> monotonic_offset;
1119 clock_offset_fetcher_.Fetch();
1120 if (clock_offset_fetcher_.get() != nullptr) {
1121 for (const auto connection : *clock_offset_fetcher_->connections()) {
1122 if (connection->has_node() && connection->node()->has_name() &&
1123 connection->node()->name()->string_view() == pi) {
1124 if (connection->has_monotonic_offset()) {
1125 monotonic_offset =
1126 std::chrono::nanoseconds(connection->monotonic_offset());
1127 } else {
1128 // If we don't have a monotonic offset, that means we aren't
1129 // connected.
1130 model_based_.TallyRejection(
1131 RejectionReason::MESSAGE_BRIDGE_DISCONNECTED);
1132 return std::nullopt;
1133 }
1134 break;
1135 }
1136 }
1137 }
1138 CHECK(monotonic_offset.has_value());
1139 return monotonic_offset;
1140}
1141
James Kuszmaul29c59522022-02-12 16:44:26 -08001142} // namespace frc971::controls