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