blob: 61e78e787a3ec2c4ff68d762534819fe829f03da [file] [log] [blame]
James Kuszmaul313e9ce2024-02-11 17:47:33 -08001#include "y2024/localizer/localizer.h"
2
3#include "gflags/gflags.h"
4
5#include "aos/containers/sized_array.h"
6#include "frc971/control_loops/drivetrain/localizer_generated.h"
7#include "frc971/control_loops/pose.h"
James Kuszmaul86116c22024-03-15 22:50:34 -07008#include "frc971/math/flatbuffers_matrix.h"
James Kuszmaul313e9ce2024-02-11 17:47:33 -08009#include "frc971/vision/target_map_utils.h"
10#include "y2024/constants.h"
11
James Kuszmaul86116c22024-03-15 22:50:34 -070012DEFINE_double(max_pose_error, 1e-5,
James Kuszmaul313e9ce2024-02-11 17:47:33 -080013 "Throw out target poses with a higher pose error than this");
Austin Schuh98b732d2024-03-22 19:59:09 -070014DEFINE_double(max_distortion, 1000.0, "");
James Kuszmaul313e9ce2024-02-11 17:47:33 -080015DEFINE_double(
16 max_pose_error_ratio, 0.4,
17 "Throw out target poses with a higher pose error ratio than this");
James Kuszmaul86116c22024-03-15 22:50:34 -070018DEFINE_double(distortion_noise_scalar, 4.0,
James Kuszmaul313e9ce2024-02-11 17:47:33 -080019 "Scale the target pose distortion factor by this when computing "
20 "the noise.");
21DEFINE_double(
James Kuszmaul86116c22024-03-15 22:50:34 -070022 max_implied_yaw_error, 5.0,
James Kuszmaul313e9ce2024-02-11 17:47:33 -080023 "Reject target poses that imply a robot yaw of more than this many degrees "
24 "off from our estimate.");
25DEFINE_double(
26 max_implied_teleop_yaw_error, 30.0,
27 "Reject target poses that imply a robot yaw of more than this many degrees "
28 "off from our estimate.");
29DEFINE_double(max_distance_to_target, 5.0,
30 "Reject target poses that have a 3d distance of more than this "
31 "many meters.");
32DEFINE_double(max_auto_image_robot_speed, 2.0,
33 "Reject target poses when the robot is travelling faster than "
34 "this speed in auto.");
James Kuszmaul86116c22024-03-15 22:50:34 -070035DEFINE_bool(
36 do_xytheta_corrections, true,
37 "If set, uses the x/y/theta corrector rather than a heading/distance/skew "
38 "one. This is better conditioned currently, but is theoretically worse due "
39 "to not capturing noise effectively.");
40DEFINE_bool(
41 always_use_extra_tags, true,
42 "If set, we will use the \"deweighted\" tags even in auto mode (this "
43 "affects april tags whose field positions we do not trust as much).");
James Kuszmaul313e9ce2024-02-11 17:47:33 -080044
45namespace y2024::localizer {
46namespace {
47constexpr std::array<std::string_view, Localizer::kNumCameras>
Maxwell Henderson3279bc52024-03-01 09:50:53 -080048 kDetectionChannels{"/orin1/camera0", "/orin1/camera1", "/imu/camera0",
49 "/imu/camera1"};
James Kuszmaul313e9ce2024-02-11 17:47:33 -080050
51size_t CameraIndexForName(std::string_view name) {
52 for (size_t index = 0; index < kDetectionChannels.size(); ++index) {
53 if (name == kDetectionChannels.at(index)) {
54 return index;
55 }
56 }
57 LOG(FATAL) << "No camera channel named " << name;
58}
59
60std::map<uint64_t, Localizer::Transform> GetTargetLocations(
61 const Constants &constants) {
62 CHECK(constants.has_common());
63 CHECK(constants.common()->has_target_map());
64 CHECK(constants.common()->target_map()->has_target_poses());
65 std::map<uint64_t, Localizer::Transform> transforms;
66 for (const frc971::vision::TargetPoseFbs *target :
67 *constants.common()->target_map()->target_poses()) {
68 CHECK(target->has_id());
69 CHECK(target->has_position());
70 CHECK(target->has_orientation());
71 CHECK_EQ(0u, transforms.count(target->id()));
72 transforms[target->id()] = PoseToTransform(target);
73 }
74 return transforms;
75}
James Kuszmaul86116c22024-03-15 22:50:34 -070076
77// Returns the "nominal" covariance of localizer---i.e., the values to which it
78// tends to converge during normal operation. By initializing the localizer's
79// covariance this way, we reduce the likelihood that the first few corrections
80// we receive will result in insane jumps in robot state.
81Eigen::Matrix<double, Localizer::HybridEkf::kNStates,
82 Localizer::HybridEkf::kNStates>
83NominalCovariance() {
84 Eigen::Matrix<double, Localizer::HybridEkf::kNStates,
85 Localizer::HybridEkf::kNStates>
86 P_transpose;
87 // Grabbed from when the robot was in a steady-state.
88 P_transpose << 0.00344391020344026, 2.78255540964953e-05,
89 -3.44257436790434e-09, 1.57165298196431e-09, 0.0207259965606711,
90 1.57165298180587e-09, 0.0207259965606711, 0.054775354511474,
91 0.0547753545094318, 3.6435938125014e-13, 0.0136249573295751,
92 -1.00705421392865e-05, 2.78255540964953e-05, 0.00107448929200992,
93 -7.42495169208041e-08, 1.85634700506266e-11, 0.000244343925617656,
94 1.85634874205036e-11, 0.000244343925617656, 0.000645553479721632,
95 0.000645553790286344, -3.98991820983687e-11, 0.000160471639203211,
96 0.00085437373557969, -3.44257436791122e-09, -7.42495169208033e-08,
97 8.84891122456971e-05, 5.60929454430362e-16, -3.19015358072956e-08,
98 1.00798618104673e-15, -3.19015357689791e-08, 4.05905848804053e-07,
99 -5.37043312466153e-07, 2.59177623699213e-08, -3.54286115799832e-08,
100 -2.46295184320124e-07, 1.57165298196416e-09, 1.85634700506217e-11,
101 5.60929459005148e-16, 4.99891338811926e-09, 3.59436612693873e-08,
102 3.54690022095621e-18, 3.59436612693713e-08, 1.47025442116767e-07,
103 1.47035806190949e-07, 4.66877989234937e-08, -1.08209016210542e-08,
104 -3.39984473837553e-14, 0.0207259965606711, 0.000244343925617655,
105 -3.19015358072649e-08, 3.59436612693935e-08, 0.301240404540565,
106 3.59436612690168e-08, 0.301240404540535, 1.05741200222346,
107 1.0574120022184, 8.29472747900822e-13, 0.138401597893958,
108 -1.43941751907531e-06, 1.57165298180564e-09, 1.85634874205096e-11,
109 1.00798617244172e-15, 3.54690020212816e-18, 3.59436612690224e-08,
110 4.99891338811924e-09, 3.59436612690048e-08, 1.4703580619019e-07,
111 1.47025442115683e-07, -4.66877989234395e-08, -1.0820901621393e-08,
112 -3.40023588372784e-14, 0.0207259965606711, 0.000244343925617655,
113 -3.19015357689244e-08, 3.59436612693859e-08, 0.301240404540535,
114 3.5943661269025e-08, 0.301240404540565, 1.05741200222289,
115 1.05741200221897, 8.29752131358864e-13, 0.138401597893958,
116 -1.43941751907531e-06, 0.0547753545114739, 0.000645553479721628,
117 4.05905848802199e-07, 1.4702544211661e-07, 1.05741200222346,
118 1.47035806190016e-07, 1.05741200222289, 5.51003071369415,
119 4.85571868991385, 3.11581831710161e-06, 0.388669918077443,
120 -2.97795819369728e-06, 0.054775354509432, 0.000645553790286345,
121 -5.37043312465425e-07, 1.47035806190839e-07, 1.0574120022184,
122 1.47025442115792e-07, 1.05741200221897, 4.85571868991385,
123 5.51003071367444, -3.11581462746269e-06, 0.388669918072973,
124 -2.97799067538699e-06, 3.64359250152554e-13, -3.98991820983e-11,
125 2.5917762369921e-08, 4.66877989234987e-08, 8.2947423101614e-13,
126 -4.66877989234886e-08, 8.29754326977491e-13, 3.11581831710969e-06,
127 -3.11581462747612e-06, 0.212136173309098, 8.06835372350592e-13,
128 8.80190080862899e-12, 0.0136249573295751, 0.000160471639203211,
129 -3.54286115799303e-08, -1.08209016210412e-08, 0.138401597893958,
130 -1.08209016213997e-08, 0.138401597893958, 0.388669918077444,
131 0.388669918072972, 8.06834601598773e-13, 0.187427410345505,
132 -1.28632768080328e-06, -1.00705421392865e-05, 0.000854373735579689,
133 -2.46295184320122e-07, -3.39984473838037e-14, -1.4394175190755e-06,
134 -3.40023588373113e-14, -1.4394175190755e-06, -2.97795819369787e-06,
135 -2.9779906753875e-06, 8.80190080900245e-12, -1.28632768080338e-06,
136 0.00381653175156393;
137 return P_transpose.transpose();
138}
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800139} // namespace
140
141std::array<Localizer::CameraState, Localizer::kNumCameras>
142Localizer::MakeCameras(const Constants &constants, aos::EventLoop *event_loop) {
143 CHECK(constants.has_cameras());
144 std::array<Localizer::CameraState, Localizer::kNumCameras> cameras;
145 for (const CameraConfiguration *camera : *constants.cameras()) {
146 CHECK(camera->has_calibration());
147 const frc971::vision::calibration::CameraCalibration *calibration =
148 camera->calibration();
149 CHECK(!calibration->has_turret_extrinsics())
150 << "The 2024 robot does not have cameras on a turret.";
151 CHECK(calibration->has_node_name());
152 const std::string channel_name =
153 absl::StrFormat("/%s/camera%d", calibration->node_name()->string_view(),
154 calibration->camera_number());
155 const size_t index = CameraIndexForName(channel_name);
156 // We default-construct the extrinsics matrix to all-zeros; use that to
157 // sanity-check whether we have populated the matrix yet or not.
158 CHECK(cameras.at(index).extrinsics.norm() == 0)
159 << "Got multiple calibrations for "
160 << calibration->node_name()->string_view();
161 CHECK(calibration->has_fixed_extrinsics());
162 cameras.at(index).extrinsics =
163 frc971::control_loops::drivetrain::FlatbufferToTransformationMatrix(
164 *calibration->fixed_extrinsics());
165 cameras.at(index).debug_sender =
166 event_loop->MakeSender<VisualizationStatic>(channel_name);
167 }
168 for (const CameraState &camera : cameras) {
169 CHECK(camera.extrinsics.norm() != 0) << "Missing a camera calibration.";
170 }
171 return cameras;
172}
173
174Localizer::Localizer(aos::EventLoop *event_loop)
175 : event_loop_(event_loop),
176 constants_fetcher_(event_loop),
177 dt_config_(
178 frc971::control_loops::drivetrain::DrivetrainConfig<double>::
179 FromFlatbuffer(*CHECK_NOTNULL(
180 constants_fetcher_.constants().common()->drivetrain()))),
181 cameras_(MakeCameras(constants_fetcher_.constants(), event_loop)),
182 target_poses_(GetTargetLocations(constants_fetcher_.constants())),
183 down_estimator_(dt_config_),
James Kuszmaul86116c22024-03-15 22:50:34 -0700184 // Force the dt to 1 ms (the nominal IMU frequency) since we have observed
185 // issues with timing on the orins.
186 // TODO(james): Ostensibly, we should be able to use the timestamps from
187 // the IMU board itself for exactly this; however, I am currently worried
188 // about the impacts of clock drift in using that.
189 ekf_(dt_config_, std::chrono::milliseconds(1)),
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800190 observations_(&ekf_),
James Kuszmaul86116c22024-03-15 22:50:34 -0700191 xyz_observations_(&ekf_),
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800192 imu_watcher_(event_loop, dt_config_,
193 y2024::constants::Values::DrivetrainEncoderToMeters(1),
194 std::bind(&Localizer::HandleImu, this, std::placeholders::_1,
195 std::placeholders::_2, std::placeholders::_3,
196 std::placeholders::_4, std::placeholders::_5),
197 frc971::controls::ImuWatcher::TimestampSource::kPi),
198 utils_(event_loop),
199 status_sender_(event_loop->MakeSender<Status>("/localizer")),
200 output_sender_(event_loop->MakeSender<frc971::controls::LocalizerOutput>(
201 "/localizer")),
202 server_statistics_fetcher_(
203 event_loop_->MakeFetcher<aos::message_bridge::ServerStatistics>(
204 "/aos")),
205 client_statistics_fetcher_(
206 event_loop_->MakeFetcher<aos::message_bridge::ClientStatistics>(
James Kuszmaul86116c22024-03-15 22:50:34 -0700207 "/aos")),
208 control_fetcher_(event_loop_->MakeFetcher<
209 frc971::control_loops::drivetrain::LocalizerControl>(
210 "/drivetrain")) {
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800211 if (dt_config_.is_simulated) {
212 down_estimator_.assume_perfect_gravity();
213 }
214
215 for (size_t camera_index = 0; camera_index < kNumCameras; ++camera_index) {
216 const std::string_view channel_name = kDetectionChannels.at(camera_index);
217 const aos::Channel *const channel = CHECK_NOTNULL(
218 event_loop->GetChannel<frc971::vision::TargetMap>(channel_name));
219 event_loop->MakeWatcher(
220 channel_name, [this, channel,
221 camera_index](const frc971::vision::TargetMap &targets) {
222 CHECK(targets.has_target_poses());
223 CHECK(targets.has_monotonic_timestamp_ns());
224 const std::optional<aos::monotonic_clock::duration> clock_offset =
225 utils_.ClockOffset(channel->source_node()->string_view());
226 if (!clock_offset.has_value()) {
227 VLOG(1) << "Rejecting image due to disconnected message bridge at "
228 << event_loop_->monotonic_now();
229 cameras_.at(camera_index)
230 .rejection_counter.IncrementError(
231 RejectionReason::MESSAGE_BRIDGE_DISCONNECTED);
232 return;
233 }
234 const aos::monotonic_clock::time_point orin_capture_time(
235 std::chrono::nanoseconds(targets.monotonic_timestamp_ns()) -
236 clock_offset.value());
237 if (orin_capture_time > event_loop_->context().monotonic_event_time) {
238 VLOG(1) << "Rejecting image due to being from future at "
239 << event_loop_->monotonic_now() << " with timestamp of "
240 << orin_capture_time << " and event time pf "
241 << event_loop_->context().monotonic_event_time;
242 cameras_.at(camera_index)
243 .rejection_counter.IncrementError(
244 RejectionReason::IMAGE_FROM_FUTURE);
245 return;
246 }
247 auto debug_builder =
248 cameras_.at(camera_index).debug_sender.MakeStaticBuilder();
249 auto target_debug_list = debug_builder->add_targets();
250 // The static_length should already be 20.
251 CHECK(target_debug_list->reserve(20));
252 for (const frc971::vision::TargetPoseFbs *target :
253 *targets.target_poses()) {
254 VLOG(1) << "Handling target from " << camera_index;
255 HandleTarget(camera_index, orin_capture_time, *target,
256 target_debug_list->emplace_back());
257 }
258 StatisticsForCamera(cameras_.at(camera_index),
259 debug_builder->add_statistics());
260 debug_builder.CheckOk(debug_builder.Send());
261 SendStatus();
262 });
263 }
264
265 event_loop_->AddPhasedLoop([this](int) { SendOutput(); },
266 std::chrono::milliseconds(20));
267
268 event_loop_->MakeWatcher(
269 "/drivetrain",
270 [this](
271 const frc971::control_loops::drivetrain::LocalizerControl &control) {
James Kuszmaul86116c22024-03-15 22:50:34 -0700272 HandleControl(control);
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800273 });
274
275 ekf_.set_ignore_accel(true);
276 // Priority should be lower than the imu reading process, but non-zero.
277 event_loop->SetRuntimeRealtimePriority(10);
278 event_loop->OnRun([this, event_loop]() {
279 ekf_.ResetInitialState(event_loop->monotonic_now(),
James Kuszmaul86116c22024-03-15 22:50:34 -0700280 HybridEkf::State::Zero(), NominalCovariance());
281 if (control_fetcher_.Fetch()) {
282 HandleControl(*control_fetcher_.get());
283 }
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800284 });
285}
286
James Kuszmaul86116c22024-03-15 22:50:34 -0700287void Localizer::HandleControl(
288 const frc971::control_loops::drivetrain::LocalizerControl &control) {
289 // This is triggered whenever we need to force the X/Y/(maybe theta)
290 // position of the robot to a particular point---e.g., during pre-match
291 // setup, or when commanded by a button on the driverstation.
292
293 // For some forms of reset, we choose to keep our current yaw estimate
294 // rather than overriding it from the control message.
295 const double theta = control.keep_current_theta()
296 ? ekf_.X_hat(StateIdx::kTheta)
297 : control.theta();
298 // Encoder values need to be reset based on the current values to ensure
299 // that we don't get weird corrections on the next encoder update.
300 const double left_encoder = ekf_.X_hat(StateIdx::kLeftEncoder);
301 const double right_encoder = ekf_.X_hat(StateIdx::kRightEncoder);
302 ekf_.ResetInitialState(t_,
303 (HybridEkf::State() << control.x(), control.y(), theta,
304 left_encoder, 0, right_encoder, 0, 0, 0, 0, 0, 0)
305 .finished(),
306 NominalCovariance());
307 VLOG(1) << "Reset state";
308}
309
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800310void Localizer::HandleImu(aos::monotonic_clock::time_point /*sample_time_pico*/,
311 aos::monotonic_clock::time_point sample_time_orin,
312 std::optional<Eigen::Vector2d> /*encoders*/,
313 Eigen::Vector3d gyro, Eigen::Vector3d accel) {
314 std::optional<Eigen::Vector2d> encoders = utils_.Encoders(sample_time_orin);
315 last_encoder_readings_ = encoders;
James Kuszmaul86116c22024-03-15 22:50:34 -0700316 VLOG(1) << "Got encoders";
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800317 if (t_ == aos::monotonic_clock::min_time) {
318 t_ = sample_time_orin;
319 }
320 if (t_ + 10 * frc971::controls::ImuWatcher::kNominalDt < sample_time_orin) {
321 t_ = sample_time_orin;
322 ++clock_resets_;
323 }
324 const aos::monotonic_clock::duration dt = sample_time_orin - t_;
325 t_ = sample_time_orin;
326 // We don't actually use the down estimator currently, but it's really
327 // convenient for debugging.
328 down_estimator_.Predict(gyro, accel, dt);
329 const double yaw_rate = (dt_config_.imu_transform * gyro)(2);
James Kuszmaul2700e0f2024-03-16 16:45:48 -0700330 ekf_.UpdateEncodersAndGyro(
331 encoders.has_value() ? std::make_optional<double>(encoders.value()(0))
332 : std::nullopt,
333 encoders.has_value() ? std::make_optional<double>(encoders.value()(1))
334 : std::nullopt,
335 yaw_rate, utils_.VoltageOrZero(sample_time_orin), accel, t_);
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800336 SendStatus();
337}
338
339void Localizer::RejectImage(int camera_index, RejectionReason reason,
340 TargetEstimateDebugStatic *builder) {
341 if (builder != nullptr) {
342 builder->set_accepted(false);
343 builder->set_rejection_reason(reason);
344 }
345 cameras_.at(camera_index).rejection_counter.IncrementError(reason);
346}
347
348// Only use april tags present in the target map; this method has also been used
349// (in the past) for ignoring april tags that tend to produce problematic
350// readings.
351bool Localizer::UseAprilTag(uint64_t target_id) {
James Kuszmaul86116c22024-03-15 22:50:34 -0700352 if (target_poses_.count(target_id) == 0) {
353 return false;
354 }
355 return true;
356}
357
358bool Localizer::DeweightAprilTag(uint64_t target_id) {
359 const flatbuffers::Vector<uint64_t> *ignore_tags = nullptr;
360
361 switch (utils_.Alliance()) {
362 case aos::Alliance::kRed:
363 ignore_tags = CHECK_NOTNULL(
364 constants_fetcher_.constants().common()->ignore_targets()->red());
365 break;
366 case aos::Alliance::kBlue:
367 ignore_tags = CHECK_NOTNULL(
368 constants_fetcher_.constants().common()->ignore_targets()->blue());
369 break;
370 case aos::Alliance::kInvalid:
371 return false;
372 }
373 return std::find(ignore_tags->begin(), ignore_tags->end(), target_id) !=
374 ignore_tags->end();
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800375}
376
377namespace {
378// Converts a camera transformation matrix from treating the +Z axis from
379// pointing straight out the lens to having the +X pointing straight out the
380// lens, with +Z going "up" (i.e., -Y in the normal convention) and +Y going
381// leftwards (i.e., -X in the normal convention).
382Localizer::Transform ZToXCamera(const Localizer::Transform &transform) {
383 return transform *
384 Eigen::Matrix4d{
385 {0, -1, 0, 0}, {0, 0, -1, 0}, {1, 0, 0, 0}, {0, 0, 0, 1}};
386}
387} // namespace
388
389void Localizer::HandleTarget(
390 int camera_index, const aos::monotonic_clock::time_point capture_time,
391 const frc971::vision::TargetPoseFbs &target,
392 TargetEstimateDebugStatic *debug_builder) {
393 ++total_candidate_targets_;
394 ++cameras_.at(camera_index).total_candidate_targets;
395 const uint64_t target_id = target.id();
396
397 if (debug_builder == nullptr) {
398 AOS_LOG(ERROR, "Dropped message from debug vector.");
399 } else {
400 debug_builder->set_camera(camera_index);
401 debug_builder->set_image_age_sec(aos::time::DurationInSeconds(
402 event_loop_->monotonic_now() - capture_time));
403 debug_builder->set_image_monotonic_timestamp_ns(
404 std::chrono::duration_cast<std::chrono::nanoseconds>(
405 capture_time.time_since_epoch())
406 .count());
407 debug_builder->set_april_tag(target_id);
408 }
409 VLOG(2) << aos::FlatbufferToJson(&target);
410 if (!UseAprilTag(target_id)) {
411 VLOG(1) << "Rejecting target due to invalid ID " << target_id;
412 RejectImage(camera_index, RejectionReason::NO_SUCH_TARGET, debug_builder);
413 return;
414 }
James Kuszmaul86116c22024-03-15 22:50:34 -0700415 double april_tag_noise_scalar = 1.0;
416 if (DeweightAprilTag(target_id)) {
417 if (!FLAGS_always_use_extra_tags && utils_.MaybeInAutonomous()) {
418 VLOG(1) << "Rejecting target due to auto invalid ID " << target_id;
419 RejectImage(camera_index, RejectionReason::NO_SUCH_TARGET, debug_builder);
420 return;
421 } else {
422 april_tag_noise_scalar = 10.0;
423 }
424 }
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800425
426 const Transform &H_field_target = target_poses_.at(target_id);
427 const Transform &H_robot_camera = cameras_.at(camera_index).extrinsics;
428
429 const Transform H_camera_target = PoseToTransform(&target);
430
431 // In order to do the EKF correction, we determine the expected state based
432 // on the state at the time the image was captured; however, we insert the
433 // correction update itself at the current time. This is technically not
434 // quite correct, but saves substantial CPU usage & code complexity by
435 // making it so that we don't have to constantly rewind the entire EKF
436 // history.
437 const std::optional<State> state_at_capture =
438 ekf_.LastStateBeforeTime(capture_time);
439
440 if (!state_at_capture.has_value()) {
441 VLOG(1) << "Rejecting image due to being too old.";
442 return RejectImage(camera_index, RejectionReason::IMAGE_TOO_OLD,
443 debug_builder);
444 } else if (target.pose_error() > FLAGS_max_pose_error) {
445 VLOG(1) << "Rejecting target due to high pose error "
446 << target.pose_error();
447 return RejectImage(camera_index, RejectionReason::HIGH_POSE_ERROR,
448 debug_builder);
449 } else if (target.pose_error_ratio() > FLAGS_max_pose_error_ratio) {
450 VLOG(1) << "Rejecting target due to high pose error ratio "
451 << target.pose_error_ratio();
452 return RejectImage(camera_index, RejectionReason::HIGH_POSE_ERROR_RATIO,
453 debug_builder);
454 }
455
456 Corrector corrector(state_at_capture.value(), H_field_target, H_robot_camera,
457 H_camera_target);
458 const double distance_to_target = corrector.observed()(Corrector::kDistance);
459
460 // Heading, distance, skew at 1 meter.
461 Eigen::Matrix<double, 3, 1> noises(0.01, 0.05, 0.05);
James Kuszmaul86116c22024-03-15 22:50:34 -0700462 const double distance_noise_scalar =
463 std::min(1.0, std::pow(distance_to_target, 2.0));
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800464 noises(Corrector::kDistance) *= distance_noise_scalar;
465 noises(Corrector::kSkew) *= distance_noise_scalar;
466 // TODO(james): This is leftover from last year; figure out if we want it.
467 // Scale noise by the distortion factor for this detection
468 noises *= (1.0 + FLAGS_distortion_noise_scalar * target.distortion_factor());
James Kuszmaul86116c22024-03-15 22:50:34 -0700469 noises *= april_tag_noise_scalar;
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800470
471 Eigen::Matrix3d R = Eigen::Matrix3d::Zero();
472 R.diagonal() = noises.cwiseAbs2();
James Kuszmaul86116c22024-03-15 22:50:34 -0700473 const Eigen::Vector3d camera_position =
474 corrector.observed_camera_pose().abs_pos();
475 // Calculate the camera-to-robot transformation matrix ignoring the
476 // pitch/roll of the camera.
477 const Transform H_camera_robot_stripped =
478 frc971::control_loops::Pose(ZToXCamera(H_robot_camera))
479 .AsTransformationMatrix()
480 .inverse();
481 const frc971::control_loops::Pose measured_pose(
482 corrector.observed_camera_pose().AsTransformationMatrix() *
483 H_camera_robot_stripped);
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800484 if (debug_builder != nullptr) {
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800485 debug_builder->set_camera_x(camera_position.x());
486 debug_builder->set_camera_y(camera_position.y());
487 debug_builder->set_camera_theta(
488 corrector.observed_camera_pose().abs_theta());
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800489 debug_builder->set_implied_robot_x(measured_pose.rel_pos().x());
490 debug_builder->set_implied_robot_y(measured_pose.rel_pos().y());
491 debug_builder->set_implied_robot_theta(measured_pose.rel_theta());
492
493 Corrector::PopulateMeasurement(corrector.expected(),
494 debug_builder->add_expected_observation());
495 Corrector::PopulateMeasurement(corrector.observed(),
496 debug_builder->add_actual_observation());
497 Corrector::PopulateMeasurement(noises, debug_builder->add_modeled_noise());
498 }
499
500 const double camera_yaw_error =
501 aos::math::NormalizeAngle(corrector.expected_camera_pose().abs_theta() -
502 corrector.observed_camera_pose().abs_theta());
503 constexpr double kDegToRad = M_PI / 180.0;
504
505 const double robot_speed =
506 (state_at_capture.value()(StateIdx::kLeftVelocity) +
507 state_at_capture.value()(StateIdx::kRightVelocity)) /
508 2.0;
509 const double yaw_threshold =
510 (utils_.MaybeInAutonomous() ? FLAGS_max_implied_yaw_error
511 : FLAGS_max_implied_teleop_yaw_error) *
512 kDegToRad;
513
James Kuszmaul86116c22024-03-15 22:50:34 -0700514 if (target.distortion_factor() > FLAGS_max_distortion) {
515 VLOG(1) << "Rejecting target due to high distortion.";
516 return RejectImage(camera_index, RejectionReason::HIGH_DISTORTION,
517 debug_builder);
518 } else if (utils_.MaybeInAutonomous() &&
519 (std::abs(robot_speed) > FLAGS_max_auto_image_robot_speed)) {
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800520 return RejectImage(camera_index, RejectionReason::ROBOT_TOO_FAST,
521 debug_builder);
522 } else if (std::abs(camera_yaw_error) > yaw_threshold) {
523 return RejectImage(camera_index, RejectionReason::HIGH_IMPLIED_YAW_ERROR,
524 debug_builder);
525 } else if (distance_to_target > FLAGS_max_distance_to_target) {
526 return RejectImage(camera_index, RejectionReason::HIGH_DISTANCE_TO_TARGET,
527 debug_builder);
528 }
529
530 const Input U = ekf_.MostRecentInput();
James Kuszmaul86116c22024-03-15 22:50:34 -0700531 VLOG(1) << "previous state " << ekf_.X_hat().transpose();
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800532 const State prior_state = ekf_.X_hat();
533 // For the correction step, instead of passing in the measurement directly,
534 // we pass in (0, 0, 0) as the measurement and then for the expected
535 // measurement (Zhat) we calculate the error between the pose implied by
536 // the camera measurement and the current estimate of the
537 // pose. This doesn't affect any of the math, it just makes the code a bit
538 // more convenient to write given the Correct() interface we already have.
James Kuszmaul86116c22024-03-15 22:50:34 -0700539 if (FLAGS_do_xytheta_corrections) {
540 Eigen::Vector3d Z(measured_pose.rel_pos().x(), measured_pose.rel_pos().y(),
541 measured_pose.rel_theta());
542 Eigen::Matrix<double, 3, 1> xyz_noises(0.2, 0.2, 0.5);
543 xyz_noises *= distance_noise_scalar;
544 xyz_noises *= april_tag_noise_scalar;
545 // Scale noise by the distortion factor for this detection
546 xyz_noises *=
547 (1.0 + FLAGS_distortion_noise_scalar * target.distortion_factor());
548
549 Eigen::Matrix3d R_xyz = Eigen::Matrix3d::Zero();
550 R_xyz.diagonal() = xyz_noises.cwiseAbs2();
551 xyz_observations_.CorrectKnownH(Eigen::Vector3d::Zero(), &U,
552 XyzCorrector(state_at_capture.value(), Z),
553 R_xyz, t_);
554 } else {
555 observations_.CorrectKnownH(Eigen::Vector3d::Zero(), &U, corrector, R, t_);
556 }
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800557 ++total_accepted_targets_;
558 ++cameras_.at(camera_index).total_accepted_targets;
James Kuszmaul86116c22024-03-15 22:50:34 -0700559 VLOG(1) << "new state " << ekf_.X_hat().transpose();
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800560 if (debug_builder != nullptr) {
561 debug_builder->set_correction_x(ekf_.X_hat()(StateIdx::kX) -
562 prior_state(StateIdx::kX));
563 debug_builder->set_correction_y(ekf_.X_hat()(StateIdx::kY) -
564 prior_state(StateIdx::kY));
565 debug_builder->set_correction_theta(ekf_.X_hat()(StateIdx::kTheta) -
566 prior_state(StateIdx::kTheta));
567 debug_builder->set_accepted(true);
James Kuszmaul86116c22024-03-15 22:50:34 -0700568 debug_builder->set_expected_robot_x(ekf_.X_hat()(StateIdx::kX));
569 debug_builder->set_expected_robot_y(ekf_.X_hat()(StateIdx::kY));
570 debug_builder->set_expected_robot_theta(ekf_.X_hat()(StateIdx::kTheta));
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800571 }
572}
573
574void Localizer::SendOutput() {
575 auto builder = output_sender_.MakeBuilder();
576 frc971::controls::LocalizerOutput::Builder output_builder =
577 builder.MakeBuilder<frc971::controls::LocalizerOutput>();
578 output_builder.add_monotonic_timestamp_ns(
579 std::chrono::duration_cast<std::chrono::nanoseconds>(
580 event_loop_->context().monotonic_event_time.time_since_epoch())
581 .count());
582 output_builder.add_x(ekf_.X_hat(StateIdx::kX));
583 output_builder.add_y(ekf_.X_hat(StateIdx::kY));
584 output_builder.add_theta(ekf_.X_hat(StateIdx::kTheta));
585 output_builder.add_zeroed(imu_watcher_.zeroer().Zeroed());
586 output_builder.add_image_accepted_count(total_accepted_targets_);
587 const Eigen::Quaterniond &orientation =
588 Eigen::AngleAxis<double>(ekf_.X_hat(StateIdx::kTheta),
589 Eigen::Vector3d::UnitZ()) *
590 down_estimator_.X_hat();
591 frc971::controls::Quaternion quaternion;
592 quaternion.mutate_x(orientation.x());
593 quaternion.mutate_y(orientation.y());
594 quaternion.mutate_z(orientation.z());
595 quaternion.mutate_w(orientation.w());
596 output_builder.add_orientation(&quaternion);
597 server_statistics_fetcher_.Fetch();
598 client_statistics_fetcher_.Fetch();
599
600 bool orins_connected = true;
601
602 if (server_statistics_fetcher_.get()) {
603 for (const auto *orin_server_status :
604 *server_statistics_fetcher_->connections()) {
605 if (orin_server_status->state() ==
606 aos::message_bridge::State::DISCONNECTED) {
607 orins_connected = false;
608 }
609 }
610 }
611
612 if (client_statistics_fetcher_.get()) {
613 for (const auto *pi_client_status :
614 *client_statistics_fetcher_->connections()) {
615 if (pi_client_status->state() ==
616 aos::message_bridge::State::DISCONNECTED) {
617 orins_connected = false;
618 }
619 }
620 }
621
622 // The output message is year-agnostic, and retains "pi" naming for histrocial
623 // reasons.
624 output_builder.add_all_pis_connected(orins_connected);
625 builder.CheckOk(builder.Send(output_builder.Finish()));
626}
627
628flatbuffers::Offset<frc971::control_loops::drivetrain::LocalizerState>
629Localizer::PopulateState(const State &X_hat,
630 flatbuffers::FlatBufferBuilder *fbb) {
631 frc971::control_loops::drivetrain::LocalizerState::Builder builder(*fbb);
632 builder.add_x(X_hat(StateIdx::kX));
633 builder.add_y(X_hat(StateIdx::kY));
Stephan Pleines78df16d2024-04-03 20:45:26 -0700634 builder.add_theta(aos::math::NormalizeAngle(X_hat(StateIdx::kTheta)));
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800635 builder.add_left_velocity(X_hat(StateIdx::kLeftVelocity));
636 builder.add_right_velocity(X_hat(StateIdx::kRightVelocity));
637 builder.add_left_encoder(X_hat(StateIdx::kLeftEncoder));
638 builder.add_right_encoder(X_hat(StateIdx::kRightEncoder));
639 builder.add_left_voltage_error(X_hat(StateIdx::kLeftVoltageError));
640 builder.add_right_voltage_error(X_hat(StateIdx::kRightVoltageError));
641 builder.add_angular_error(X_hat(StateIdx::kAngularError));
642 builder.add_longitudinal_velocity_offset(
643 X_hat(StateIdx::kLongitudinalVelocityOffset));
644 builder.add_lateral_velocity(X_hat(StateIdx::kLateralVelocity));
645 return builder.Finish();
646}
647
648flatbuffers::Offset<ImuStatus> Localizer::PopulateImu(
649 flatbuffers::FlatBufferBuilder *fbb) const {
650 const auto zeroer_offset = imu_watcher_.zeroer().PopulateStatus(fbb);
651 const auto failures_offset = imu_watcher_.PopulateImuFailures(fbb);
652 ImuStatus::Builder builder(*fbb);
653 builder.add_zeroed(imu_watcher_.zeroer().Zeroed());
654 builder.add_faulted_zero(imu_watcher_.zeroer().Faulted());
655 builder.add_zeroing(zeroer_offset);
656 if (imu_watcher_.pico_offset().has_value()) {
657 builder.add_board_offset_ns(imu_watcher_.pico_offset().value().count());
658 builder.add_board_offset_error_ns(imu_watcher_.pico_offset_error().count());
659 }
660 if (last_encoder_readings_.has_value()) {
661 builder.add_left_encoder(last_encoder_readings_.value()(0));
662 builder.add_right_encoder(last_encoder_readings_.value()(1));
663 }
664 builder.add_imu_failures(failures_offset);
665 return builder.Finish();
666}
667
668flatbuffers::Offset<CumulativeStatistics> Localizer::StatisticsForCamera(
669 const CameraState &camera, flatbuffers::FlatBufferBuilder *fbb) {
670 const auto counts_offset = camera.rejection_counter.PopulateCounts(fbb);
671 CumulativeStatistics::Builder stats_builder(*fbb);
672 stats_builder.add_total_accepted(camera.total_accepted_targets);
673 stats_builder.add_total_candidates(camera.total_candidate_targets);
674 stats_builder.add_rejection_reasons(counts_offset);
675 return stats_builder.Finish();
676}
677
678void Localizer::StatisticsForCamera(const CameraState &camera,
679 CumulativeStatisticsStatic *builder) {
680 camera.rejection_counter.PopulateCountsStaticFbs(
681 builder->add_rejection_reasons());
682 builder->set_total_accepted(camera.total_accepted_targets);
683 builder->set_total_candidates(camera.total_candidate_targets);
684}
685
686void Localizer::SendStatus() {
687 auto builder = status_sender_.MakeBuilder();
688 std::array<flatbuffers::Offset<CumulativeStatistics>, kNumCameras>
689 stats_offsets;
690 for (size_t ii = 0; ii < kNumCameras; ++ii) {
691 stats_offsets.at(ii) = StatisticsForCamera(cameras_.at(ii), builder.fbb());
692 }
693 auto stats_offset =
694 builder.fbb()->CreateVector(stats_offsets.data(), stats_offsets.size());
695 auto down_estimator_offset =
696 down_estimator_.PopulateStatus(builder.fbb(), t_);
697 auto imu_offset = PopulateImu(builder.fbb());
698 auto state_offset = PopulateState(ekf_.X_hat(), builder.fbb());
James Kuszmaul86116c22024-03-15 22:50:34 -0700699 // covariance is a square; we use the number of rows in the state as the rows
700 // and cols of the covariance.
701 auto covariance_offset =
702 frc971::FromEigen<State::RowsAtCompileTime, State::RowsAtCompileTime>(
703 ekf_.P(), builder.fbb());
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800704 Status::Builder status_builder = builder.MakeBuilder<Status>();
705 status_builder.add_state(state_offset);
706 status_builder.add_down_estimator(down_estimator_offset);
707 status_builder.add_imu(imu_offset);
708 status_builder.add_statistics(stats_offset);
James Kuszmaul86116c22024-03-15 22:50:34 -0700709 status_builder.add_ekf_covariance(covariance_offset);
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800710 builder.CheckOk(builder.Send(status_builder.Finish()));
711}
712
713Eigen::Vector3d Localizer::Corrector::HeadingDistanceSkew(
714 const Pose &relative_pose) {
715 const double heading = relative_pose.heading();
716 const double distance = relative_pose.xy_norm();
717 const double skew =
718 ::aos::math::NormalizeAngle(relative_pose.rel_theta() - heading);
719 return {heading, distance, skew};
720}
721
722Localizer::Corrector Localizer::Corrector::CalculateHeadingDistanceSkewH(
723 const State &state_at_capture, const Transform &H_field_target,
724 const Transform &H_robot_camera, const Transform &H_camera_target) {
725 const Transform H_field_camera = H_field_target * H_camera_target.inverse();
726 const Pose expected_robot_pose(
727 {state_at_capture(StateIdx::kX), state_at_capture(StateIdx::kY), 0.0},
728 state_at_capture(StateIdx::kTheta));
729 // Observed position on the field, reduced to just the 2-D pose.
730 const Pose observed_camera(ZToXCamera(H_field_camera));
731 const Pose expected_camera(expected_robot_pose.AsTransformationMatrix() *
732 ZToXCamera(H_robot_camera));
733 const Pose nominal_target(ZToXCamera(H_field_target));
734 const Pose observed_target = nominal_target.Rebase(&observed_camera);
735 const Pose expected_target = nominal_target.Rebase(&expected_camera);
736 return Localizer::Corrector{
737 expected_robot_pose,
738 observed_camera,
739 expected_camera,
740 HeadingDistanceSkew(expected_target),
741 HeadingDistanceSkew(observed_target),
742 frc971::control_loops::drivetrain::HMatrixForCameraHeadingDistanceSkew(
743 nominal_target, observed_camera)};
744}
745
746Localizer::Corrector::Corrector(const State &state_at_capture,
747 const Transform &H_field_target,
748 const Transform &H_robot_camera,
749 const Transform &H_camera_target)
750 : Corrector(CalculateHeadingDistanceSkewH(
751 state_at_capture, H_field_target, H_robot_camera, H_camera_target)) {}
752
753Localizer::Output Localizer::Corrector::H(const State &, const Input &) {
754 return expected_ - observed_;
755}
756
James Kuszmaul86116c22024-03-15 22:50:34 -0700757Localizer::Output Localizer::XyzCorrector::H(const State &, const Input &) {
758 CHECK(Z_.allFinite());
759 Eigen::Vector3d Zhat = H_ * state_at_capture_ - Z_;
760 // Rewrap angle difference to put it back in range.
761 Zhat(2) = aos::math::NormalizeAngle(Zhat(2));
762 VLOG(1) << "Zhat " << Zhat.transpose() << " Z_ " << Z_.transpose()
763 << " state " << (H_ * state_at_capture_).transpose();
764 return Zhat;
765}
766
James Kuszmaul313e9ce2024-02-11 17:47:33 -0800767} // namespace y2024::localizer