blob: 7d7c83fecd2b2d3ce4a233d5b8298cf4f0a9fa35 [file] [log] [blame]
James Kuszmaul5398fae2020-02-17 16:44:03 -08001#include "y2020/control_loops/drivetrain/localizer.h"
2
3#include "y2020/constants.h"
4
5namespace y2020 {
6namespace control_loops {
7namespace drivetrain {
8
9namespace {
10// Converts a flatbuffer TransformationMatrix to an Eigen matrix. Technically,
11// this should be able to do a single memcpy, but the extra verbosity here seems
12// appropriate.
James Kuszmauld478f872020-03-16 20:54:27 -070013Eigen::Matrix<float, 4, 4> FlatbufferToTransformationMatrix(
James Kuszmaul5398fae2020-02-17 16:44:03 -080014 const frc971::vision::sift::TransformationMatrix &flatbuffer) {
15 CHECK_EQ(16u, CHECK_NOTNULL(flatbuffer.data())->size());
James Kuszmauld478f872020-03-16 20:54:27 -070016 Eigen::Matrix<float, 4, 4> result;
James Kuszmaul5398fae2020-02-17 16:44:03 -080017 result.setIdentity();
18 for (int row = 0; row < 4; ++row) {
19 for (int col = 0; col < 4; ++col) {
20 result(row, col) = (*flatbuffer.data())[row * 4 + col];
21 }
22 }
23 return result;
24}
James Kuszmaul958b21e2020-02-26 21:51:40 -080025
James Kuszmaulc6723cf2020-03-01 14:45:59 -080026// Indices of the pis to use.
27const std::array<std::string, 3> kPisToUse{"pi1", "pi2", "pi3"};
28
James Kuszmaul66efe832020-03-16 19:38:33 -070029// Calculates the pose implied by the camera target, just based on
30// distance/heading components.
James Kuszmauld478f872020-03-16 20:54:27 -070031Eigen::Vector3f CalculateImpliedPose(const Localizer::State &X,
32 const Eigen::Matrix4f &H_field_target,
James Kuszmaul66efe832020-03-16 19:38:33 -070033 const Localizer::Pose &pose_robot_target) {
34 // This code overrides the pose sent directly from the camera code and
35 // effectively distills it down to just a distance + heading estimate, on
36 // the presumption that these signals will tend to be much lower noise and
37 // better-conditioned than other portions of the robot pose.
38 // As such, this code assumes that the current estimate of the robot
39 // heading is correct and then, given the heading from the camera to the
40 // target and the distance from the camera to the target, calculates the
41 // position that the robot would have to be at to make the current camera
42 // heading + distance correct. This X/Y implied robot position is then
43 // used as the measurement in the EKF, rather than the X/Y that is
44 // directly returned from the vision processing. This means that
45 // the cameras will not correct any drift in the robot heading estimate
46 // but will compensate for X/Y position in a way that prioritizes keeping
47 // an accurate distance + heading to the goal.
48
49 // Calculate the heading to the robot in the target's coordinate frame.
James Kuszmauld478f872020-03-16 20:54:27 -070050 const float implied_heading_from_target = aos::math::NormalizeAngle(
James Kuszmaul66efe832020-03-16 19:38:33 -070051 pose_robot_target.heading() + M_PI + X(Localizer::StateIdx::kTheta));
James Kuszmauld478f872020-03-16 20:54:27 -070052 const float implied_distance = pose_robot_target.xy_norm();
53 const Eigen::Vector4f robot_pose_in_target_frame(
James Kuszmaul66efe832020-03-16 19:38:33 -070054 implied_distance * std::cos(implied_heading_from_target),
55 implied_distance * std::sin(implied_heading_from_target), 0, 1);
James Kuszmauld478f872020-03-16 20:54:27 -070056 const Eigen::Vector4f implied_pose =
James Kuszmaul66efe832020-03-16 19:38:33 -070057 H_field_target * robot_pose_in_target_frame;
58 return implied_pose.topRows<3>();
59}
60
James Kuszmaul5398fae2020-02-17 16:44:03 -080061} // namespace
62
63Localizer::Localizer(
64 aos::EventLoop *event_loop,
65 const frc971::control_loops::drivetrain::DrivetrainConfig<double>
66 &dt_config)
James Kuszmaul958b21e2020-02-26 21:51:40 -080067 : event_loop_(event_loop),
68 dt_config_(dt_config),
69 ekf_(dt_config),
70 clock_offset_fetcher_(
71 event_loop_->MakeFetcher<aos::message_bridge::ServerStatistics>(
72 "/aos")) {
James Kuszmaul5398fae2020-02-17 16:44:03 -080073 // TODO(james): This doesn't really need to be a watcher; we could just use a
74 // fetcher for the superstructure status.
75 // This probably should be a Fetcher instead of a Watcher, but this
76 // seems simpler for the time being (although technically it should be
77 // possible to do everything we need to using just a Fetcher without
78 // even maintaining a separate buffer, but that seems overly cute).
79 event_loop_->MakeWatcher("/superstructure",
80 [this](const superstructure::Status &status) {
81 HandleSuperstructureStatus(status);
82 });
83
James Kuszmaul286b4282020-02-26 20:29:32 -080084 event_loop->OnRun([this, event_loop]() {
James Kuszmauld478f872020-03-16 20:54:27 -070085 ekf_.ResetInitialState(event_loop->monotonic_now(),
86 HybridEkf::State::Zero(), ekf_.P());
James Kuszmaul286b4282020-02-26 20:29:32 -080087 });
88
James Kuszmaulc6723cf2020-03-01 14:45:59 -080089 for (const auto &pi : kPisToUse) {
90 image_fetchers_.emplace_back(
91 event_loop_->MakeFetcher<frc971::vision::sift::ImageMatchResult>(
92 "/" + pi + "/camera"));
93 }
James Kuszmaul5398fae2020-02-17 16:44:03 -080094
95 target_selector_.set_has_target(false);
96}
97
98void Localizer::HandleSuperstructureStatus(
99 const y2020::control_loops::superstructure::Status &status) {
100 CHECK(status.has_turret());
101 turret_data_.Push({event_loop_->monotonic_now(), status.turret()->position(),
102 status.turret()->velocity()});
103}
104
105Localizer::TurretData Localizer::GetTurretDataForTime(
106 aos::monotonic_clock::time_point time) {
107 if (turret_data_.empty()) {
108 return {};
109 }
110
111 aos::monotonic_clock::duration lowest_time_error =
112 aos::monotonic_clock::duration::max();
113 TurretData best_data_match;
114 for (const auto &sample : turret_data_) {
115 const aos::monotonic_clock::duration time_error =
116 std::chrono::abs(sample.receive_time - time);
117 if (time_error < lowest_time_error) {
118 lowest_time_error = time_error;
119 best_data_match = sample;
120 }
121 }
122 return best_data_match;
123}
124
James Kuszmaul06257f42020-05-09 15:40:09 -0700125void Localizer::Update(const Eigen::Matrix<double, 2, 1> &U,
James Kuszmaul5398fae2020-02-17 16:44:03 -0800126 aos::monotonic_clock::time_point now,
127 double left_encoder, double right_encoder,
128 double gyro_rate, const Eigen::Vector3d &accel) {
James Kuszmauld478f872020-03-16 20:54:27 -0700129 ekf_.UpdateEncodersAndGyro(left_encoder, right_encoder, gyro_rate,
130 U.cast<float>(), accel.cast<float>(), now);
James Kuszmaulc6723cf2020-03-01 14:45:59 -0800131 for (size_t ii = 0; ii < kPisToUse.size(); ++ii) {
132 auto &image_fetcher = image_fetchers_[ii];
James Kuszmaul5398fae2020-02-17 16:44:03 -0800133 while (image_fetcher.FetchNext()) {
James Kuszmaul58cb1fe2020-03-07 16:18:59 -0800134 HandleImageMatch(kPisToUse[ii], *image_fetcher, now);
James Kuszmaul5398fae2020-02-17 16:44:03 -0800135 }
136 }
James Kuszmaul5398fae2020-02-17 16:44:03 -0800137}
138
139void Localizer::HandleImageMatch(
James Kuszmaul58cb1fe2020-03-07 16:18:59 -0800140 std::string_view pi, const frc971::vision::sift::ImageMatchResult &result,
141 aos::monotonic_clock::time_point now) {
James Kuszmaul958b21e2020-02-26 21:51:40 -0800142 std::chrono::nanoseconds monotonic_offset(0);
143 clock_offset_fetcher_.Fetch();
144 if (clock_offset_fetcher_.get() != nullptr) {
145 for (const auto connection : *clock_offset_fetcher_->connections()) {
146 if (connection->has_node() && connection->node()->has_name() &&
James Kuszmaulc6723cf2020-03-01 14:45:59 -0800147 connection->node()->name()->string_view() == pi) {
James Kuszmaul958b21e2020-02-26 21:51:40 -0800148 monotonic_offset =
149 std::chrono::nanoseconds(connection->monotonic_offset());
150 break;
151 }
152 }
153 }
James Kuszmaul5398fae2020-02-17 16:44:03 -0800154 aos::monotonic_clock::time_point capture_time(
James Kuszmaul958b21e2020-02-26 21:51:40 -0800155 std::chrono::nanoseconds(result.image_monotonic_timestamp_ns()) -
156 monotonic_offset);
James Kuszmaul2d8fa2a2020-03-01 13:51:50 -0800157 VLOG(1) << "Got monotonic offset of "
158 << aos::time::DurationInSeconds(monotonic_offset)
James Kuszmaul58cb1fe2020-03-07 16:18:59 -0800159 << " when at time of " << now << " and capture time estimate of "
160 << capture_time;
161 if (capture_time > now) {
James Kuszmaul2d8fa2a2020-03-01 13:51:50 -0800162 LOG(WARNING) << "Got camera frame from the future.";
163 return;
164 }
James Kuszmaul5398fae2020-02-17 16:44:03 -0800165 CHECK(result.has_camera_calibration());
166 // Per the ImageMatchResult specification, we can actually determine whether
167 // the camera is the turret camera just from the presence of the
168 // turret_extrinsics member.
169 const bool is_turret = result.camera_calibration()->has_turret_extrinsics();
170 const TurretData turret_data = GetTurretDataForTime(capture_time);
171 // Ignore readings when the turret is spinning too fast, on the assumption
172 // that the odds of screwing up the time compensation are higher.
173 // Note that the current number here is chosen pretty arbitrarily--1 rad / sec
174 // seems reasonable, but may be unnecessarily low or high.
James Kuszmauld478f872020-03-16 20:54:27 -0700175 constexpr float kMaxTurretVelocity = 1.0;
James Kuszmaul5398fae2020-02-17 16:44:03 -0800176 if (is_turret && std::abs(turret_data.velocity) > kMaxTurretVelocity) {
177 return;
178 }
179 CHECK(result.camera_calibration()->has_fixed_extrinsics());
James Kuszmauld478f872020-03-16 20:54:27 -0700180 const Eigen::Matrix<float, 4, 4> fixed_extrinsics =
James Kuszmaul5398fae2020-02-17 16:44:03 -0800181 FlatbufferToTransformationMatrix(
182 *result.camera_calibration()->fixed_extrinsics());
James Kuszmaul58cb1fe2020-03-07 16:18:59 -0800183
James Kuszmaul5398fae2020-02-17 16:44:03 -0800184 // Calculate the pose of the camera relative to the robot origin.
James Kuszmauld478f872020-03-16 20:54:27 -0700185 Eigen::Matrix<float, 4, 4> H_robot_camera = fixed_extrinsics;
James Kuszmaul5398fae2020-02-17 16:44:03 -0800186 if (is_turret) {
James Kuszmaulc51dbfe2020-02-23 15:39:00 -0800187 H_robot_camera = H_robot_camera *
James Kuszmauld478f872020-03-16 20:54:27 -0700188 frc971::control_loops::TransformationMatrixForYaw<float>(
James Kuszmaul5398fae2020-02-17 16:44:03 -0800189 turret_data.position) *
190 FlatbufferToTransformationMatrix(
191 *result.camera_calibration()->turret_extrinsics());
192 }
193
194 if (!result.has_camera_poses()) {
195 return;
196 }
197
198 for (const frc971::vision::sift::CameraPose *vision_result :
199 *result.camera_poses()) {
200 if (!vision_result->has_camera_to_target() ||
201 !vision_result->has_field_to_target()) {
202 continue;
203 }
James Kuszmauld478f872020-03-16 20:54:27 -0700204 const Eigen::Matrix<float, 4, 4> H_camera_target =
James Kuszmaul5398fae2020-02-17 16:44:03 -0800205 FlatbufferToTransformationMatrix(*vision_result->camera_to_target());
James Kuszmaul58cb1fe2020-03-07 16:18:59 -0800206
James Kuszmauld478f872020-03-16 20:54:27 -0700207 const Eigen::Matrix<float, 4, 4> H_field_target =
James Kuszmaul5398fae2020-02-17 16:44:03 -0800208 FlatbufferToTransformationMatrix(*vision_result->field_to_target());
209 // Back out the robot position that is implied by the current camera
210 // reading.
James Kuszmaulc51dbfe2020-02-23 15:39:00 -0800211 const Pose measured_pose(H_field_target *
212 (H_robot_camera * H_camera_target).inverse());
James Kuszmaul66efe832020-03-16 19:38:33 -0700213 // This "Z" is the robot pose directly implied by the camera results.
214 // Currently, we do not actually use this result directly. However, it is
215 // kept around in case we want to quickly re-enable it.
James Kuszmauld478f872020-03-16 20:54:27 -0700216 const Eigen::Matrix<float, 3, 1> Z(measured_pose.rel_pos().x(),
217 measured_pose.rel_pos().y(),
218 measured_pose.rel_theta());
James Kuszmaul58cb1fe2020-03-07 16:18:59 -0800219 // Pose of the target in the robot frame.
220 Pose pose_robot_target(H_robot_camera * H_camera_target);
James Kuszmaul5398fae2020-02-17 16:44:03 -0800221 // TODO(james): Figure out how to properly handle calculating the
222 // noise. Currently, the values are deliberately tuned so that image updates
223 // will not be trusted overly much. In theory, we should probably also be
224 // populating some cross-correlation terms.
225 // Note that these are the noise standard deviations (they are squared below
226 // to get variances).
James Kuszmauld478f872020-03-16 20:54:27 -0700227 Eigen::Matrix<float, 3, 1> noises(2.0, 2.0, 0.2);
James Kuszmaul5398fae2020-02-17 16:44:03 -0800228 // Augment the noise by the approximate rotational speed of the
229 // camera. This should help account for the fact that, while we are
230 // spinning, slight timing errors in the camera/turret data will tend to
231 // have mutch more drastic effects on the results.
232 noises *= 1.0 + std::abs((right_velocity() - left_velocity()) /
233 (2.0 * dt_config_.robot_radius) +
234 (is_turret ? turret_data.velocity : 0.0));
James Kuszmauld478f872020-03-16 20:54:27 -0700235 Eigen::Matrix3f R = Eigen::Matrix3f::Zero();
James Kuszmaul5398fae2020-02-17 16:44:03 -0800236 R.diagonal() = noises.cwiseAbs2();
James Kuszmauld478f872020-03-16 20:54:27 -0700237 Eigen::Matrix<float, HybridEkf::kNOutputs, HybridEkf::kNStates> H;
James Kuszmaul5398fae2020-02-17 16:44:03 -0800238 H.setZero();
239 H(0, StateIdx::kX) = 1;
240 H(1, StateIdx::kY) = 1;
James Kuszmaul58cb1fe2020-03-07 16:18:59 -0800241 // This is currently set to zero because we ignore the heading implied by
242 // the camera.
243 H(2, StateIdx::kTheta) = 0;
244 VLOG(1) << "Pose implied by target: " << Z.transpose()
245 << " and current pose " << x() << ", " << y() << ", " << theta()
246 << " Heading/dist/skew implied by target: "
247 << pose_robot_target.ToHeadingDistanceSkew().transpose();
James Kuszmauladd40ca2020-03-01 14:10:50 -0800248 // If the heading is off by too much, assume that we got a false-positive
249 // and don't use the correction.
James Kuszmauld478f872020-03-16 20:54:27 -0700250 if (std::abs(aos::math::DiffAngle<float>(theta(), Z(2))) > M_PI_2) {
James Kuszmauladd40ca2020-03-01 14:10:50 -0800251 AOS_LOG(WARNING, "Dropped image match due to heading mismatch.\n");
James Kuszmaul58cb1fe2020-03-07 16:18:59 -0800252 continue;
James Kuszmauladd40ca2020-03-01 14:10:50 -0800253 }
James Kuszmaul06257f42020-05-09 15:40:09 -0700254 // In order to do the EKF correction, we determine the expected state based
255 // on the state at the time the image was captured; however, we insert the
256 // correction update itself at the current time. This is technically not
257 // quite correct, but saves substantial CPU usage by making it so that we
258 // don't have to constantly rewind the entire EKF history.
259 const std::optional<State> state_at_capture =
260 ekf_.LastStateBeforeTime(capture_time);
261 if (!state_at_capture.has_value()) {
262 AOS_LOG(WARNING, "Dropped image match due to age of image.\n");
263 continue;
264 }
265 const Input U = ekf_.MostRecentInput();
James Kuszmaul66efe832020-03-16 19:38:33 -0700266 // For the correction step, instead of passing in the measurement directly,
267 // we pass in (0, 0, 0) as the measurement and then for the expected
268 // measurement (Zhat) we calculate the error between the implied and actual
269 // poses. This doesn't affect any of the math, it just makes the code a bit
270 // more convenient to write given the Correct() interface we already have.
James Kuszmaul58cb1fe2020-03-07 16:18:59 -0800271 ekf_.Correct(
James Kuszmaul06257f42020-05-09 15:40:09 -0700272 Eigen::Vector3f::Zero(), &U, {},
273 [H, H_field_target, pose_robot_target, state_at_capture](
274 const State &, const Input &) -> Eigen::Vector3f {
275 const Eigen::Vector3f Z = CalculateImpliedPose(
276 state_at_capture.value(), H_field_target, pose_robot_target);
James Kuszmaul66efe832020-03-16 19:38:33 -0700277 // Just in case we ever do encounter any, drop measurements if they
278 // have non-finite numbers.
279 if (!Z.allFinite()) {
280 AOS_LOG(WARNING, "Got measurement with infinites or NaNs.\n");
James Kuszmauld478f872020-03-16 20:54:27 -0700281 return Eigen::Vector3f::Zero();
James Kuszmaul66efe832020-03-16 19:38:33 -0700282 }
James Kuszmaul06257f42020-05-09 15:40:09 -0700283 Eigen::Vector3f Zhat = H * state_at_capture.value() - Z;
James Kuszmaul66efe832020-03-16 19:38:33 -0700284 // Rewrap angle difference to put it back in range. Note that this
285 // component of the error is currently ignored (see definition of H
286 // above).
287 Zhat(2) = aos::math::NormalizeAngle(Zhat(2));
James Kuszmaul58cb1fe2020-03-07 16:18:59 -0800288 // If the measurement implies that we are too far from the current
289 // estimate, then ignore it.
290 // Note that I am not entirely sure how much effect this actually has,
291 // because I primarily introduced it to make sure that any grossly
292 // invalid measurements get thrown out.
James Kuszmaul66efe832020-03-16 19:38:33 -0700293 if (Zhat.squaredNorm() > std::pow(10.0, 2)) {
James Kuszmauld478f872020-03-16 20:54:27 -0700294 return Eigen::Vector3f::Zero();
James Kuszmaul58cb1fe2020-03-07 16:18:59 -0800295 }
296 return Zhat;
297 },
James Kuszmaul06257f42020-05-09 15:40:09 -0700298 [H](const State &) { return H; }, R, now);
James Kuszmaul5398fae2020-02-17 16:44:03 -0800299 }
300}
301
302} // namespace drivetrain
303} // namespace control_loops
304} // namespace y2020