blob: a298f980dcf2bf81983ed169ab033b559c08a715 [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
8namespace frc971::controls {
9
10namespace {
11constexpr double kG = 9.80665;
12constexpr std::chrono::microseconds kNominalDt(500);
13
James Kuszmaul8c4f6592022-02-26 15:49:30 -080014// Field position of the target (the 2022 target is conveniently in the middle
15// of the field....).
16constexpr double kVisionTargetX = 0.0;
17constexpr double kVisionTargetY = 0.0;
18
James Kuszmaulaa39d962022-03-06 14:54:28 -080019// Minimum confidence to require to use a target match.
20constexpr double kMinTargetEstimateConfidence = 0.2;
21
James Kuszmaul29c59522022-02-12 16:44:26 -080022template <int N>
23Eigen::Matrix<double, N, 1> MakeState(std::vector<double> values) {
24 CHECK_EQ(static_cast<size_t>(N), values.size());
25 Eigen::Matrix<double, N, 1> vector;
26 for (int ii = 0; ii < N; ++ii) {
27 vector(ii, 0) = values[ii];
28 }
29 return vector;
30}
James Kuszmaul29c59522022-02-12 16:44:26 -080031} // namespace
32
33ModelBasedLocalizer::ModelBasedLocalizer(
34 const control_loops::drivetrain::DrivetrainConfig<double> &dt_config)
35 : dt_config_(dt_config),
36 velocity_drivetrain_coefficients_(
37 dt_config.make_hybrid_drivetrain_velocity_loop()
38 .plant()
39 .coefficients()),
40 down_estimator_(dt_config) {
James Kuszmaul8c4f6592022-02-26 15:49:30 -080041 statistics_.rejection_counts.fill(0);
James Kuszmaulf6b69112022-03-12 21:34:39 -080042 CHECK_EQ(branches_.capacity(),
43 static_cast<size_t>(std::chrono::seconds(1) / kNominalDt /
44 kBranchPeriod));
James Kuszmaul29c59522022-02-12 16:44:26 -080045 if (dt_config_.is_simulated) {
46 down_estimator_.assume_perfect_gravity();
47 }
48 A_continuous_accel_.setZero();
49 A_continuous_model_.setZero();
50 B_continuous_accel_.setZero();
51 B_continuous_model_.setZero();
52
53 A_continuous_accel_(kX, kVelocityX) = 1.0;
54 A_continuous_accel_(kY, kVelocityY) = 1.0;
55
56 const double diameter = 2.0 * dt_config_.robot_radius;
57
58 A_continuous_model_(kTheta, kLeftVelocity) = -1.0 / diameter;
59 A_continuous_model_(kTheta, kRightVelocity) = 1.0 / diameter;
60 A_continuous_model_(kLeftEncoder, kLeftVelocity) = 1.0;
61 A_continuous_model_(kRightEncoder, kRightVelocity) = 1.0;
62 const auto &vel_coefs = velocity_drivetrain_coefficients_;
63 A_continuous_model_(kLeftVelocity, kLeftVelocity) =
64 vel_coefs.A_continuous(0, 0);
65 A_continuous_model_(kLeftVelocity, kRightVelocity) =
66 vel_coefs.A_continuous(0, 1);
67 A_continuous_model_(kRightVelocity, kLeftVelocity) =
68 vel_coefs.A_continuous(1, 0);
69 A_continuous_model_(kRightVelocity, kRightVelocity) =
70 vel_coefs.A_continuous(1, 1);
71
72 A_continuous_model_(kLeftVelocity, kLeftVoltageError) =
73 1 * vel_coefs.B_continuous(0, 0);
74 A_continuous_model_(kLeftVelocity, kRightVoltageError) =
75 1 * vel_coefs.B_continuous(0, 1);
76 A_continuous_model_(kRightVelocity, kLeftVoltageError) =
77 1 * vel_coefs.B_continuous(1, 0);
78 A_continuous_model_(kRightVelocity, kRightVoltageError) =
79 1 * vel_coefs.B_continuous(1, 1);
80
81 B_continuous_model_.block<1, 2>(kLeftVelocity, kLeftVoltage) =
82 vel_coefs.B_continuous.row(0);
83 B_continuous_model_.block<1, 2>(kRightVelocity, kLeftVoltage) =
84 vel_coefs.B_continuous.row(1);
85
86 B_continuous_accel_(kVelocityX, kAccelX) = 1.0;
87 B_continuous_accel_(kVelocityY, kAccelY) = 1.0;
88 B_continuous_accel_(kTheta, kThetaRate) = 1.0;
89
90 Q_continuous_model_.setZero();
James Kuszmaul8c4f6592022-02-26 15:49:30 -080091 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 -080092 1e-0, 1e-0;
93
James Kuszmaul8c4f6592022-02-26 15:49:30 -080094 Q_continuous_accel_.setZero();
95 Q_continuous_accel_.diagonal() << 1e-2, 1e-2, 1e-20, 1e-4, 1e-4;
96
James Kuszmaul29c59522022-02-12 16:44:26 -080097 P_model_ = Q_continuous_model_ * aos::time::DurationInSeconds(kNominalDt);
James Kuszmaul8c4f6592022-02-26 15:49:30 -080098
99 // We can precalculate the discretizations of the accel model because it is
100 // actually LTI.
101
102 DiscretizeQAFast(Q_continuous_accel_, A_continuous_accel_, kNominalDt,
103 &Q_discrete_accel_, &A_discrete_accel_);
104 P_accel_ = Q_discrete_accel_;
James Kuszmaul29c59522022-02-12 16:44:26 -0800105}
106
107Eigen::Matrix<double, ModelBasedLocalizer::kNModelStates,
108 ModelBasedLocalizer::kNModelStates>
109ModelBasedLocalizer::AModel(
110 const ModelBasedLocalizer::ModelState &state) const {
111 Eigen::Matrix<double, kNModelStates, kNModelStates> A = A_continuous_model_;
112 const double theta = state(kTheta);
113 const double stheta = std::sin(theta);
114 const double ctheta = std::cos(theta);
115 const double velocity = (state(kLeftVelocity) + state(kRightVelocity)) / 2.0;
116 A(kX, kTheta) = -stheta * velocity;
117 A(kX, kLeftVelocity) = ctheta / 2.0;
118 A(kX, kRightVelocity) = ctheta / 2.0;
119 A(kY, kTheta) = ctheta * velocity;
120 A(kY, kLeftVelocity) = stheta / 2.0;
121 A(kY, kRightVelocity) = stheta / 2.0;
122 return A;
123}
124
125Eigen::Matrix<double, ModelBasedLocalizer::kNAccelStates,
126 ModelBasedLocalizer::kNAccelStates>
127ModelBasedLocalizer::AAccel() const {
128 return A_continuous_accel_;
129}
130
131ModelBasedLocalizer::ModelState ModelBasedLocalizer::DiffModel(
132 const ModelBasedLocalizer::ModelState &state,
133 const ModelBasedLocalizer::ModelInput &U) const {
134 ModelState x_dot = AModel(state) * state + B_continuous_model_ * U;
135 const double theta = state(kTheta);
136 const double stheta = std::sin(theta);
137 const double ctheta = std::cos(theta);
138 const double velocity = (state(kLeftVelocity) + state(kRightVelocity)) / 2.0;
139 x_dot(kX) = ctheta * velocity;
140 x_dot(kY) = stheta * velocity;
141 return x_dot;
142}
143
144ModelBasedLocalizer::AccelState ModelBasedLocalizer::DiffAccel(
145 const ModelBasedLocalizer::AccelState &state,
146 const ModelBasedLocalizer::AccelInput &U) const {
147 return AAccel() * state + B_continuous_accel_ * U;
148}
149
150ModelBasedLocalizer::ModelState ModelBasedLocalizer::UpdateModel(
151 const ModelBasedLocalizer::ModelState &model,
152 const ModelBasedLocalizer::ModelInput &input,
153 const aos::monotonic_clock::duration dt) const {
154 return control_loops::RungeKutta(
155 std::bind(&ModelBasedLocalizer::DiffModel, this, std::placeholders::_1,
156 input),
157 model, aos::time::DurationInSeconds(dt));
158}
159
160ModelBasedLocalizer::AccelState ModelBasedLocalizer::UpdateAccel(
161 const ModelBasedLocalizer::AccelState &accel,
162 const ModelBasedLocalizer::AccelInput &input,
163 const aos::monotonic_clock::duration dt) const {
164 return control_loops::RungeKutta(
165 std::bind(&ModelBasedLocalizer::DiffAccel, this, std::placeholders::_1,
166 input),
167 accel, aos::time::DurationInSeconds(dt));
168}
169
170ModelBasedLocalizer::AccelState ModelBasedLocalizer::AccelStateForModelState(
171 const ModelBasedLocalizer::ModelState &state) const {
172 const double robot_speed =
173 (state(kLeftVelocity) + state(kRightVelocity)) / 2.0;
James Kuszmaulf6b69112022-03-12 21:34:39 -0800174 const double lat_speed = (AModel(state) * state)(kTheta)*long_offset_;
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800175 const double velocity_x = std::cos(state(kTheta)) * robot_speed -
176 std::sin(state(kTheta)) * lat_speed;
177 const double velocity_y = std::sin(state(kTheta)) * robot_speed +
178 std::cos(state(kTheta)) * lat_speed;
James Kuszmaul29c59522022-02-12 16:44:26 -0800179 return (AccelState() << state(0), state(1), state(2), velocity_x, velocity_y)
180 .finished();
181}
182
183ModelBasedLocalizer::ModelState ModelBasedLocalizer::ModelStateForAccelState(
184 const ModelBasedLocalizer::AccelState &state,
185 const Eigen::Vector2d &encoders, const double yaw_rate) const {
186 const double robot_speed = state(kVelocityX) * std::cos(state(kTheta)) +
187 state(kVelocityY) * std::sin(state(kTheta));
188 const double radius = dt_config_.robot_radius;
189 const double left_velocity = robot_speed - yaw_rate * radius;
190 const double right_velocity = robot_speed + yaw_rate * radius;
191 return (ModelState() << state(0), state(1), state(2), encoders(0),
192 left_velocity, 0.0, encoders(1), right_velocity, 0.0)
193 .finished();
194}
195
196double ModelBasedLocalizer::ModelDivergence(
197 const ModelBasedLocalizer::CombinedState &state,
198 const ModelBasedLocalizer::AccelInput &accel_inputs,
199 const Eigen::Vector2d &filtered_accel,
200 const ModelBasedLocalizer::ModelInput &model_inputs) {
201 // Convert the model state into the acceleration-based state-space and check
202 // the distance between the two (should really be a weighted norm, but all the
203 // numbers are on ~the same scale).
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800204 // TODO(james): Maybe weight lateral velocity divergence different than
205 // longitudinal? Seems like we tend to get false-positives currently when in
206 // sharp turns.
207 // TODO(james): For off-center gyros, maybe reduce noise when turning?
James Kuszmaul29c59522022-02-12 16:44:26 -0800208 VLOG(2) << "divergence: "
209 << (state.accel_state - AccelStateForModelState(state.model_state))
210 .transpose();
211 const AccelState diff_accel = DiffAccel(state.accel_state, accel_inputs);
212 const ModelState diff_model = DiffModel(state.model_state, model_inputs);
213 const double model_lng_velocity =
214 (state.model_state(kLeftVelocity) + state.model_state(kRightVelocity)) /
215 2.0;
216 const double model_lng_accel =
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800217 (diff_model(kLeftVelocity) + diff_model(kRightVelocity)) / 2.0 -
218 diff_model(kTheta) * diff_model(kTheta) * long_offset_;
219 const double model_lat_accel = diff_model(kTheta) * model_lng_velocity;
220 const Eigen::Vector2d robot_frame_accel(model_lng_accel, model_lat_accel);
James Kuszmaul29c59522022-02-12 16:44:26 -0800221 const Eigen::Vector2d model_accel =
222 Eigen::AngleAxisd(state.model_state(kTheta), Eigen::Vector3d::UnitZ())
223 .toRotationMatrix()
224 .block<2, 2>(0, 0) *
225 robot_frame_accel;
226 const double accel_diff = (model_accel - filtered_accel).norm();
227 const double theta_rate_diff =
228 std::abs(diff_accel(kTheta) - diff_model(kTheta));
229
230 const Eigen::Vector2d accel_vel = state.accel_state.bottomRows<2>();
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800231 Eigen::Vector2d model_vel =
James Kuszmaul29c59522022-02-12 16:44:26 -0800232 AccelStateForModelState(state.model_state).bottomRows<2>();
233 velocity_residual_ = (accel_vel - model_vel).norm() /
234 (1.0 + accel_vel.norm() + model_vel.norm());
235 theta_rate_residual_ = theta_rate_diff;
236 accel_residual_ = accel_diff / 4.0;
237 return velocity_residual_ + theta_rate_residual_ + accel_residual_;
238}
239
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800240void ModelBasedLocalizer::UpdateState(
241 CombinedState *state,
242 const Eigen::Matrix<double, kNModelStates, kNModelOutputs> &K,
243 const Eigen::Matrix<double, kNModelOutputs, 1> &Z,
244 const Eigen::Matrix<double, kNModelOutputs, kNModelStates> &H,
245 const AccelInput &accel_input, const ModelInput &model_input,
246 aos::monotonic_clock::duration dt) {
247 state->accel_state = UpdateAccel(state->accel_state, accel_input, dt);
248 if (down_estimator_.consecutive_still() > 500.0) {
249 state->accel_state(kVelocityX) *= 0.9;
250 state->accel_state(kVelocityY) *= 0.9;
251 }
252 state->model_state = UpdateModel(state->model_state, model_input, dt);
253 state->model_state += K * (Z - H * state->model_state);
254}
255
James Kuszmaul29c59522022-02-12 16:44:26 -0800256void ModelBasedLocalizer::HandleImu(aos::monotonic_clock::time_point t,
257 const Eigen::Vector3d &gyro,
258 const Eigen::Vector3d &accel,
259 const Eigen::Vector2d encoders,
260 const Eigen::Vector2d voltage) {
261 VLOG(2) << t;
262 if (t_ == aos::monotonic_clock::min_time) {
263 t_ = t;
264 }
265 if (t_ + 2 * kNominalDt < t) {
266 t_ = t;
267 ++clock_resets_;
268 }
269 const aos::monotonic_clock::duration dt = t - t_;
270 t_ = t;
271 down_estimator_.Predict(gyro, accel, dt);
272 // TODO(james): Should we prefer this or use the down-estimator corrected
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800273 // version? Using the down estimator is more principled, but does create more
274 // opportunities for subtle biases.
James Kuszmaul29c59522022-02-12 16:44:26 -0800275 const double yaw_rate = (dt_config_.imu_transform * gyro)(2);
276 const double diameter = 2.0 * dt_config_.robot_radius;
277
278 const Eigen::AngleAxis<double> orientation(
279 Eigen::AngleAxis<double>(xytheta()(kTheta), Eigen::Vector3d::UnitZ()) *
280 down_estimator_.X_hat());
James Kuszmaul10d3fd42022-02-25 21:57:36 -0800281 last_orientation_ = orientation;
James Kuszmaul29c59522022-02-12 16:44:26 -0800282
283 const Eigen::Vector3d absolute_accel =
284 orientation * dt_config_.imu_transform * kG * accel;
285 abs_accel_ = absolute_accel;
James Kuszmaul29c59522022-02-12 16:44:26 -0800286
287 VLOG(2) << "abs accel " << absolute_accel.transpose();
James Kuszmaul29c59522022-02-12 16:44:26 -0800288 VLOG(2) << "dt " << aos::time::DurationInSeconds(dt);
289
290 // Update all the branched states.
291 const AccelInput accel_input(absolute_accel.x(), absolute_accel.y(),
292 yaw_rate);
293 const ModelInput model_input(voltage);
294
295 const Eigen::Matrix<double, kNModelStates, kNModelStates> A_continuous =
296 AModel(current_state_.model_state);
297
298 Eigen::Matrix<double, kNModelStates, kNModelStates> A_discrete;
299 Eigen::Matrix<double, kNModelStates, kNModelStates> Q_discrete;
300
301 DiscretizeQAFast(Q_continuous_model_, A_continuous, dt, &Q_discrete,
302 &A_discrete);
303
304 P_model_ = A_discrete * P_model_ * A_discrete.transpose() + Q_discrete;
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800305 P_accel_ = A_discrete_accel_ * P_accel_ * A_discrete_accel_.transpose() +
306 Q_discrete_accel_;
James Kuszmaul29c59522022-02-12 16:44:26 -0800307
308 Eigen::Matrix<double, kNModelOutputs, kNModelStates> H;
309 Eigen::Matrix<double, kNModelOutputs, kNModelOutputs> R;
310 {
311 H.setZero();
312 R.setZero();
313 H(0, kLeftEncoder) = 1.0;
314 H(1, kRightEncoder) = 1.0;
315 H(2, kRightVelocity) = 1.0 / diameter;
316 H(2, kLeftVelocity) = -1.0 / diameter;
317
318 R.diagonal() << 1e-9, 1e-9, 1e-13;
319 }
320
321 const Eigen::Matrix<double, kNModelOutputs, 1> Z(encoders(0), encoders(1),
322 yaw_rate);
323
324 if (branches_.empty()) {
325 VLOG(2) << "Initializing";
James Kuszmaul29c59522022-02-12 16:44:26 -0800326 current_state_.model_state(kLeftEncoder) = encoders(0);
327 current_state_.model_state(kRightEncoder) = encoders(1);
328 current_state_.branch_time = t;
329 branches_.Push(current_state_);
330 }
331
332 const Eigen::Matrix<double, kNModelStates, kNModelOutputs> K =
333 P_model_ * H.transpose() * (H * P_model_ * H.transpose() + R).inverse();
334 P_model_ = (Eigen::Matrix<double, kNModelStates, kNModelStates>::Identity() -
335 K * H) *
336 P_model_;
337 VLOG(2) << "K\n" << K;
338 VLOG(2) << "Z\n" << Z.transpose();
339
340 for (CombinedState &state : branches_) {
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800341 UpdateState(&state, K, Z, H, accel_input, model_input, dt);
James Kuszmaul29c59522022-02-12 16:44:26 -0800342 }
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800343 UpdateState(&current_state_, K, Z, H, accel_input, model_input, dt);
James Kuszmaul29c59522022-02-12 16:44:26 -0800344
345 VLOG(2) << "oildest accel " << branches_[0].accel_state.transpose();
346 VLOG(2) << "oildest accel diff "
347 << DiffAccel(branches_[0].accel_state, accel_input).transpose();
348 VLOG(2) << "oildest model " << branches_[0].model_state.transpose();
349
350 // Determine whether to switch modes--if we are currently in model-based mode,
351 // swap to accel-based if the two states have divergeed meaningfully in the
352 // oldest branch. If we are currently in accel-based, then swap back to model
353 // if the oldest model branch matches has matched the
354 filtered_residual_accel_ +=
355 0.01 * (accel_input.topRows<2>() - filtered_residual_accel_);
356 const double model_divergence =
357 branches_.full() ? ModelDivergence(branches_[0], accel_input,
358 filtered_residual_accel_, model_input)
359 : 0.0;
360 filtered_residual_ +=
361 (1.0 - std::exp(-aos::time::DurationInSeconds(kNominalDt) / 0.0095)) *
362 (model_divergence - filtered_residual_);
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800363 // TODO(james): Tune this more. Currently set to generally trust the model,
364 // perhaps a bit too much.
365 // When the residual exceeds the accel threshold, we start using the inertials
366 // alone; when it drops back below the model threshold, we go back to being
367 // model-based.
368 constexpr double kUseAccelThreshold = 2.0;
369 constexpr double kUseModelThreshold = 0.5;
James Kuszmaul29c59522022-02-12 16:44:26 -0800370 constexpr size_t kShareStates = kNModelStates;
371 static_assert(kUseModelThreshold < kUseAccelThreshold);
372 if (using_model_) {
373 if (filtered_residual_ > kUseAccelThreshold) {
374 hysteresis_count_++;
375 } else {
376 hysteresis_count_ = 0;
377 }
378 if (hysteresis_count_ > 0) {
379 using_model_ = false;
380 // Grab the accel-based state from back when we started diverging.
381 // TODO(james): This creates a problematic selection bias, because
382 // we will tend to bias towards deliberately out-of-tune measurements.
383 current_state_.accel_state = branches_[0].accel_state;
384 current_state_.model_state = branches_[0].model_state;
385 current_state_.model_state = ModelStateForAccelState(
386 current_state_.accel_state, encoders, yaw_rate);
387 } else {
388 VLOG(2) << "Normal branching";
James Kuszmaul29c59522022-02-12 16:44:26 -0800389 current_state_.accel_state =
390 AccelStateForModelState(current_state_.model_state);
391 current_state_.branch_time = t;
392 }
393 hysteresis_count_ = 0;
394 } else {
395 if (filtered_residual_ < kUseModelThreshold) {
396 hysteresis_count_++;
397 } else {
398 hysteresis_count_ = 0;
399 }
400 if (hysteresis_count_ > 100) {
401 using_model_ = true;
402 // Grab the model-based state from back when we stopped diverging.
403 current_state_.model_state.topRows<kShareStates>() =
404 ModelStateForAccelState(branches_[0].accel_state, encoders, yaw_rate)
405 .topRows<kShareStates>();
406 current_state_.accel_state =
407 AccelStateForModelState(current_state_.model_state);
408 } else {
James Kuszmaul29c59522022-02-12 16:44:26 -0800409 // TODO(james): Why was I leaving the encoders/wheel velocities in place?
James Kuszmaul29c59522022-02-12 16:44:26 -0800410 current_state_.model_state = ModelStateForAccelState(
411 current_state_.accel_state, encoders, yaw_rate);
412 current_state_.branch_time = t;
413 }
414 }
415
416 // Generate a new branch, with the accel state reset based on the model-based
417 // state (really, just getting rid of the lateral velocity).
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800418 // By resetting the accel state in the new branch, this tries to minimize the
419 // odds of runaway lateral velocities. This doesn't help with runaway
420 // longitudinal velocities, however.
James Kuszmaul29c59522022-02-12 16:44:26 -0800421 CombinedState new_branch = current_state_;
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800422 new_branch.accel_state = AccelStateForModelState(new_branch.model_state);
James Kuszmaul29c59522022-02-12 16:44:26 -0800423 new_branch.accumulated_divergence = 0.0;
424
James Kuszmaul93825a02022-02-13 16:50:33 -0800425 ++branch_counter_;
426 if (branch_counter_ % kBranchPeriod == 0) {
427 branches_.Push(new_branch);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800428 old_positions_.Push(OldPosition{t, xytheta(), latest_turret_position_,
429 latest_turret_velocity_});
James Kuszmaul93825a02022-02-13 16:50:33 -0800430 branch_counter_ = 0;
431 }
James Kuszmaul29c59522022-02-12 16:44:26 -0800432
433 last_residual_ = model_divergence;
434
435 VLOG(2) << "Using " << (using_model_ ? "model" : "accel");
436 VLOG(2) << "Residual " << last_residual_;
437 VLOG(2) << "Filtered Residual " << filtered_residual_;
438 VLOG(2) << "buffer size " << branches_.size();
439 VLOG(2) << "Model state " << current_state_.model_state.transpose();
440 VLOG(2) << "Accel state " << current_state_.accel_state.transpose();
441 VLOG(2) << "Accel state for model "
James Kuszmaulf6b69112022-03-12 21:34:39 -0800442 << AccelStateForModelState(current_state_.model_state).transpose();
James Kuszmaul29c59522022-02-12 16:44:26 -0800443 VLOG(2) << "Input acce " << accel.transpose();
444 VLOG(2) << "Input gyro " << gyro.transpose();
445 VLOG(2) << "Input voltage " << voltage.transpose();
446 VLOG(2) << "Input encoder " << encoders.transpose();
447 VLOG(2) << "yaw rate " << yaw_rate;
448
449 CHECK(std::isfinite(last_residual_));
450}
451
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800452const ModelBasedLocalizer::OldPosition ModelBasedLocalizer::GetStateForTime(
453 aos::monotonic_clock::time_point time) {
454 if (old_positions_.empty()) {
455 return OldPosition{};
456 }
457
458 aos::monotonic_clock::duration lowest_time_error =
459 aos::monotonic_clock::duration::max();
460 const OldPosition *best_match = nullptr;
461 for (const OldPosition &sample : old_positions_) {
462 const aos::monotonic_clock::duration time_error =
463 std::chrono::abs(sample.sample_time - time);
464 if (time_error < lowest_time_error) {
465 lowest_time_error = time_error;
466 best_match = &sample;
467 }
468 }
469 return *best_match;
470}
471
472namespace {
473// Converts a flatbuffer TransformationMatrix to an Eigen matrix. Technically,
474// this should be able to do a single memcpy, but the extra verbosity here seems
475// appropriate.
476Eigen::Matrix<double, 4, 4> FlatbufferToTransformationMatrix(
477 const frc971::vision::calibration::TransformationMatrix &flatbuffer) {
478 CHECK_EQ(16u, CHECK_NOTNULL(flatbuffer.data())->size());
479 Eigen::Matrix<double, 4, 4> result;
480 result.setIdentity();
481 for (int row = 0; row < 4; ++row) {
482 for (int col = 0; col < 4; ++col) {
483 result(row, col) = (*flatbuffer.data())[row * 4 + col];
484 }
485 }
486 return result;
487}
488
489// Node names of the pis to listen for cameras from.
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800490const std::array<std::string_view, 4> kPisToUse{"pi1", "pi2", "pi3", "pi4"};
James Kuszmaulf6b69112022-03-12 21:34:39 -0800491} // namespace
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800492
493const Eigen::Matrix<double, 4, 4> ModelBasedLocalizer::CameraTransform(
494 const OldPosition &state,
495 const frc971::vision::calibration::CameraCalibration *calibration,
496 std::optional<RejectionReason> *rejection_reason) const {
497 CHECK_NOTNULL(rejection_reason);
498 CHECK_NOTNULL(calibration);
499 // Per the CameraCalibration specification, we can actually determine whether
500 // the camera is the turret camera just from the presence of the
501 // turret_extrinsics member.
502 const bool is_turret = calibration->has_turret_extrinsics();
503 // Ignore readings when the turret is spinning too fast, on the assumption
504 // that the odds of screwing up the time compensation are higher.
505 // Note that the current number here is chosen pretty arbitrarily--1 rad / sec
506 // seems reasonable, but may be unnecessarily low or high.
507 constexpr double kMaxTurretVelocity = 1.0;
508 if (is_turret && std::abs(state.turret_velocity) > kMaxTurretVelocity &&
509 !rejection_reason->has_value()) {
510 *rejection_reason = RejectionReason::TURRET_TOO_FAST;
511 }
512 CHECK(calibration->has_fixed_extrinsics());
513 const Eigen::Matrix<double, 4, 4> fixed_extrinsics =
514 FlatbufferToTransformationMatrix(*calibration->fixed_extrinsics());
515
516 // Calculate the pose of the camera relative to the robot origin.
517 Eigen::Matrix<double, 4, 4> H_robot_camera = fixed_extrinsics;
518 if (is_turret) {
519 H_robot_camera =
520 H_robot_camera *
521 frc971::control_loops::TransformationMatrixForYaw<double>(
522 state.turret_position) *
523 FlatbufferToTransformationMatrix(*calibration->turret_extrinsics());
524 }
525 return H_robot_camera;
526}
527
528const std::optional<Eigen::Vector2d>
529ModelBasedLocalizer::CameraMeasuredRobotPosition(
530 const OldPosition &state, const y2022::vision::TargetEstimate *target,
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800531 std::optional<RejectionReason> *rejection_reason,
532 Eigen::Matrix<double, 4, 4> *H_field_camera_measured) const {
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800533 if (!target->has_camera_calibration()) {
534 *rejection_reason = RejectionReason::NO_CALIBRATION;
535 return std::nullopt;
536 }
537 const Eigen::Matrix<double, 4, 4> H_robot_camera =
538 CameraTransform(state, target->camera_calibration(), rejection_reason);
539 const control_loops::Pose robot_pose(
540 {state.xytheta(0), state.xytheta(1), 0.0}, state.xytheta(2));
541 const Eigen::Matrix<double, 4, 4> H_field_robot =
542 robot_pose.AsTransformationMatrix();
543 // Current estimated pose of the camera in the global frame.
544 // Note that this is all really just an elaborate way of extracting the
545 // current estimated camera yaw, and nothing else.
546 const Eigen::Matrix<double, 4, 4> H_field_camera =
547 H_field_robot * H_robot_camera;
548 // Grab the implied yaw of the camera (the +Z axis is coming out of the front
549 // of the cameras).
550 const Eigen::Vector3d rotated_camera_z =
551 H_field_camera.block<3, 3>(0, 0) * Eigen::Vector3d(0, 0, 1);
552 const double camera_yaw =
553 std::atan2(rotated_camera_z.y(), rotated_camera_z.x());
554 // All right, now we need to use the heading and distance from the
555 // TargetEstimate, plus the yaw embedded in the camera_pose, to determine what
556 // the implied X/Y position of the robot is. To do this, we calculate the
557 // heading/distance from the target to the robot. The distance is easy, since
558 // that's the same as the distance from the robot to the target. The heading
559 // isn't too hard, but is obnoxious to think about, since the heading from the
560 // target to the robot is distinct from the heading from the robot to the
561 // target.
562
563 // Just to walk through examples to confirm that the below calculation is
564 // correct:
565 // * If yaw = 0, and angle_to_target = 0, we are at 180 deg relative to the
566 // target.
567 // * If yaw = 90 deg, and angle_to_target = 0, we are at -90 deg relative to
568 // the target.
569 // * If yaw = 0, and angle_to_target = 90 deg, we are at -90 deg relative to
570 // the target.
571 const double heading_from_target =
572 aos::math::NormalizeAngle(M_PI + camera_yaw + target->angle_to_target());
573 const double distance_from_target = target->distance();
574 // Extract the implied camera position on the field.
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800575 *H_field_camera_measured = H_field_camera;
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800576 // TODO(james): Are we going to need to evict the roll/pitch components of the
577 // camera extrinsics this year as well?
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800578 (*H_field_camera_measured)(0, 3) =
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800579 distance_from_target * std::cos(heading_from_target) + kVisionTargetX;
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800580 (*H_field_camera_measured)(1, 3) =
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800581 distance_from_target * std::sin(heading_from_target) + kVisionTargetY;
582 const Eigen::Matrix<double, 4, 4> H_field_robot_measured =
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800583 *H_field_camera_measured * H_robot_camera.inverse();
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800584 return H_field_robot_measured.block<2, 1>(0, 3);
585}
586
587void ModelBasedLocalizer::HandleImageMatch(
588 aos::monotonic_clock::time_point sample_time,
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800589 const y2022::vision::TargetEstimate *target, int camera_index) {
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800590 std::optional<RejectionReason> rejection_reason;
591
James Kuszmaulaa39d962022-03-06 14:54:28 -0800592 if (target->confidence() < kMinTargetEstimateConfidence) {
593 rejection_reason = RejectionReason::LOW_CONFIDENCE;
594 TallyRejection(rejection_reason.value());
595 return;
596 }
597
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800598 const OldPosition &state = GetStateForTime(sample_time);
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800599 Eigen::Matrix<double, 4, 4> H_field_camera_measured;
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800600 const std::optional<Eigen::Vector2d> measured_robot_position =
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800601 CameraMeasuredRobotPosition(state, target, &rejection_reason,
602 &H_field_camera_measured);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800603 // Technically, rejection_reason should always be set if
604 // measured_robot_position is nullopt, but in the future we may have more
605 // recoverable rejection reasons that we wish to allow to propagate further
606 // into the process.
607 if (!measured_robot_position || rejection_reason.has_value()) {
608 CHECK(rejection_reason.has_value());
609 TallyRejection(rejection_reason.value());
610 return;
611 }
612
613 // Next, go through and do the actual Kalman corrections for the x/y
614 // measurement, for both the accel state and the model-based state.
615 const Eigen::Matrix<double, kNModelStates, kNModelStates> A_continuous_model =
616 AModel(current_state_.model_state);
617
618 Eigen::Matrix<double, kNModelStates, kNModelStates> A_discrete_model;
619 Eigen::Matrix<double, kNModelStates, kNModelStates> Q_discrete_model;
620
621 DiscretizeQAFast(Q_continuous_model_, A_continuous_model, kNominalDt,
622 &Q_discrete_model, &A_discrete_model);
623
624 Eigen::Matrix<double, 2, kNModelStates> H_model;
625 H_model.setZero();
626 Eigen::Matrix<double, 2, kNAccelStates> H_accel;
627 H_accel.setZero();
628 Eigen::Matrix<double, 2, 2> R;
629 R.setZero();
630 H_model(0, kX) = 1.0;
631 H_model(1, kY) = 1.0;
632 H_accel(0, kX) = 1.0;
633 H_accel(1, kY) = 1.0;
634 R.diagonal() << 1e-2, 1e-2;
635
636 const Eigen::Matrix<double, kNModelStates, 2> K_model =
637 P_model_ * H_model.transpose() *
638 (H_model * P_model_ * H_model.transpose() + R).inverse();
639 const Eigen::Matrix<double, kNAccelStates, 2> K_accel =
640 P_accel_ * H_accel.transpose() *
641 (H_accel * P_accel_ * H_accel.transpose() + R).inverse();
642 P_model_ = (Eigen::Matrix<double, kNModelStates, kNModelStates>::Identity() -
643 K_model * H_model) *
644 P_model_;
645 P_accel_ = (Eigen::Matrix<double, kNAccelStates, kNAccelStates>::Identity() -
646 K_accel * H_accel) *
647 P_accel_;
648 // And now we have to correct *everything* on all the branches:
649 for (CombinedState &state : branches_) {
650 state.model_state += K_model * (measured_robot_position.value() -
James Kuszmaulf6b69112022-03-12 21:34:39 -0800651 H_model * state.model_state);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800652 state.accel_state += K_accel * (measured_robot_position.value() -
James Kuszmaulf6b69112022-03-12 21:34:39 -0800653 H_accel * state.accel_state);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800654 }
655 current_state_.model_state +=
656 K_model *
657 (measured_robot_position.value() - H_model * current_state_.model_state);
658 current_state_.accel_state +=
659 K_accel *
660 (measured_robot_position.value() - H_accel * current_state_.accel_state);
661
662 statistics_.total_accepted++;
663 statistics_.total_candidates++;
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800664
665 const Eigen::Vector3d camera_z_in_field =
666 H_field_camera_measured.block<3, 3>(0, 0) * Eigen::Vector3d::UnitZ();
667 const double camera_yaw =
668 std::atan2(camera_z_in_field.y(), camera_z_in_field.x());
669
670 TargetEstimateDebugT debug;
671 debug.camera = static_cast<uint8_t>(camera_index);
672 debug.camera_x = H_field_camera_measured(0, 3);
673 debug.camera_y = H_field_camera_measured(1, 3);
674 debug.camera_theta = camera_yaw;
675 debug.implied_robot_x = measured_robot_position.value().x();
676 debug.implied_robot_y = measured_robot_position.value().y();
677 debug.implied_robot_theta = xytheta()(2);
678 debug.implied_turret_goal =
679 aos::math::NormalizeAngle(camera_yaw + target->angle_to_target());
680 debug.accepted = true;
681 debug.image_age_sec = aos::time::DurationInSeconds(t_ - sample_time);
James Kuszmaul2b2f8772022-03-12 15:25:35 -0800682 CHECK_LT(image_debugs_.size(), kDebugBufferSize);
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800683 image_debugs_.push_back(debug);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800684}
685
686void ModelBasedLocalizer::HandleTurret(
687 aos::monotonic_clock::time_point sample_time, double turret_position,
688 double turret_velocity) {
689 last_turret_update_ = sample_time;
690 latest_turret_position_ = turret_position;
691 latest_turret_velocity_ = turret_velocity;
692}
693
James Kuszmaul29c59522022-02-12 16:44:26 -0800694void ModelBasedLocalizer::HandleReset(aos::monotonic_clock::time_point now,
695 const Eigen::Vector3d &xytheta) {
696 branches_.Reset();
James Kuszmaulf6b69112022-03-12 21:34:39 -0800697 t_ = now;
James Kuszmaul29c59522022-02-12 16:44:26 -0800698 using_model_ = true;
699 current_state_.model_state << xytheta(0), xytheta(1), xytheta(2),
700 current_state_.model_state(kLeftEncoder), 0.0, 0.0,
701 current_state_.model_state(kRightEncoder), 0.0, 0.0;
702 current_state_.accel_state =
703 AccelStateForModelState(current_state_.model_state);
704 last_residual_ = 0.0;
705 filtered_residual_ = 0.0;
706 filtered_residual_accel_.setZero();
707 abs_accel_.setZero();
708}
709
710flatbuffers::Offset<AccelBasedState> ModelBasedLocalizer::BuildAccelState(
711 flatbuffers::FlatBufferBuilder *fbb, const AccelState &state) {
712 AccelBasedState::Builder accel_state_builder(*fbb);
713 accel_state_builder.add_x(state(kX));
714 accel_state_builder.add_y(state(kY));
715 accel_state_builder.add_theta(state(kTheta));
716 accel_state_builder.add_velocity_x(state(kVelocityX));
717 accel_state_builder.add_velocity_y(state(kVelocityY));
718 return accel_state_builder.Finish();
719}
720
721flatbuffers::Offset<ModelBasedState> ModelBasedLocalizer::BuildModelState(
722 flatbuffers::FlatBufferBuilder *fbb, const ModelState &state) {
723 ModelBasedState::Builder model_state_builder(*fbb);
724 model_state_builder.add_x(state(kX));
725 model_state_builder.add_y(state(kY));
726 model_state_builder.add_theta(state(kTheta));
727 model_state_builder.add_left_encoder(state(kLeftEncoder));
728 model_state_builder.add_left_velocity(state(kLeftVelocity));
729 model_state_builder.add_left_voltage_error(state(kLeftVoltageError));
730 model_state_builder.add_right_encoder(state(kRightEncoder));
731 model_state_builder.add_right_velocity(state(kRightVelocity));
732 model_state_builder.add_right_voltage_error(state(kRightVoltageError));
733 return model_state_builder.Finish();
734}
735
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800736flatbuffers::Offset<CumulativeStatistics>
737ModelBasedLocalizer::PopulateStatistics(flatbuffers::FlatBufferBuilder *fbb) {
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800738 const auto rejections_offset = fbb->CreateVector(
739 statistics_.rejection_counts.data(), statistics_.rejection_counts.size());
740
741 CumulativeStatistics::Builder stats_builder(*fbb);
742 stats_builder.add_total_accepted(statistics_.total_accepted);
743 stats_builder.add_total_candidates(statistics_.total_candidates);
744 stats_builder.add_rejection_reason_count(rejections_offset);
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800745 return stats_builder.Finish();
746}
747
748flatbuffers::Offset<ModelBasedStatus> ModelBasedLocalizer::PopulateStatus(
749 flatbuffers::FlatBufferBuilder *fbb) {
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800750 const flatbuffers::Offset<CumulativeStatistics> stats_offset =
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800751 PopulateStatistics(fbb);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800752
James Kuszmaul29c59522022-02-12 16:44:26 -0800753 const flatbuffers::Offset<control_loops::drivetrain::DownEstimatorState>
754 down_estimator_offset = down_estimator_.PopulateStatus(fbb, t_);
755
756 const CombinedState &state = current_state_;
757
758 const flatbuffers::Offset<ModelBasedState> model_state_offset =
James Kuszmaulf6b69112022-03-12 21:34:39 -0800759 BuildModelState(fbb, state.model_state);
James Kuszmaul29c59522022-02-12 16:44:26 -0800760
761 const flatbuffers::Offset<AccelBasedState> accel_state_offset =
762 BuildAccelState(fbb, state.accel_state);
763
764 const flatbuffers::Offset<AccelBasedState> oldest_accel_state_offset =
765 branches_.empty() ? flatbuffers::Offset<AccelBasedState>()
766 : BuildAccelState(fbb, branches_[0].accel_state);
767
768 const flatbuffers::Offset<ModelBasedState> oldest_model_state_offset =
769 branches_.empty() ? flatbuffers::Offset<ModelBasedState>()
770 : BuildModelState(fbb, branches_[0].model_state);
771
772 ModelBasedStatus::Builder builder(*fbb);
773 builder.add_accel_state(accel_state_offset);
774 builder.add_oldest_accel_state(oldest_accel_state_offset);
775 builder.add_oldest_model_state(oldest_model_state_offset);
776 builder.add_model_state(model_state_offset);
777 builder.add_using_model(using_model_);
778 builder.add_residual(last_residual_);
779 builder.add_filtered_residual(filtered_residual_);
780 builder.add_velocity_residual(velocity_residual_);
781 builder.add_accel_residual(accel_residual_);
782 builder.add_theta_rate_residual(theta_rate_residual_);
783 builder.add_down_estimator(down_estimator_offset);
784 builder.add_x(xytheta()(0));
785 builder.add_y(xytheta()(1));
786 builder.add_theta(xytheta()(2));
787 builder.add_implied_accel_x(abs_accel_(0));
788 builder.add_implied_accel_y(abs_accel_(1));
789 builder.add_implied_accel_z(abs_accel_(2));
790 builder.add_clock_resets(clock_resets_);
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800791 builder.add_statistics(stats_offset);
James Kuszmaul29c59522022-02-12 16:44:26 -0800792 return builder.Finish();
793}
794
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800795flatbuffers::Offset<LocalizerVisualization>
796ModelBasedLocalizer::PopulateVisualization(
797 flatbuffers::FlatBufferBuilder *fbb) {
798 const flatbuffers::Offset<CumulativeStatistics> stats_offset =
799 PopulateStatistics(fbb);
800
801 aos::SizedArray<flatbuffers::Offset<TargetEstimateDebug>, kDebugBufferSize>
802 debug_offsets;
803
James Kuszmaulf6b69112022-03-12 21:34:39 -0800804 for (const TargetEstimateDebugT &debug : image_debugs_) {
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800805 debug_offsets.push_back(PackTargetEstimateDebug(debug, fbb));
806 }
807
808 image_debugs_.clear();
809
810 const flatbuffers::Offset<
811 flatbuffers::Vector<flatbuffers::Offset<TargetEstimateDebug>>>
812 debug_offset =
813 fbb->CreateVector(debug_offsets.data(), debug_offsets.size());
814
815 LocalizerVisualization::Builder builder(*fbb);
816 builder.add_statistics(stats_offset);
817 builder.add_targets(debug_offset);
818 return builder.Finish();
819}
820
821void ModelBasedLocalizer::TallyRejection(const RejectionReason reason) {
822 statistics_.total_candidates++;
823 statistics_.rejection_counts[static_cast<size_t>(reason)]++;
824 TargetEstimateDebugT debug;
825 debug.accepted = false;
826 debug.rejection_reason = reason;
James Kuszmaul2b2f8772022-03-12 15:25:35 -0800827 CHECK_LT(image_debugs_.size(), kDebugBufferSize);
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800828 image_debugs_.push_back(debug);
829}
830
831flatbuffers::Offset<TargetEstimateDebug>
832ModelBasedLocalizer::PackTargetEstimateDebug(
833 const TargetEstimateDebugT &debug, flatbuffers::FlatBufferBuilder *fbb) {
834 if (!debug.accepted) {
835 TargetEstimateDebug::Builder builder(*fbb);
836 builder.add_accepted(debug.accepted);
837 builder.add_rejection_reason(debug.rejection_reason);
838 return builder.Finish();
839 } else {
840 flatbuffers::Offset<TargetEstimateDebug> offset =
841 TargetEstimateDebug::Pack(*fbb, &debug);
842 flatbuffers::GetMutableTemporaryPointer(*fbb, offset)
843 ->clear_rejection_reason();
844 return offset;
845 }
846}
847
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800848namespace {
849// Period at which the encoder readings from the IMU board wrap.
850static double DrivetrainWrapPeriod() {
851 return y2022::constants::Values::DrivetrainEncoderToMeters(1 << 16);
852}
James Kuszmaulf6b69112022-03-12 21:34:39 -0800853} // namespace
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800854
James Kuszmaul29c59522022-02-12 16:44:26 -0800855EventLoopLocalizer::EventLoopLocalizer(
856 aos::EventLoop *event_loop,
857 const control_loops::drivetrain::DrivetrainConfig<double> &dt_config)
858 : event_loop_(event_loop),
859 model_based_(dt_config),
860 status_sender_(event_loop_->MakeSender<LocalizerStatus>("/localizer")),
861 output_sender_(event_loop_->MakeSender<LocalizerOutput>("/localizer")),
James Kuszmaul0dedb5e2022-03-05 16:02:20 -0800862 visualization_sender_(
863 event_loop_->MakeSender<LocalizerVisualization>("/localizer")),
James Kuszmaul29c59522022-02-12 16:44:26 -0800864 output_fetcher_(
865 event_loop_->MakeFetcher<frc971::control_loops::drivetrain::Output>(
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800866 "/drivetrain")),
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800867 clock_offset_fetcher_(
868 event_loop_->MakeFetcher<aos::message_bridge::ServerStatistics>(
869 "/aos")),
James Kuszmaulf6b69112022-03-12 21:34:39 -0800870 superstructure_fetcher_(
871 event_loop_
872 ->MakeFetcher<y2022::control_loops::superstructure::Status>(
873 "/superstructure")),
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800874 left_encoder_(-DrivetrainWrapPeriod() / 2.0, DrivetrainWrapPeriod()),
875 right_encoder_(-DrivetrainWrapPeriod() / 2.0, DrivetrainWrapPeriod()) {
James Kuszmaul29c59522022-02-12 16:44:26 -0800876 event_loop_->MakeWatcher(
877 "/drivetrain",
878 [this](
879 const frc971::control_loops::drivetrain::LocalizerControl &control) {
880 const double theta = control.keep_current_theta()
881 ? model_based_.xytheta()(2)
882 : control.theta();
883 model_based_.HandleReset(event_loop_->monotonic_now(),
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800884 {control.x(), control.y(), theta});
James Kuszmaul29c59522022-02-12 16:44:26 -0800885 });
James Kuszmaul2b2f8772022-03-12 15:25:35 -0800886 aos::TimerHandler *superstructure_timer = event_loop_->AddTimer([this]() {
887 if (superstructure_fetcher_.Fetch()) {
888 const y2022::control_loops::superstructure::Status &status =
889 *superstructure_fetcher_.get();
890 if (!status.has_turret()) {
891 return;
892 }
893 CHECK(status.has_turret());
894 model_based_.HandleTurret(
895 superstructure_fetcher_.context().monotonic_event_time,
896 status.turret()->position(), status.turret()->velocity());
897 }
898 });
899 event_loop_->OnRun([this, superstructure_timer]() {
900 superstructure_timer->Setup(event_loop_->monotonic_now(),
901 std::chrono::milliseconds(20));
902 });
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800903
James Kuszmaulf6b69112022-03-12 21:34:39 -0800904 for (size_t camera_index = 0; camera_index < kPisToUse.size();
905 ++camera_index) {
James Kuszmaul2b2f8772022-03-12 15:25:35 -0800906 CHECK_LT(camera_index, target_estimate_fetchers_.size());
907 target_estimate_fetchers_[camera_index] =
908 event_loop_->MakeFetcher<y2022::vision::TargetEstimate>(
909 absl::StrCat("/", kPisToUse[camera_index], "/camera"));
910 }
James Kuszmaulf6b69112022-03-12 21:34:39 -0800911 aos::TimerHandler *estimate_timer = event_loop_->AddTimer([this]() {
912 for (size_t camera_index = 0; camera_index < kPisToUse.size();
913 ++camera_index) {
914 if (model_based_.NumQueuedImageDebugs() ==
915 ModelBasedLocalizer::kDebugBufferSize ||
916 (last_visualization_send_ + kMinVisualizationPeriod <
917 event_loop_->monotonic_now())) {
918 auto builder = visualization_sender_.MakeBuilder();
919 visualization_sender_.CheckOk(
920 builder.Send(model_based_.PopulateVisualization(builder.fbb())));
921 }
922 if (target_estimate_fetchers_[camera_index].Fetch()) {
923 const std::optional<aos::monotonic_clock::duration> monotonic_offset =
924 ClockOffset(kPisToUse[camera_index]);
925 if (!monotonic_offset.has_value()) {
926 continue;
James Kuszmaul2b2f8772022-03-12 15:25:35 -0800927 }
James Kuszmaulf6b69112022-03-12 21:34:39 -0800928 // TODO(james): Get timestamp from message contents.
929 aos::monotonic_clock::time_point capture_time(
930 target_estimate_fetchers_[camera_index]
931 .context()
932 .monotonic_remote_time -
933 monotonic_offset.value());
934 if (capture_time > target_estimate_fetchers_[camera_index]
935 .context()
936 .monotonic_event_time) {
937 model_based_.TallyRejection(RejectionReason::IMAGE_FROM_FUTURE);
938 continue;
939 }
940 model_based_.HandleImageMatch(
941 capture_time, target_estimate_fetchers_[camera_index].get(),
942 camera_index);
943 }
944 }
945 });
James Kuszmaul2b2f8772022-03-12 15:25:35 -0800946 event_loop_->OnRun([this, estimate_timer]() {
947 estimate_timer->Setup(event_loop_->monotonic_now(),
948 std::chrono::milliseconds(100));
949 });
James Kuszmaul8c4f6592022-02-26 15:49:30 -0800950 event_loop_->MakeWatcher(
James Kuszmaul29c59522022-02-12 16:44:26 -0800951 "/localizer", [this](const frc971::IMUValuesBatch &values) {
952 CHECK(values.has_readings());
James Kuszmaul29c59522022-02-12 16:44:26 -0800953 output_fetcher_.Fetch();
954 for (const IMUValues *value : *values.readings()) {
955 zeroer_.InsertAndProcessMeasurement(*value);
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800956 const Eigen::Vector2d encoders{
957 left_encoder_.Unwrap(value->left_encoder()),
958 right_encoder_.Unwrap(value->right_encoder())};
James Kuszmaul29c59522022-02-12 16:44:26 -0800959 if (zeroer_.Zeroed()) {
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800960 const aos::monotonic_clock::time_point pico_timestamp{
961 std::chrono::microseconds(value->pico_timestamp_us())};
962 // TODO(james): If we get large enough drift off of the pico,
963 // actually do something about it.
964 if (!pico_offset_.has_value()) {
965 pico_offset_ =
966 event_loop_->context().monotonic_event_time - pico_timestamp;
967 last_pico_timestamp_ = pico_timestamp;
James Kuszmaule5f67dd2022-02-12 20:08:29 -0800968 }
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800969 if (pico_timestamp < last_pico_timestamp_) {
970 pico_offset_.value() += std::chrono::microseconds(1ULL << 32);
971 }
972 const aos::monotonic_clock::time_point sample_timestamp =
973 pico_offset_.value() + pico_timestamp;
974 pico_offset_error_ =
975 event_loop_->context().monotonic_event_time - sample_timestamp;
976 const bool disabled =
977 (output_fetcher_.get() == nullptr) ||
978 (output_fetcher_.context().monotonic_event_time +
979 std::chrono::milliseconds(10) <
980 event_loop_->context().monotonic_event_time);
981 model_based_.HandleImu(
James Kuszmaulf6b69112022-03-12 21:34:39 -0800982 sample_timestamp, zeroer_.ZeroedGyro(), zeroer_.ZeroedAccel(),
983 encoders,
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800984 disabled ? Eigen::Vector2d::Zero()
985 : Eigen::Vector2d{output_fetcher_->left_voltage(),
986 output_fetcher_->right_voltage()});
987 last_pico_timestamp_ = pico_timestamp;
James Kuszmaul29c59522022-02-12 16:44:26 -0800988 }
989 {
990 auto builder = status_sender_.MakeBuilder();
991 const flatbuffers::Offset<ModelBasedStatus> model_based_status =
992 model_based_.PopulateStatus(builder.fbb());
James Kuszmaul5ed29dd2022-02-13 18:32:06 -0800993 const flatbuffers::Offset<control_loops::drivetrain::ImuZeroerState>
994 zeroer_status = zeroer_.PopulateStatus(builder.fbb());
James Kuszmaul29c59522022-02-12 16:44:26 -0800995 LocalizerStatus::Builder status_builder =
996 builder.MakeBuilder<LocalizerStatus>();
997 status_builder.add_model_based(model_based_status);
998 status_builder.add_zeroed(zeroer_.Zeroed());
999 status_builder.add_faulted_zero(zeroer_.Faulted());
James Kuszmaul5ed29dd2022-02-13 18:32:06 -08001000 status_builder.add_zeroing(zeroer_status);
1001 status_builder.add_left_encoder(encoders(0));
1002 status_builder.add_right_encoder(encoders(1));
1003 if (pico_offset_.has_value()) {
1004 status_builder.add_pico_offset_ns(pico_offset_.value().count());
1005 status_builder.add_pico_offset_error_ns(
1006 pico_offset_error_.count());
1007 }
James Kuszmaul29c59522022-02-12 16:44:26 -08001008 builder.CheckOk(builder.Send(status_builder.Finish()));
1009 }
1010 if (last_output_send_ + std::chrono::milliseconds(5) <
1011 event_loop_->context().monotonic_event_time) {
1012 auto builder = output_sender_.MakeBuilder();
1013 LocalizerOutput::Builder output_builder =
1014 builder.MakeBuilder<LocalizerOutput>();
James Kuszmaul1798c072022-02-13 15:32:11 -08001015 // TODO(james): Should we bother to try to estimate time offsets for
1016 // the pico?
1017 output_builder.add_monotonic_timestamp_ns(
1018 value->monotonic_timestamp_ns());
James Kuszmaul29c59522022-02-12 16:44:26 -08001019 output_builder.add_x(model_based_.xytheta()(0));
1020 output_builder.add_y(model_based_.xytheta()(1));
1021 output_builder.add_theta(model_based_.xytheta()(2));
James Kuszmaulf3ef9e12022-03-05 17:13:00 -08001022 output_builder.add_zeroed(zeroer_.Zeroed());
James Kuszmaul10d3fd42022-02-25 21:57:36 -08001023 const Eigen::Quaterniond &orientation = model_based_.orientation();
1024 Quaternion quaternion;
1025 quaternion.mutate_x(orientation.x());
1026 quaternion.mutate_y(orientation.y());
1027 quaternion.mutate_z(orientation.z());
1028 quaternion.mutate_w(orientation.w());
1029 output_builder.add_orientation(&quaternion);
James Kuszmaul29c59522022-02-12 16:44:26 -08001030 builder.CheckOk(builder.Send(output_builder.Finish()));
1031 last_output_send_ = event_loop_->monotonic_now();
1032 }
1033 }
1034 });
1035}
1036
James Kuszmaul8c4f6592022-02-26 15:49:30 -08001037std::optional<aos::monotonic_clock::duration> EventLoopLocalizer::ClockOffset(
1038 std::string_view pi) {
1039 std::optional<aos::monotonic_clock::duration> monotonic_offset;
1040 clock_offset_fetcher_.Fetch();
1041 if (clock_offset_fetcher_.get() != nullptr) {
1042 for (const auto connection : *clock_offset_fetcher_->connections()) {
1043 if (connection->has_node() && connection->node()->has_name() &&
1044 connection->node()->name()->string_view() == pi) {
1045 if (connection->has_monotonic_offset()) {
1046 monotonic_offset =
1047 std::chrono::nanoseconds(connection->monotonic_offset());
1048 } else {
1049 // If we don't have a monotonic offset, that means we aren't
1050 // connected.
1051 model_based_.TallyRejection(
1052 RejectionReason::MESSAGE_BRIDGE_DISCONNECTED);
1053 return std::nullopt;
1054 }
1055 break;
1056 }
1057 }
1058 }
1059 CHECK(monotonic_offset.has_value());
1060 return monotonic_offset;
1061}
1062
James Kuszmaul29c59522022-02-12 16:44:26 -08001063} // namespace frc971::controls