blob: c663954be2ab023608f42cf5e5d681ac6166e132 [file] [log] [blame]
James Kuszmaul04a343c2023-02-20 16:38:22 -08001#include "y2023/localizer/localizer.h"
2
3#include "aos/containers/sized_array.h"
4#include "frc971/control_loops/drivetrain/localizer_generated.h"
5#include "frc971/control_loops/pose.h"
milind-u7a7f6662023-02-26 16:41:29 -08006#include "gflags/gflags.h"
James Kuszmaul04a343c2023-02-20 16:38:22 -08007#include "y2023/constants.h"
James Kuszmaul18008f82023-02-23 20:52:50 -08008#include "y2023/localizer/utils.h"
James Kuszmaul04a343c2023-02-20 16:38:22 -08009
milind-u7a7f6662023-02-26 16:41:29 -080010DEFINE_double(max_pose_error, 1e-6,
11 "Throw out target poses with a higher pose error than this");
milind-u08fb9722023-03-25 18:23:59 -070012DEFINE_double(
13 max_pose_error_ratio, 0.4,
14 "Throw out target poses with a higher pose error ratio than this");
milind-ua4f44ac2023-02-26 17:03:43 -080015DEFINE_double(distortion_noise_scalar, 1.0,
16 "Scale the target pose distortion factor by this when computing "
17 "the noise.");
milind-u48601192023-03-11 19:44:46 -080018DEFINE_double(
James Kuszmaul3c6a9682023-03-23 20:36:53 -070019 max_implied_yaw_error, 3.0,
milind-u48601192023-03-11 19:44:46 -080020 "Reject target poses that imply a robot yaw of more than this many degrees "
21 "off from our estimate.");
James Kuszmaul3c6a9682023-03-23 20:36:53 -070022DEFINE_double(
23 max_implied_teleop_yaw_error, 30.0,
24 "Reject target poses that imply a robot yaw of more than this many degrees "
25 "off from our estimate.");
26DEFINE_double(max_distance_to_target, 3.5,
milind-u48601192023-03-11 19:44:46 -080027 "Reject target poses that have a 3d distance of more than this "
28 "many meters.");
James Kuszmaul3c6a9682023-03-23 20:36:53 -070029DEFINE_double(max_auto_image_robot_speed, 2.0,
30 "Reject target poses when the robot is travelling faster than "
31 "this speed in auto.");
milind-u7a7f6662023-02-26 16:41:29 -080032
James Kuszmaul04a343c2023-02-20 16:38:22 -080033namespace y2023::localizer {
34namespace {
35constexpr std::array<std::string_view, Localizer::kNumCameras> kPisToUse{
36 "pi1", "pi2", "pi3", "pi4"};
37
38size_t CameraIndexForName(std::string_view name) {
39 for (size_t index = 0; index < kPisToUse.size(); ++index) {
40 if (name == kPisToUse.at(index)) {
41 return index;
42 }
43 }
44 LOG(FATAL) << "No camera named " << name;
45}
46
47std::map<uint64_t, Localizer::Transform> GetTargetLocations(
48 const Constants &constants) {
49 CHECK(constants.has_target_map());
50 CHECK(constants.target_map()->has_target_poses());
51 std::map<uint64_t, Localizer::Transform> transforms;
52 for (const frc971::vision::TargetPoseFbs *target :
53 *constants.target_map()->target_poses()) {
54 CHECK(target->has_id());
55 CHECK(target->has_position());
56 CHECK(target->has_orientation());
57 CHECK_EQ(0u, transforms.count(target->id()));
58 transforms[target->id()] = PoseToTransform(target);
59 }
60 return transforms;
61}
62} // namespace
63
James Kuszmaul04a343c2023-02-20 16:38:22 -080064std::array<Localizer::CameraState, Localizer::kNumCameras>
65Localizer::MakeCameras(const Constants &constants, aos::EventLoop *event_loop) {
66 CHECK(constants.has_cameras());
67 std::array<Localizer::CameraState, Localizer::kNumCameras> cameras;
68 for (const CameraConfiguration *camera : *constants.cameras()) {
69 CHECK(camera->has_calibration());
70 const frc971::vision::calibration::CameraCalibration *calibration =
71 camera->calibration();
72 CHECK(!calibration->has_turret_extrinsics())
73 << "The 2023 robot does not have a turret.";
74 CHECK(calibration->has_node_name());
75 const size_t index =
76 CameraIndexForName(calibration->node_name()->string_view());
77 // We default-construct the extrinsics matrix to all-zeros; use that to
78 // sanity-check whether we have populated the matrix yet or not.
79 CHECK(cameras.at(index).extrinsics.norm() == 0)
80 << "Got multiple calibrations for "
81 << calibration->node_name()->string_view();
82 CHECK(calibration->has_fixed_extrinsics());
83 cameras.at(index).extrinsics =
84 frc971::control_loops::drivetrain::FlatbufferToTransformationMatrix(
85 *calibration->fixed_extrinsics());
86 cameras.at(index).debug_sender = event_loop->MakeSender<Visualization>(
87 absl::StrCat("/", calibration->node_name()->string_view(), "/camera"));
88 }
89 for (const CameraState &camera : cameras) {
90 CHECK(camera.extrinsics.norm() != 0) << "Missing a camera calibration.";
91 }
92 return cameras;
93}
94
95Localizer::Localizer(
96 aos::EventLoop *event_loop,
97 const frc971::control_loops::drivetrain::DrivetrainConfig<double> dt_config)
98 : event_loop_(event_loop),
99 dt_config_(dt_config),
100 constants_fetcher_(event_loop),
101 cameras_(MakeCameras(constants_fetcher_.constants(), event_loop)),
102 target_poses_(GetTargetLocations(constants_fetcher_.constants())),
103 down_estimator_(dt_config),
104 ekf_(dt_config),
105 observations_(&ekf_),
106 imu_watcher_(event_loop, dt_config,
107 y2023::constants::Values::DrivetrainEncoderToMeters(1),
108 std::bind(&Localizer::HandleImu, this, std::placeholders::_1,
109 std::placeholders::_2, std::placeholders::_3,
James Kuszmaul54fe9d02023-03-23 20:32:40 -0700110 std::placeholders::_4, std::placeholders::_5),
111 frc971::controls::ImuWatcher::TimestampSource::kPi),
James Kuszmaul04a343c2023-02-20 16:38:22 -0800112 utils_(event_loop),
113 status_sender_(event_loop->MakeSender<Status>("/localizer")),
114 output_sender_(event_loop->MakeSender<frc971::controls::LocalizerOutput>(
115 "/localizer")) {
116 if (dt_config_.is_simulated) {
117 down_estimator_.assume_perfect_gravity();
118 }
119
120 for (size_t camera_index = 0; camera_index < kNumCameras; ++camera_index) {
121 const std::string_view pi_name = kPisToUse.at(camera_index);
122 event_loop->MakeWatcher(
123 absl::StrCat("/", pi_name, "/camera"),
124 [this, pi_name,
125 camera_index](const frc971::vision::TargetMap &targets) {
126 CHECK(targets.has_target_poses());
127 CHECK(targets.has_monotonic_timestamp_ns());
128 const std::optional<aos::monotonic_clock::duration> clock_offset =
129 utils_.ClockOffset(pi_name);
130 if (!clock_offset.has_value()) {
131 VLOG(1) << "Rejecting image due to disconnected message bridge at "
132 << event_loop_->monotonic_now();
133 cameras_.at(camera_index)
134 .rejection_counter.IncrementError(
135 RejectionReason::MESSAGE_BRIDGE_DISCONNECTED);
136 return;
137 }
138 const aos::monotonic_clock::time_point pi_capture_time(
139 std::chrono::nanoseconds(targets.monotonic_timestamp_ns()) -
140 clock_offset.value());
141 const aos::monotonic_clock::time_point capture_time =
142 pi_capture_time - imu_watcher_.pico_offset_error();
143 VLOG(2) << "Capture time of "
144 << targets.monotonic_timestamp_ns() * 1e-9
145 << " clock offset of "
146 << aos::time::DurationInSeconds(clock_offset.value())
147 << " pico error "
148 << aos::time::DurationInSeconds(
149 imu_watcher_.pico_offset_error());
150 if (pi_capture_time > event_loop_->context().monotonic_event_time) {
151 VLOG(1) << "Rejecting image due to being from future at "
152 << event_loop_->monotonic_now() << " with timestamp of "
153 << pi_capture_time << " and event time pf "
154 << event_loop_->context().monotonic_event_time;
155 cameras_.at(camera_index)
156 .rejection_counter.IncrementError(
157 RejectionReason::IMAGE_FROM_FUTURE);
158 return;
159 }
160 auto builder = cameras_.at(camera_index).debug_sender.MakeBuilder();
161 aos::SizedArray<flatbuffers::Offset<TargetEstimateDebug>, 20>
162 debug_offsets;
163 for (const frc971::vision::TargetPoseFbs *target :
164 *targets.target_poses()) {
165 VLOG(1) << "Handling target from " << camera_index;
166 auto offset = HandleTarget(camera_index, capture_time, *target,
167 builder.fbb());
168 if (debug_offsets.size() < debug_offsets.capacity()) {
169 debug_offsets.push_back(offset);
170 } else {
171 AOS_LOG(ERROR, "Dropped message from debug vector.");
172 }
173 }
174 auto vector_offset = builder.fbb()->CreateVector(
175 debug_offsets.data(), debug_offsets.size());
James Kuszmaulfb894572023-02-23 17:25:06 -0800176 auto stats_offset =
177 StatisticsForCamera(cameras_.at(camera_index), builder.fbb());
James Kuszmaul04a343c2023-02-20 16:38:22 -0800178 Visualization::Builder visualize_builder(*builder.fbb());
179 visualize_builder.add_targets(vector_offset);
James Kuszmaulfb894572023-02-23 17:25:06 -0800180 visualize_builder.add_statistics(stats_offset);
James Kuszmaul04a343c2023-02-20 16:38:22 -0800181 builder.CheckOk(builder.Send(visualize_builder.Finish()));
182 SendStatus();
183 });
184 }
185
186 event_loop_->AddPhasedLoop([this](int) { SendOutput(); },
James Kuszmaul456774b2023-03-08 21:29:15 -0800187 std::chrono::milliseconds(20));
James Kuszmaul04a343c2023-02-20 16:38:22 -0800188
189 event_loop_->MakeWatcher(
190 "/drivetrain",
191 [this](
192 const frc971::control_loops::drivetrain::LocalizerControl &control) {
193 const double theta = control.keep_current_theta()
194 ? ekf_.X_hat(StateIdx::kTheta)
195 : control.theta();
196 const double left_encoder = ekf_.X_hat(StateIdx::kLeftEncoder);
197 const double right_encoder = ekf_.X_hat(StateIdx::kRightEncoder);
198 ekf_.ResetInitialState(
199 t_,
200 (HybridEkf::State() << control.x(), control.y(), theta,
201 left_encoder, 0, right_encoder, 0, 0, 0, 0, 0, 0)
202 .finished(),
203 ekf_.P());
204 });
205
206 ekf_.set_ignore_accel(true);
207 // Priority should be lower than the imu reading process, but non-zero.
208 event_loop->SetRuntimeRealtimePriority(10);
209 event_loop->OnRun([this, event_loop]() {
210 ekf_.ResetInitialState(event_loop->monotonic_now(),
211 HybridEkf::State::Zero(), ekf_.P());
212 });
213}
214
215void Localizer::HandleImu(aos::monotonic_clock::time_point sample_time_pico,
216 aos::monotonic_clock::time_point sample_time_pi,
217 std::optional<Eigen::Vector2d> encoders,
218 Eigen::Vector3d gyro, Eigen::Vector3d accel) {
219 last_encoder_readings_ = encoders;
220 // Ignore ivnalid readings; the HybridEkf will handle it reasonably.
221 if (!encoders.has_value()) {
222 return;
223 }
224 if (t_ == aos::monotonic_clock::min_time) {
225 t_ = sample_time_pico;
226 }
227 if (t_ + 10 * frc971::controls::ImuWatcher::kNominalDt < sample_time_pico) {
228 t_ = sample_time_pico;
229 ++clock_resets_;
230 }
231 const aos::monotonic_clock::duration dt = sample_time_pico - t_;
232 t_ = sample_time_pico;
233 // We don't actually use the down estimator currently, but it's really
234 // convenient for debugging.
235 down_estimator_.Predict(gyro, accel, dt);
236 const double yaw_rate = (dt_config_.imu_transform * gyro)(2);
237 ekf_.UpdateEncodersAndGyro(encoders.value()(0), encoders.value()(1), yaw_rate,
238 utils_.VoltageOrZero(sample_time_pi), accel, t_);
239 SendStatus();
240}
241
242flatbuffers::Offset<TargetEstimateDebug> Localizer::RejectImage(
243 int camera_index, RejectionReason reason,
244 TargetEstimateDebug::Builder *builder) {
245 builder->add_accepted(false);
246 builder->add_rejection_reason(reason);
247 cameras_.at(camera_index).rejection_counter.IncrementError(reason);
248 return builder->Finish();
249}
250
James Kuszmaul4fe845a2023-03-26 12:57:30 -0700251bool Localizer::UseAprilTag(uint64_t target_id) {
252 if (target_poses_.count(target_id) == 0) {
253 return false;
254 }
255
256 const flatbuffers::Vector<uint64_t> *ignore_tags = nullptr;
257
258 switch (utils_.Alliance()) {
259 case aos::Alliance::kRed:
260 ignore_tags =
261 CHECK_NOTNULL(constants_fetcher_.constants().ignore_targets()->red());
262 break;
263 case aos::Alliance::kBlue:
264 ignore_tags = CHECK_NOTNULL(
265 constants_fetcher_.constants().ignore_targets()->blue());
266 break;
267 case aos::Alliance::kInvalid:
268 return true;
269 }
270 return std::find(ignore_tags->begin(), ignore_tags->end(), target_id) ==
271 ignore_tags->end();
272}
273
James Kuszmaul04a343c2023-02-20 16:38:22 -0800274flatbuffers::Offset<TargetEstimateDebug> Localizer::HandleTarget(
275 int camera_index, const aos::monotonic_clock::time_point capture_time,
276 const frc971::vision::TargetPoseFbs &target,
277 flatbuffers::FlatBufferBuilder *debug_fbb) {
278 ++total_candidate_targets_;
279 ++cameras_.at(camera_index).total_candidate_targets;
280
281 TargetEstimateDebug::Builder builder(*debug_fbb);
282 builder.add_camera(camera_index);
283 builder.add_image_age_sec(aos::time::DurationInSeconds(
284 event_loop_->monotonic_now() - capture_time));
James Kuszmaule600d172023-03-12 10:19:44 -0700285 builder.add_image_monotonic_timestamp_ns(
286 std::chrono::duration_cast<std::chrono::nanoseconds>(
287 capture_time.time_since_epoch())
288 .count());
James Kuszmaul04a343c2023-02-20 16:38:22 -0800289
290 const uint64_t target_id = target.id();
James Kuszmaule600d172023-03-12 10:19:44 -0700291 builder.add_april_tag(target_id);
James Kuszmaul04a343c2023-02-20 16:38:22 -0800292 VLOG(2) << aos::FlatbufferToJson(&target);
James Kuszmaul4fe845a2023-03-26 12:57:30 -0700293 if (!UseAprilTag(target_id)) {
James Kuszmaul04a343c2023-02-20 16:38:22 -0800294 VLOG(1) << "Rejecting target due to invalid ID " << target_id;
295 return RejectImage(camera_index, RejectionReason::NO_SUCH_TARGET, &builder);
296 }
297
298 const Transform &H_field_target = target_poses_.at(target_id);
299 const Transform &H_robot_camera = cameras_.at(camera_index).extrinsics;
300
301 const Transform H_camera_target = PoseToTransform(&target);
302
303 const Transform H_field_camera = H_field_target * H_camera_target.inverse();
304 // Back out the robot position that is implied by the current camera
305 // reading. Note that the Pose object ignores any roll/pitch components, so
306 // if the camera's extrinsics for pitch/roll are off, this should just
307 // ignore it.
308 const frc971::control_loops::Pose measured_camera_pose(H_field_camera);
309 builder.add_camera_x(measured_camera_pose.rel_pos().x());
310 builder.add_camera_y(measured_camera_pose.rel_pos().y());
311 // Because the camera uses Z as forwards rather than X, just calculate the
312 // debugging theta value using the transformation matrix directly.
313 builder.add_camera_theta(
314 std::atan2(H_field_camera(1, 2), H_field_camera(0, 2)));
315 // Calculate the camera-to-robot transformation matrix ignoring the
316 // pitch/roll of the camera.
317 const Transform H_camera_robot_stripped =
318 frc971::control_loops::Pose(H_robot_camera)
319 .AsTransformationMatrix()
320 .inverse();
321 const frc971::control_loops::Pose measured_pose(
322 measured_camera_pose.AsTransformationMatrix() * H_camera_robot_stripped);
323 // This "Z" is the robot pose directly implied by the camera results.
324 const Eigen::Matrix<double, 3, 1> Z(measured_pose.rel_pos().x(),
325 measured_pose.rel_pos().y(),
326 measured_pose.rel_theta());
327 builder.add_implied_robot_x(Z(Corrector::kX));
328 builder.add_implied_robot_y(Z(Corrector::kY));
329 builder.add_implied_robot_theta(Z(Corrector::kTheta));
330
milind-u5e055a02023-03-12 14:20:06 -0700331 Eigen::AngleAxisd rvec_camera_target(
332 Eigen::Affine3d(H_camera_target).rotation());
333 // Use y angle (around vertical axis) to compute skew
334 double skew = rvec_camera_target.axis().y() * rvec_camera_target.angle();
335 builder.add_skew(skew);
336
milind-u48601192023-03-11 19:44:46 -0800337 double distance_to_target =
338 Eigen::Affine3d(H_camera_target).translation().norm();
339
James Kuszmaul04a343c2023-02-20 16:38:22 -0800340 // TODO(james): Tune this. Also, gain schedule for auto mode?
341 Eigen::Matrix<double, 3, 1> noises(1.0, 1.0, 0.5);
James Kuszmaul285a7902023-03-05 18:06:36 -0800342 noises /= 4.0;
milind-ua4f44ac2023-02-26 17:03:43 -0800343 // Scale noise by the distortion factor for this detection
milind-u48601192023-03-11 19:44:46 -0800344 noises *= (1.0 + FLAGS_distortion_noise_scalar * target.distortion_factor() *
345 std::exp(distance_to_target));
James Kuszmaul04a343c2023-02-20 16:38:22 -0800346
347 Eigen::Matrix3d R = Eigen::Matrix3d::Zero();
348 R.diagonal() = noises.cwiseAbs2();
349 // In order to do the EKF correction, we determine the expected state based
350 // on the state at the time the image was captured; however, we insert the
351 // correction update itself at the current time. This is technically not
352 // quite correct, but saves substantial CPU usage & code complexity by
353 // making
354 // it so that we don't have to constantly rewind the entire EKF history.
355 const std::optional<State> state_at_capture =
356 ekf_.LastStateBeforeTime(capture_time);
357
358 if (!state_at_capture.has_value()) {
359 VLOG(1) << "Rejecting image due to being too old.";
360 return RejectImage(camera_index, RejectionReason::IMAGE_TOO_OLD, &builder);
milind-u7a7f6662023-02-26 16:41:29 -0800361 } else if (target.pose_error() > FLAGS_max_pose_error) {
362 VLOG(1) << "Rejecting target due to high pose error "
363 << target.pose_error();
364 return RejectImage(camera_index, RejectionReason::HIGH_POSE_ERROR,
365 &builder);
milind-u08fb9722023-03-25 18:23:59 -0700366 } else if (target.pose_error_ratio() > FLAGS_max_pose_error_ratio) {
367 VLOG(1) << "Rejecting target due to high pose error ratio "
368 << target.pose_error_ratio();
369 return RejectImage(camera_index, RejectionReason::HIGH_POSE_ERROR_RATIO,
370 &builder);
James Kuszmaul9da3b7a2023-03-11 21:02:25 -0800371 }
372
373 double theta_at_capture = state_at_capture.value()(StateIdx::kTheta);
374 double camera_implied_theta = Z(Corrector::kTheta);
375 constexpr double kDegToRad = M_PI / 180.0;
376
James Kuszmaul3c6a9682023-03-23 20:36:53 -0700377 const double robot_speed =
378 (state_at_capture.value()(StateIdx::kLeftVelocity) +
379 state_at_capture.value()(StateIdx::kRightVelocity)) /
380 2.0;
381 const double yaw_threshold =
382 (utils_.MaybeInAutonomous() ? FLAGS_max_implied_yaw_error
383 : FLAGS_max_implied_teleop_yaw_error) *
384 kDegToRad;
385 if (utils_.MaybeInAutonomous() &&
386 (std::abs(robot_speed) > FLAGS_max_auto_image_robot_speed)) {
387 return RejectImage(camera_index, RejectionReason::ROBOT_TOO_FAST, &builder);
388 } else if (std::abs(aos::math::NormalizeAngle(
389 camera_implied_theta - theta_at_capture)) > yaw_threshold) {
milind-u48601192023-03-11 19:44:46 -0800390 return RejectImage(camera_index, RejectionReason::HIGH_IMPLIED_YAW_ERROR,
391 &builder);
392 } else if (distance_to_target > FLAGS_max_distance_to_target) {
393 return RejectImage(camera_index, RejectionReason::HIGH_DISTANCE_TO_TARGET,
394 &builder);
James Kuszmaul04a343c2023-02-20 16:38:22 -0800395 }
396
397 const Input U = ekf_.MostRecentInput();
398 VLOG(1) << "previous state " << ekf_.X_hat().topRows<3>().transpose();
James Kuszmaule600d172023-03-12 10:19:44 -0700399 const State prior_state = ekf_.X_hat();
James Kuszmaul04a343c2023-02-20 16:38:22 -0800400 // For the correction step, instead of passing in the measurement directly,
401 // we pass in (0, 0, 0) as the measurement and then for the expected
402 // measurement (Zhat) we calculate the error between the pose implied by
403 // the camera measurement and the current estimate of the
404 // pose. This doesn't affect any of the math, it just makes the code a bit
405 // more convenient to write given the Correct() interface we already have.
406 observations_.CorrectKnownH(Eigen::Vector3d::Zero(), &U,
407 Corrector(state_at_capture.value(), Z), R, t_);
408 ++total_accepted_targets_;
409 ++cameras_.at(camera_index).total_accepted_targets;
410 VLOG(1) << "new state " << ekf_.X_hat().topRows<3>().transpose();
James Kuszmaule600d172023-03-12 10:19:44 -0700411 builder.add_correction_x(ekf_.X_hat()(StateIdx::kX) -
412 prior_state(StateIdx::kX));
413 builder.add_correction_y(ekf_.X_hat()(StateIdx::kY) -
414 prior_state(StateIdx::kY));
415 builder.add_correction_theta(ekf_.X_hat()(StateIdx::kTheta) -
416 prior_state(StateIdx::kTheta));
James Kuszmaul71518872023-02-25 18:00:15 -0800417 builder.add_accepted(true);
James Kuszmaul04a343c2023-02-20 16:38:22 -0800418 return builder.Finish();
419}
420
421Localizer::Output Localizer::Corrector::H(const State &, const Input &) {
422 CHECK(Z_.allFinite());
423 Eigen::Vector3d Zhat = H_ * state_at_capture_ - Z_;
424 // Rewrap angle difference to put it back in range.
425 Zhat(2) = aos::math::NormalizeAngle(Zhat(2));
426 VLOG(1) << "Zhat " << Zhat.transpose() << " Z_ " << Z_.transpose()
427 << " state " << (H_ * state_at_capture_).transpose();
428 return Zhat;
429}
430
431void Localizer::SendOutput() {
432 auto builder = output_sender_.MakeBuilder();
433 frc971::controls::LocalizerOutput::Builder output_builder =
434 builder.MakeBuilder<frc971::controls::LocalizerOutput>();
435 output_builder.add_monotonic_timestamp_ns(
436 std::chrono::duration_cast<std::chrono::nanoseconds>(
437 event_loop_->context().monotonic_event_time.time_since_epoch())
438 .count());
439 output_builder.add_x(ekf_.X_hat(StateIdx::kX));
440 output_builder.add_y(ekf_.X_hat(StateIdx::kY));
441 output_builder.add_theta(ekf_.X_hat(StateIdx::kTheta));
442 output_builder.add_zeroed(imu_watcher_.zeroer().Zeroed());
443 output_builder.add_image_accepted_count(total_accepted_targets_);
444 const Eigen::Quaterniond &orientation =
445 Eigen::AngleAxis<double>(ekf_.X_hat(StateIdx::kTheta),
446 Eigen::Vector3d::UnitZ()) *
447 down_estimator_.X_hat();
448 frc971::controls::Quaternion quaternion;
449 quaternion.mutate_x(orientation.x());
450 quaternion.mutate_y(orientation.y());
451 quaternion.mutate_z(orientation.z());
452 quaternion.mutate_w(orientation.w());
453 output_builder.add_orientation(&quaternion);
454 builder.CheckOk(builder.Send(output_builder.Finish()));
455}
456
457flatbuffers::Offset<frc971::control_loops::drivetrain::LocalizerState>
James Kuszmaule600d172023-03-12 10:19:44 -0700458Localizer::PopulateState(const State &X_hat,
459 flatbuffers::FlatBufferBuilder *fbb) {
James Kuszmaul04a343c2023-02-20 16:38:22 -0800460 frc971::control_loops::drivetrain::LocalizerState::Builder builder(*fbb);
James Kuszmaule600d172023-03-12 10:19:44 -0700461 builder.add_x(X_hat(StateIdx::kX));
462 builder.add_y(X_hat(StateIdx::kY));
463 builder.add_theta(X_hat(StateIdx::kTheta));
464 builder.add_left_velocity(X_hat(StateIdx::kLeftVelocity));
465 builder.add_right_velocity(X_hat(StateIdx::kRightVelocity));
466 builder.add_left_encoder(X_hat(StateIdx::kLeftEncoder));
467 builder.add_right_encoder(X_hat(StateIdx::kRightEncoder));
468 builder.add_left_voltage_error(X_hat(StateIdx::kLeftVoltageError));
469 builder.add_right_voltage_error(X_hat(StateIdx::kRightVoltageError));
470 builder.add_angular_error(X_hat(StateIdx::kAngularError));
James Kuszmaul04a343c2023-02-20 16:38:22 -0800471 builder.add_longitudinal_velocity_offset(
James Kuszmaule600d172023-03-12 10:19:44 -0700472 X_hat(StateIdx::kLongitudinalVelocityOffset));
473 builder.add_lateral_velocity(X_hat(StateIdx::kLateralVelocity));
James Kuszmaul04a343c2023-02-20 16:38:22 -0800474 return builder.Finish();
475}
476
477flatbuffers::Offset<ImuStatus> Localizer::PopulateImu(
478 flatbuffers::FlatBufferBuilder *fbb) const {
479 const auto zeroer_offset = imu_watcher_.zeroer().PopulateStatus(fbb);
480 const auto failures_offset = imu_watcher_.PopulateImuFailures(fbb);
481 ImuStatus::Builder builder(*fbb);
482 builder.add_zeroed(imu_watcher_.zeroer().Zeroed());
483 builder.add_faulted_zero(imu_watcher_.zeroer().Faulted());
484 builder.add_zeroing(zeroer_offset);
485 if (imu_watcher_.pico_offset().has_value()) {
486 builder.add_pico_offset_ns(imu_watcher_.pico_offset().value().count());
487 builder.add_pico_offset_error_ns(imu_watcher_.pico_offset_error().count());
488 }
489 if (last_encoder_readings_.has_value()) {
490 builder.add_left_encoder(last_encoder_readings_.value()(0));
491 builder.add_right_encoder(last_encoder_readings_.value()(1));
492 }
493 builder.add_imu_failures(failures_offset);
494 return builder.Finish();
495}
496
James Kuszmaulfb894572023-02-23 17:25:06 -0800497flatbuffers::Offset<CumulativeStatistics> Localizer::StatisticsForCamera(
498 const CameraState &camera, flatbuffers::FlatBufferBuilder *fbb) {
499 const auto counts_offset = camera.rejection_counter.PopulateCounts(fbb);
500 CumulativeStatistics::Builder stats_builder(*fbb);
501 stats_builder.add_total_accepted(camera.total_accepted_targets);
502 stats_builder.add_total_candidates(camera.total_candidate_targets);
503 stats_builder.add_rejection_reasons(counts_offset);
504 return stats_builder.Finish();
505}
506
James Kuszmaul04a343c2023-02-20 16:38:22 -0800507void Localizer::SendStatus() {
508 auto builder = status_sender_.MakeBuilder();
509 std::array<flatbuffers::Offset<CumulativeStatistics>, kNumCameras>
510 stats_offsets;
511 for (size_t ii = 0; ii < kNumCameras; ++ii) {
James Kuszmaulfb894572023-02-23 17:25:06 -0800512 stats_offsets.at(ii) = StatisticsForCamera(cameras_.at(ii), builder.fbb());
James Kuszmaul04a343c2023-02-20 16:38:22 -0800513 }
514 auto stats_offset =
515 builder.fbb()->CreateVector(stats_offsets.data(), stats_offsets.size());
516 auto down_estimator_offset =
517 down_estimator_.PopulateStatus(builder.fbb(), t_);
518 auto imu_offset = PopulateImu(builder.fbb());
James Kuszmaule600d172023-03-12 10:19:44 -0700519 auto state_offset = PopulateState(ekf_.X_hat(), builder.fbb());
James Kuszmaul04a343c2023-02-20 16:38:22 -0800520 Status::Builder status_builder = builder.MakeBuilder<Status>();
521 status_builder.add_state(state_offset);
522 status_builder.add_down_estimator(down_estimator_offset);
523 status_builder.add_imu(imu_offset);
524 status_builder.add_statistics(stats_offset);
525 builder.CheckOk(builder.Send(status_builder.Finish()));
526}
527
528} // namespace y2023::localizer