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