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