blob: 32f5604797dfde16967bbb398c8dd02dedefed89 [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-ua4f44ac2023-02-26 17:03:43 -080012DEFINE_double(distortion_noise_scalar, 1.0,
13 "Scale the target pose distortion factor by this when computing "
14 "the noise.");
milind-u48601192023-03-11 19:44:46 -080015DEFINE_double(
16 max_implied_yaw_error, 30.0,
17 "Reject target poses that imply a robot yaw of more than this many degrees "
18 "off from our estimate.");
19DEFINE_double(max_distance_to_target, 6.0,
20 "Reject target poses that have a 3d distance of more than this "
21 "many meters.");
milind-u7a7f6662023-02-26 16:41:29 -080022
James Kuszmaul04a343c2023-02-20 16:38:22 -080023namespace y2023::localizer {
24namespace {
25constexpr std::array<std::string_view, Localizer::kNumCameras> kPisToUse{
26 "pi1", "pi2", "pi3", "pi4"};
27
28size_t CameraIndexForName(std::string_view name) {
29 for (size_t index = 0; index < kPisToUse.size(); ++index) {
30 if (name == kPisToUse.at(index)) {
31 return index;
32 }
33 }
34 LOG(FATAL) << "No camera named " << name;
35}
36
37std::map<uint64_t, Localizer::Transform> GetTargetLocations(
38 const Constants &constants) {
39 CHECK(constants.has_target_map());
40 CHECK(constants.target_map()->has_target_poses());
41 std::map<uint64_t, Localizer::Transform> transforms;
42 for (const frc971::vision::TargetPoseFbs *target :
43 *constants.target_map()->target_poses()) {
44 CHECK(target->has_id());
45 CHECK(target->has_position());
46 CHECK(target->has_orientation());
47 CHECK_EQ(0u, transforms.count(target->id()));
48 transforms[target->id()] = PoseToTransform(target);
49 }
50 return transforms;
51}
52} // namespace
53
James Kuszmaul04a343c2023-02-20 16:38:22 -080054std::array<Localizer::CameraState, Localizer::kNumCameras>
55Localizer::MakeCameras(const Constants &constants, aos::EventLoop *event_loop) {
56 CHECK(constants.has_cameras());
57 std::array<Localizer::CameraState, Localizer::kNumCameras> cameras;
58 for (const CameraConfiguration *camera : *constants.cameras()) {
59 CHECK(camera->has_calibration());
60 const frc971::vision::calibration::CameraCalibration *calibration =
61 camera->calibration();
62 CHECK(!calibration->has_turret_extrinsics())
63 << "The 2023 robot does not have a turret.";
64 CHECK(calibration->has_node_name());
65 const size_t index =
66 CameraIndexForName(calibration->node_name()->string_view());
67 // We default-construct the extrinsics matrix to all-zeros; use that to
68 // sanity-check whether we have populated the matrix yet or not.
69 CHECK(cameras.at(index).extrinsics.norm() == 0)
70 << "Got multiple calibrations for "
71 << calibration->node_name()->string_view();
72 CHECK(calibration->has_fixed_extrinsics());
73 cameras.at(index).extrinsics =
74 frc971::control_loops::drivetrain::FlatbufferToTransformationMatrix(
75 *calibration->fixed_extrinsics());
76 cameras.at(index).debug_sender = event_loop->MakeSender<Visualization>(
77 absl::StrCat("/", calibration->node_name()->string_view(), "/camera"));
78 }
79 for (const CameraState &camera : cameras) {
80 CHECK(camera.extrinsics.norm() != 0) << "Missing a camera calibration.";
81 }
82 return cameras;
83}
84
85Localizer::Localizer(
86 aos::EventLoop *event_loop,
87 const frc971::control_loops::drivetrain::DrivetrainConfig<double> dt_config)
88 : event_loop_(event_loop),
89 dt_config_(dt_config),
90 constants_fetcher_(event_loop),
91 cameras_(MakeCameras(constants_fetcher_.constants(), event_loop)),
92 target_poses_(GetTargetLocations(constants_fetcher_.constants())),
93 down_estimator_(dt_config),
94 ekf_(dt_config),
95 observations_(&ekf_),
96 imu_watcher_(event_loop, dt_config,
97 y2023::constants::Values::DrivetrainEncoderToMeters(1),
98 std::bind(&Localizer::HandleImu, this, std::placeholders::_1,
99 std::placeholders::_2, std::placeholders::_3,
100 std::placeholders::_4, std::placeholders::_5)),
101 utils_(event_loop),
102 status_sender_(event_loop->MakeSender<Status>("/localizer")),
103 output_sender_(event_loop->MakeSender<frc971::controls::LocalizerOutput>(
104 "/localizer")) {
105 if (dt_config_.is_simulated) {
106 down_estimator_.assume_perfect_gravity();
107 }
108
109 for (size_t camera_index = 0; camera_index < kNumCameras; ++camera_index) {
110 const std::string_view pi_name = kPisToUse.at(camera_index);
111 event_loop->MakeWatcher(
112 absl::StrCat("/", pi_name, "/camera"),
113 [this, pi_name,
114 camera_index](const frc971::vision::TargetMap &targets) {
115 CHECK(targets.has_target_poses());
116 CHECK(targets.has_monotonic_timestamp_ns());
117 const std::optional<aos::monotonic_clock::duration> clock_offset =
118 utils_.ClockOffset(pi_name);
119 if (!clock_offset.has_value()) {
120 VLOG(1) << "Rejecting image due to disconnected message bridge at "
121 << event_loop_->monotonic_now();
122 cameras_.at(camera_index)
123 .rejection_counter.IncrementError(
124 RejectionReason::MESSAGE_BRIDGE_DISCONNECTED);
125 return;
126 }
127 const aos::monotonic_clock::time_point pi_capture_time(
128 std::chrono::nanoseconds(targets.monotonic_timestamp_ns()) -
129 clock_offset.value());
130 const aos::monotonic_clock::time_point capture_time =
131 pi_capture_time - imu_watcher_.pico_offset_error();
132 VLOG(2) << "Capture time of "
133 << targets.monotonic_timestamp_ns() * 1e-9
134 << " clock offset of "
135 << aos::time::DurationInSeconds(clock_offset.value())
136 << " pico error "
137 << aos::time::DurationInSeconds(
138 imu_watcher_.pico_offset_error());
139 if (pi_capture_time > event_loop_->context().monotonic_event_time) {
140 VLOG(1) << "Rejecting image due to being from future at "
141 << event_loop_->monotonic_now() << " with timestamp of "
142 << pi_capture_time << " and event time pf "
143 << event_loop_->context().monotonic_event_time;
144 cameras_.at(camera_index)
145 .rejection_counter.IncrementError(
146 RejectionReason::IMAGE_FROM_FUTURE);
147 return;
148 }
149 auto builder = cameras_.at(camera_index).debug_sender.MakeBuilder();
150 aos::SizedArray<flatbuffers::Offset<TargetEstimateDebug>, 20>
151 debug_offsets;
152 for (const frc971::vision::TargetPoseFbs *target :
153 *targets.target_poses()) {
154 VLOG(1) << "Handling target from " << camera_index;
155 auto offset = HandleTarget(camera_index, capture_time, *target,
156 builder.fbb());
157 if (debug_offsets.size() < debug_offsets.capacity()) {
158 debug_offsets.push_back(offset);
159 } else {
160 AOS_LOG(ERROR, "Dropped message from debug vector.");
161 }
162 }
163 auto vector_offset = builder.fbb()->CreateVector(
164 debug_offsets.data(), debug_offsets.size());
James Kuszmaulfb894572023-02-23 17:25:06 -0800165 auto stats_offset =
166 StatisticsForCamera(cameras_.at(camera_index), builder.fbb());
James Kuszmaul04a343c2023-02-20 16:38:22 -0800167 Visualization::Builder visualize_builder(*builder.fbb());
168 visualize_builder.add_targets(vector_offset);
James Kuszmaulfb894572023-02-23 17:25:06 -0800169 visualize_builder.add_statistics(stats_offset);
James Kuszmaul04a343c2023-02-20 16:38:22 -0800170 builder.CheckOk(builder.Send(visualize_builder.Finish()));
171 SendStatus();
172 });
173 }
174
175 event_loop_->AddPhasedLoop([this](int) { SendOutput(); },
James Kuszmaul456774b2023-03-08 21:29:15 -0800176 std::chrono::milliseconds(20));
James Kuszmaul04a343c2023-02-20 16:38:22 -0800177
178 event_loop_->MakeWatcher(
179 "/drivetrain",
180 [this](
181 const frc971::control_loops::drivetrain::LocalizerControl &control) {
182 const double theta = control.keep_current_theta()
183 ? ekf_.X_hat(StateIdx::kTheta)
184 : control.theta();
185 const double left_encoder = ekf_.X_hat(StateIdx::kLeftEncoder);
186 const double right_encoder = ekf_.X_hat(StateIdx::kRightEncoder);
187 ekf_.ResetInitialState(
188 t_,
189 (HybridEkf::State() << control.x(), control.y(), theta,
190 left_encoder, 0, right_encoder, 0, 0, 0, 0, 0, 0)
191 .finished(),
192 ekf_.P());
193 });
194
195 ekf_.set_ignore_accel(true);
196 // Priority should be lower than the imu reading process, but non-zero.
197 event_loop->SetRuntimeRealtimePriority(10);
198 event_loop->OnRun([this, event_loop]() {
199 ekf_.ResetInitialState(event_loop->monotonic_now(),
200 HybridEkf::State::Zero(), ekf_.P());
201 });
202}
203
204void Localizer::HandleImu(aos::monotonic_clock::time_point sample_time_pico,
205 aos::monotonic_clock::time_point sample_time_pi,
206 std::optional<Eigen::Vector2d> encoders,
207 Eigen::Vector3d gyro, Eigen::Vector3d accel) {
208 last_encoder_readings_ = encoders;
209 // Ignore ivnalid readings; the HybridEkf will handle it reasonably.
210 if (!encoders.has_value()) {
211 return;
212 }
213 if (t_ == aos::monotonic_clock::min_time) {
214 t_ = sample_time_pico;
215 }
216 if (t_ + 10 * frc971::controls::ImuWatcher::kNominalDt < sample_time_pico) {
217 t_ = sample_time_pico;
218 ++clock_resets_;
219 }
220 const aos::monotonic_clock::duration dt = sample_time_pico - t_;
221 t_ = sample_time_pico;
222 // We don't actually use the down estimator currently, but it's really
223 // convenient for debugging.
224 down_estimator_.Predict(gyro, accel, dt);
225 const double yaw_rate = (dt_config_.imu_transform * gyro)(2);
226 ekf_.UpdateEncodersAndGyro(encoders.value()(0), encoders.value()(1), yaw_rate,
227 utils_.VoltageOrZero(sample_time_pi), accel, t_);
228 SendStatus();
229}
230
231flatbuffers::Offset<TargetEstimateDebug> Localizer::RejectImage(
232 int camera_index, RejectionReason reason,
233 TargetEstimateDebug::Builder *builder) {
234 builder->add_accepted(false);
235 builder->add_rejection_reason(reason);
236 cameras_.at(camera_index).rejection_counter.IncrementError(reason);
237 return builder->Finish();
238}
239
240flatbuffers::Offset<TargetEstimateDebug> Localizer::HandleTarget(
241 int camera_index, const aos::monotonic_clock::time_point capture_time,
242 const frc971::vision::TargetPoseFbs &target,
243 flatbuffers::FlatBufferBuilder *debug_fbb) {
244 ++total_candidate_targets_;
245 ++cameras_.at(camera_index).total_candidate_targets;
246
247 TargetEstimateDebug::Builder builder(*debug_fbb);
248 builder.add_camera(camera_index);
249 builder.add_image_age_sec(aos::time::DurationInSeconds(
250 event_loop_->monotonic_now() - capture_time));
James Kuszmaule600d172023-03-12 10:19:44 -0700251 builder.add_image_monotonic_timestamp_ns(
252 std::chrono::duration_cast<std::chrono::nanoseconds>(
253 capture_time.time_since_epoch())
254 .count());
James Kuszmaul04a343c2023-02-20 16:38:22 -0800255
256 const uint64_t target_id = target.id();
James Kuszmaule600d172023-03-12 10:19:44 -0700257 builder.add_april_tag(target_id);
James Kuszmaul04a343c2023-02-20 16:38:22 -0800258 VLOG(2) << aos::FlatbufferToJson(&target);
259 if (target_poses_.count(target_id) == 0) {
260 VLOG(1) << "Rejecting target due to invalid ID " << target_id;
261 return RejectImage(camera_index, RejectionReason::NO_SUCH_TARGET, &builder);
262 }
263
264 const Transform &H_field_target = target_poses_.at(target_id);
265 const Transform &H_robot_camera = cameras_.at(camera_index).extrinsics;
266
267 const Transform H_camera_target = PoseToTransform(&target);
268
269 const Transform H_field_camera = H_field_target * H_camera_target.inverse();
270 // Back out the robot position that is implied by the current camera
271 // reading. Note that the Pose object ignores any roll/pitch components, so
272 // if the camera's extrinsics for pitch/roll are off, this should just
273 // ignore it.
274 const frc971::control_loops::Pose measured_camera_pose(H_field_camera);
275 builder.add_camera_x(measured_camera_pose.rel_pos().x());
276 builder.add_camera_y(measured_camera_pose.rel_pos().y());
277 // Because the camera uses Z as forwards rather than X, just calculate the
278 // debugging theta value using the transformation matrix directly.
279 builder.add_camera_theta(
280 std::atan2(H_field_camera(1, 2), H_field_camera(0, 2)));
281 // Calculate the camera-to-robot transformation matrix ignoring the
282 // pitch/roll of the camera.
283 const Transform H_camera_robot_stripped =
284 frc971::control_loops::Pose(H_robot_camera)
285 .AsTransformationMatrix()
286 .inverse();
287 const frc971::control_loops::Pose measured_pose(
288 measured_camera_pose.AsTransformationMatrix() * H_camera_robot_stripped);
289 // This "Z" is the robot pose directly implied by the camera results.
290 const Eigen::Matrix<double, 3, 1> Z(measured_pose.rel_pos().x(),
291 measured_pose.rel_pos().y(),
292 measured_pose.rel_theta());
293 builder.add_implied_robot_x(Z(Corrector::kX));
294 builder.add_implied_robot_y(Z(Corrector::kY));
295 builder.add_implied_robot_theta(Z(Corrector::kTheta));
296
milind-u5e055a02023-03-12 14:20:06 -0700297 Eigen::AngleAxisd rvec_camera_target(
298 Eigen::Affine3d(H_camera_target).rotation());
299 // Use y angle (around vertical axis) to compute skew
300 double skew = rvec_camera_target.axis().y() * rvec_camera_target.angle();
301 builder.add_skew(skew);
302
milind-u48601192023-03-11 19:44:46 -0800303 double distance_to_target =
304 Eigen::Affine3d(H_camera_target).translation().norm();
305
James Kuszmaul04a343c2023-02-20 16:38:22 -0800306 // TODO(james): Tune this. Also, gain schedule for auto mode?
307 Eigen::Matrix<double, 3, 1> noises(1.0, 1.0, 0.5);
James Kuszmaul285a7902023-03-05 18:06:36 -0800308 noises /= 4.0;
milind-ua4f44ac2023-02-26 17:03:43 -0800309 // Scale noise by the distortion factor for this detection
milind-u48601192023-03-11 19:44:46 -0800310 noises *= (1.0 + FLAGS_distortion_noise_scalar * target.distortion_factor() *
311 std::exp(distance_to_target));
James Kuszmaul04a343c2023-02-20 16:38:22 -0800312
313 Eigen::Matrix3d R = Eigen::Matrix3d::Zero();
314 R.diagonal() = noises.cwiseAbs2();
315 // In order to do the EKF correction, we determine the expected state based
316 // on the state at the time the image was captured; however, we insert the
317 // correction update itself at the current time. This is technically not
318 // quite correct, but saves substantial CPU usage & code complexity by
319 // making
320 // it so that we don't have to constantly rewind the entire EKF history.
321 const std::optional<State> state_at_capture =
322 ekf_.LastStateBeforeTime(capture_time);
323
324 if (!state_at_capture.has_value()) {
325 VLOG(1) << "Rejecting image due to being too old.";
326 return RejectImage(camera_index, RejectionReason::IMAGE_TOO_OLD, &builder);
milind-u7a7f6662023-02-26 16:41:29 -0800327 } else if (target.pose_error() > FLAGS_max_pose_error) {
328 VLOG(1) << "Rejecting target due to high pose error "
329 << target.pose_error();
330 return RejectImage(camera_index, RejectionReason::HIGH_POSE_ERROR,
331 &builder);
James Kuszmaul9da3b7a2023-03-11 21:02:25 -0800332 }
333
334 double theta_at_capture = state_at_capture.value()(StateIdx::kTheta);
335 double camera_implied_theta = Z(Corrector::kTheta);
336 constexpr double kDegToRad = M_PI / 180.0;
337
338 if (std::abs(camera_implied_theta - theta_at_capture) >
milind-u48601192023-03-11 19:44:46 -0800339 FLAGS_max_implied_yaw_error * kDegToRad) {
340 return RejectImage(camera_index, RejectionReason::HIGH_IMPLIED_YAW_ERROR,
341 &builder);
342 } else if (distance_to_target > FLAGS_max_distance_to_target) {
343 return RejectImage(camera_index, RejectionReason::HIGH_DISTANCE_TO_TARGET,
344 &builder);
James Kuszmaul04a343c2023-02-20 16:38:22 -0800345 }
346
347 const Input U = ekf_.MostRecentInput();
348 VLOG(1) << "previous state " << ekf_.X_hat().topRows<3>().transpose();
James Kuszmaule600d172023-03-12 10:19:44 -0700349 const State prior_state = ekf_.X_hat();
James Kuszmaul04a343c2023-02-20 16:38:22 -0800350 // For the correction step, instead of passing in the measurement directly,
351 // we pass in (0, 0, 0) as the measurement and then for the expected
352 // measurement (Zhat) we calculate the error between the pose implied by
353 // the camera measurement and the current estimate of the
354 // pose. This doesn't affect any of the math, it just makes the code a bit
355 // more convenient to write given the Correct() interface we already have.
356 observations_.CorrectKnownH(Eigen::Vector3d::Zero(), &U,
357 Corrector(state_at_capture.value(), Z), R, t_);
358 ++total_accepted_targets_;
359 ++cameras_.at(camera_index).total_accepted_targets;
360 VLOG(1) << "new state " << ekf_.X_hat().topRows<3>().transpose();
James Kuszmaule600d172023-03-12 10:19:44 -0700361 builder.add_correction_x(ekf_.X_hat()(StateIdx::kX) -
362 prior_state(StateIdx::kX));
363 builder.add_correction_y(ekf_.X_hat()(StateIdx::kY) -
364 prior_state(StateIdx::kY));
365 builder.add_correction_theta(ekf_.X_hat()(StateIdx::kTheta) -
366 prior_state(StateIdx::kTheta));
James Kuszmaul71518872023-02-25 18:00:15 -0800367 builder.add_accepted(true);
James Kuszmaul04a343c2023-02-20 16:38:22 -0800368 return builder.Finish();
369}
370
371Localizer::Output Localizer::Corrector::H(const State &, const Input &) {
372 CHECK(Z_.allFinite());
373 Eigen::Vector3d Zhat = H_ * state_at_capture_ - Z_;
374 // Rewrap angle difference to put it back in range.
375 Zhat(2) = aos::math::NormalizeAngle(Zhat(2));
376 VLOG(1) << "Zhat " << Zhat.transpose() << " Z_ " << Z_.transpose()
377 << " state " << (H_ * state_at_capture_).transpose();
378 return Zhat;
379}
380
381void Localizer::SendOutput() {
382 auto builder = output_sender_.MakeBuilder();
383 frc971::controls::LocalizerOutput::Builder output_builder =
384 builder.MakeBuilder<frc971::controls::LocalizerOutput>();
385 output_builder.add_monotonic_timestamp_ns(
386 std::chrono::duration_cast<std::chrono::nanoseconds>(
387 event_loop_->context().monotonic_event_time.time_since_epoch())
388 .count());
389 output_builder.add_x(ekf_.X_hat(StateIdx::kX));
390 output_builder.add_y(ekf_.X_hat(StateIdx::kY));
391 output_builder.add_theta(ekf_.X_hat(StateIdx::kTheta));
392 output_builder.add_zeroed(imu_watcher_.zeroer().Zeroed());
393 output_builder.add_image_accepted_count(total_accepted_targets_);
394 const Eigen::Quaterniond &orientation =
395 Eigen::AngleAxis<double>(ekf_.X_hat(StateIdx::kTheta),
396 Eigen::Vector3d::UnitZ()) *
397 down_estimator_.X_hat();
398 frc971::controls::Quaternion quaternion;
399 quaternion.mutate_x(orientation.x());
400 quaternion.mutate_y(orientation.y());
401 quaternion.mutate_z(orientation.z());
402 quaternion.mutate_w(orientation.w());
403 output_builder.add_orientation(&quaternion);
404 builder.CheckOk(builder.Send(output_builder.Finish()));
405}
406
407flatbuffers::Offset<frc971::control_loops::drivetrain::LocalizerState>
James Kuszmaule600d172023-03-12 10:19:44 -0700408Localizer::PopulateState(const State &X_hat,
409 flatbuffers::FlatBufferBuilder *fbb) {
James Kuszmaul04a343c2023-02-20 16:38:22 -0800410 frc971::control_loops::drivetrain::LocalizerState::Builder builder(*fbb);
James Kuszmaule600d172023-03-12 10:19:44 -0700411 builder.add_x(X_hat(StateIdx::kX));
412 builder.add_y(X_hat(StateIdx::kY));
413 builder.add_theta(X_hat(StateIdx::kTheta));
414 builder.add_left_velocity(X_hat(StateIdx::kLeftVelocity));
415 builder.add_right_velocity(X_hat(StateIdx::kRightVelocity));
416 builder.add_left_encoder(X_hat(StateIdx::kLeftEncoder));
417 builder.add_right_encoder(X_hat(StateIdx::kRightEncoder));
418 builder.add_left_voltage_error(X_hat(StateIdx::kLeftVoltageError));
419 builder.add_right_voltage_error(X_hat(StateIdx::kRightVoltageError));
420 builder.add_angular_error(X_hat(StateIdx::kAngularError));
James Kuszmaul04a343c2023-02-20 16:38:22 -0800421 builder.add_longitudinal_velocity_offset(
James Kuszmaule600d172023-03-12 10:19:44 -0700422 X_hat(StateIdx::kLongitudinalVelocityOffset));
423 builder.add_lateral_velocity(X_hat(StateIdx::kLateralVelocity));
James Kuszmaul04a343c2023-02-20 16:38:22 -0800424 return builder.Finish();
425}
426
427flatbuffers::Offset<ImuStatus> Localizer::PopulateImu(
428 flatbuffers::FlatBufferBuilder *fbb) const {
429 const auto zeroer_offset = imu_watcher_.zeroer().PopulateStatus(fbb);
430 const auto failures_offset = imu_watcher_.PopulateImuFailures(fbb);
431 ImuStatus::Builder builder(*fbb);
432 builder.add_zeroed(imu_watcher_.zeroer().Zeroed());
433 builder.add_faulted_zero(imu_watcher_.zeroer().Faulted());
434 builder.add_zeroing(zeroer_offset);
435 if (imu_watcher_.pico_offset().has_value()) {
436 builder.add_pico_offset_ns(imu_watcher_.pico_offset().value().count());
437 builder.add_pico_offset_error_ns(imu_watcher_.pico_offset_error().count());
438 }
439 if (last_encoder_readings_.has_value()) {
440 builder.add_left_encoder(last_encoder_readings_.value()(0));
441 builder.add_right_encoder(last_encoder_readings_.value()(1));
442 }
443 builder.add_imu_failures(failures_offset);
444 return builder.Finish();
445}
446
James Kuszmaulfb894572023-02-23 17:25:06 -0800447flatbuffers::Offset<CumulativeStatistics> Localizer::StatisticsForCamera(
448 const CameraState &camera, flatbuffers::FlatBufferBuilder *fbb) {
449 const auto counts_offset = camera.rejection_counter.PopulateCounts(fbb);
450 CumulativeStatistics::Builder stats_builder(*fbb);
451 stats_builder.add_total_accepted(camera.total_accepted_targets);
452 stats_builder.add_total_candidates(camera.total_candidate_targets);
453 stats_builder.add_rejection_reasons(counts_offset);
454 return stats_builder.Finish();
455}
456
James Kuszmaul04a343c2023-02-20 16:38:22 -0800457void Localizer::SendStatus() {
458 auto builder = status_sender_.MakeBuilder();
459 std::array<flatbuffers::Offset<CumulativeStatistics>, kNumCameras>
460 stats_offsets;
461 for (size_t ii = 0; ii < kNumCameras; ++ii) {
James Kuszmaulfb894572023-02-23 17:25:06 -0800462 stats_offsets.at(ii) = StatisticsForCamera(cameras_.at(ii), builder.fbb());
James Kuszmaul04a343c2023-02-20 16:38:22 -0800463 }
464 auto stats_offset =
465 builder.fbb()->CreateVector(stats_offsets.data(), stats_offsets.size());
466 auto down_estimator_offset =
467 down_estimator_.PopulateStatus(builder.fbb(), t_);
468 auto imu_offset = PopulateImu(builder.fbb());
James Kuszmaule600d172023-03-12 10:19:44 -0700469 auto state_offset = PopulateState(ekf_.X_hat(), builder.fbb());
James Kuszmaul04a343c2023-02-20 16:38:22 -0800470 Status::Builder status_builder = builder.MakeBuilder<Status>();
471 status_builder.add_state(state_offset);
472 status_builder.add_down_estimator(down_estimator_offset);
473 status_builder.add_imu(imu_offset);
474 status_builder.add_statistics(stats_offset);
475 builder.CheckOk(builder.Send(status_builder.Finish()));
476}
477
478} // namespace y2023::localizer