blob: 25263554bbc654b9434b617db4fcecb531e55716 [file] [log] [blame]
milind-u92195982022-01-22 20:29:31 -08001#include "y2022/vision/target_estimator.h"
2
Milind Upadhyayf61e1482022-02-11 20:42:55 -08003#include "absl/strings/str_format.h"
4#include "aos/time/time.h"
5#include "ceres/ceres.h"
6#include "frc971/control_loops/quaternion_utils.h"
Milind Upadhyay8f38ad82022-03-03 10:06:18 -08007#include "geometry.h"
Milind Upadhyayf61e1482022-02-11 20:42:55 -08008#include "opencv2/core/core.hpp"
9#include "opencv2/core/eigen.hpp"
10#include "opencv2/features2d.hpp"
11#include "opencv2/highgui/highgui.hpp"
12#include "opencv2/imgproc.hpp"
milind-ucafdd5d2022-03-01 19:58:57 -080013#include "y2022/constants.h"
Milind Upadhyayf61e1482022-02-11 20:42:55 -080014
Milind Upadhyay8f38ad82022-03-03 10:06:18 -080015DEFINE_bool(freeze_roll, false, "If true, don't solve for roll");
Milind Upadhyayf61e1482022-02-11 20:42:55 -080016DEFINE_bool(freeze_pitch, false, "If true, don't solve for pitch");
17DEFINE_bool(freeze_yaw, false, "If true, don't solve for yaw");
18DEFINE_bool(freeze_camera_height, true,
19 "If true, don't solve for camera height");
20DEFINE_bool(freeze_angle_to_camera, true,
21 "If true, don't solve for polar angle to camera");
22
23DEFINE_uint64(max_num_iterations, 200,
24 "Maximum number of iterations for the ceres solver");
25DEFINE_bool(solver_output, false,
26 "If true, log the solver progress and results");
Milind Upadhyay3336f3a2022-04-01 21:45:57 -070027DEFINE_bool(draw_projected_hub, true,
28 "If true, draw the projected hub when drawing an estimate");
Milind Upadhyayf61e1482022-02-11 20:42:55 -080029
milind-u92195982022-01-22 20:29:31 -080030namespace y2022::vision {
31
Milind Upadhyay8f38ad82022-03-03 10:06:18 -080032namespace {
33
34constexpr size_t kNumPiecesOfTape = 16;
35// Width and height of a piece of reflective tape
36constexpr double kTapePieceWidth = 0.13;
37constexpr double kTapePieceHeight = 0.05;
38// Height of the center of the tape (m)
39constexpr double kTapeCenterHeight = 2.58 + (kTapePieceHeight / 2);
40// Horizontal distance from tape to center of hub (m)
Austin Schuha685b5d2022-04-02 14:53:54 -070041constexpr double kUpperHubRadius = 1.36 / 2;
Milind Upadhyay8f38ad82022-03-03 10:06:18 -080042
43std::vector<cv::Point3d> ComputeTapePoints() {
Milind Upadhyayf61e1482022-02-11 20:42:55 -080044 std::vector<cv::Point3d> tape_points;
milind-u92195982022-01-22 20:29:31 -080045
Milind Upadhyayf61e1482022-02-11 20:42:55 -080046 constexpr size_t kNumVisiblePiecesOfTape = 5;
47 for (size_t i = 0; i < kNumVisiblePiecesOfTape; i++) {
48 // The center piece of tape is at 0 rad, so the angle indices are offset
49 // by the number of pieces of tape on each side of it
50 const double theta_index =
51 static_cast<double>(i) - ((kNumVisiblePiecesOfTape - 1) / 2);
52 // The polar angle is a multiple of the angle between tape centers
53 double theta = theta_index * ((2.0 * M_PI) / kNumPiecesOfTape);
54 tape_points.emplace_back(kUpperHubRadius * std::cos(theta),
Milind Upadhyay8f38ad82022-03-03 10:06:18 -080055 kUpperHubRadius * std::sin(theta),
56 kTapeCenterHeight);
Milind Upadhyayf61e1482022-02-11 20:42:55 -080057 }
milind-u92195982022-01-22 20:29:31 -080058
Milind Upadhyayf61e1482022-02-11 20:42:55 -080059 return tape_points;
60}
milind-u92195982022-01-22 20:29:31 -080061
Milind Upadhyay8f38ad82022-03-03 10:06:18 -080062std::array<cv::Point3d, 4> ComputeMiddleTapePiecePoints() {
63 std::array<cv::Point3d, 4> tape_piece_points;
64
65 // Angle that each piece of tape occupies on the hub
66 constexpr double kTapePieceAngle =
67 (kTapePieceWidth / (2.0 * M_PI * kUpperHubRadius)) * (2.0 * M_PI);
68
69 constexpr double kThetaTapeLeft = -kTapePieceAngle / 2.0;
70 constexpr double kThetaTapeRight = kTapePieceAngle / 2.0;
71
72 constexpr double kTapeTopHeight =
73 kTapeCenterHeight + (kTapePieceHeight / 2.0);
74 constexpr double kTapeBottomHeight =
75 kTapeCenterHeight - (kTapePieceHeight / 2.0);
76
77 tape_piece_points[0] = {kUpperHubRadius * std::cos(kThetaTapeLeft),
78 kUpperHubRadius * std::sin(kThetaTapeLeft),
79 kTapeTopHeight};
80 tape_piece_points[1] = {kUpperHubRadius * std::cos(kThetaTapeRight),
81 kUpperHubRadius * std::sin(kThetaTapeRight),
82 kTapeTopHeight};
83
84 tape_piece_points[2] = {kUpperHubRadius * std::cos(kThetaTapeRight),
85 kUpperHubRadius * std::sin(kThetaTapeRight),
86 kTapeBottomHeight};
87 tape_piece_points[3] = {kUpperHubRadius * std::cos(kThetaTapeLeft),
88 kUpperHubRadius * std::sin(kThetaTapeLeft),
89 kTapeBottomHeight};
90
91 return tape_piece_points;
92}
93
94} // namespace
95
Milind Upadhyayf61e1482022-02-11 20:42:55 -080096const std::vector<cv::Point3d> TargetEstimator::kTapePoints =
97 ComputeTapePoints();
Milind Upadhyay8f38ad82022-03-03 10:06:18 -080098const std::array<cv::Point3d, 4> TargetEstimator::kMiddleTapePiecePoints =
99 ComputeMiddleTapePiecePoints();
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800100
101TargetEstimator::TargetEstimator(cv::Mat intrinsics, cv::Mat extrinsics)
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800102 : blob_stats_(),
Milind Upadhyay1c76a042022-04-02 20:42:42 -0700103 middle_blob_index_(0),
104 max_blob_area_(0.0),
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800105 image_(std::nullopt),
106 roll_(0.0),
107 pitch_(0.0),
108 yaw_(M_PI),
109 distance_(3.0),
110 angle_to_camera_(0.0),
milind-ucafdd5d2022-03-01 19:58:57 -0800111 // Seed camera height
112 camera_height_(extrinsics.at<double>(2, 3) +
113 constants::Values::kImuHeight()) {
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800114 cv::cv2eigen(intrinsics, intrinsics_);
115 cv::cv2eigen(extrinsics, extrinsics_);
116}
117
118namespace {
119void SetBoundsOrFreeze(double *param, bool freeze, double min, double max,
120 ceres::Problem *problem) {
121 if (freeze) {
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800122 problem->SetParameterBlockConstant(param);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800123 } else {
124 problem->SetParameterLowerBound(param, 0, min);
125 problem->SetParameterUpperBound(param, 0, max);
126 }
127}
milind-ucafdd5d2022-03-01 19:58:57 -0800128
129// With X, Y, Z being hub axes and x, y, z being camera axes,
130// x = -Y, y = -Z, z = X
131const Eigen::Matrix3d kHubToCameraAxes =
132 (Eigen::Matrix3d() << 0.0, -1.0, 0.0, 0.0, 0.0, -1.0, 1.0, 0.0, 0.0)
133 .finished();
134
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800135} // namespace
136
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800137void TargetEstimator::Solve(
138 const std::vector<BlobDetector::BlobStats> &blob_stats,
139 std::optional<cv::Mat> image) {
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800140 auto start = aos::monotonic_clock::now();
141
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800142 blob_stats_ = blob_stats;
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800143 image_ = image;
144
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800145 // Do nothing if no blobs were detected
146 if (blob_stats_.size() == 0) {
147 confidence_ = 0.0;
148 return;
149 }
150
151 CHECK_GE(blob_stats_.size(), 3) << "Expected at least 3 blobs";
152
153 const auto circle =
154 Circle::Fit({blob_stats_[0].centroid, blob_stats_[1].centroid,
155 blob_stats_[2].centroid});
156 CHECK(circle.has_value());
157
Milind Upadhyay1c76a042022-04-02 20:42:42 -0700158 max_blob_area_ = 0.0;
159
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800160 // Find the middle blob, which is the one with the angle closest to the
161 // average
162 double theta_avg = 0.0;
163 for (const auto &stats : blob_stats_) {
164 theta_avg += circle->AngleOf(stats.centroid);
Milind Upadhyay1c76a042022-04-02 20:42:42 -0700165
166 if (stats.area > max_blob_area_) {
167 max_blob_area_ = stats.area;
168 }
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800169 }
170 theta_avg /= blob_stats_.size();
171
172 double min_diff = std::numeric_limits<double>::infinity();
173 for (auto it = blob_stats_.begin(); it < blob_stats_.end(); it++) {
174 const double diff = std::abs(circle->AngleOf(it->centroid) - theta_avg);
175 if (diff < min_diff) {
176 min_diff = diff;
177 middle_blob_index_ = it - blob_stats_.begin();
178 }
179 }
180
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800181 ceres::Problem problem;
182
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800183 // x and y differences between projected centroids and blob centroids, as well
184 // as width and height differences between middle projected piece and the
185 // detected blob
186 const size_t num_residuals = (blob_stats_.size() * 2) + 2;
187
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800188 // Set up the only cost function (also known as residual). This uses
189 // auto-differentiation to obtain the derivative (jacobian).
190 ceres::CostFunction *cost_function =
191 new ceres::AutoDiffCostFunction<TargetEstimator, ceres::DYNAMIC, 1, 1, 1,
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800192 1, 1, 1>(this, num_residuals,
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800193 ceres::DO_NOT_TAKE_OWNERSHIP);
194
195 // TODO(milind): add loss function when we get more noisy data
Austin Schuha685b5d2022-04-02 14:53:54 -0700196 problem.AddResidualBlock(cost_function, new ceres::HuberLoss(2.0), &roll_,
197 &pitch_, &yaw_, &distance_, &angle_to_camera_,
198 &camera_height_);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800199
milind-ucafdd5d2022-03-01 19:58:57 -0800200 // Compute the estimated rotation of the camera using the robot rotation.
Milind Upadhyayda042bb2022-03-26 16:01:45 -0700201 const Eigen::Matrix3d extrinsics_rot =
202 Eigen::Affine3d(extrinsics_).rotation() * kHubToCameraAxes;
203 // asin returns a pitch in [-pi/2, pi/2] so this will be the correct euler
204 // angles.
205 const double pitch_seed = -std::asin(extrinsics_rot(2, 0));
206 const double roll_seed =
207 std::atan2(extrinsics_rot(2, 1) / std::cos(pitch_seed),
208 extrinsics_rot(2, 2) / std::cos(pitch_seed));
209
milind-ucafdd5d2022-03-01 19:58:57 -0800210 // TODO(milind): seed with localizer output as well
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800211
milind-ucafdd5d2022-03-01 19:58:57 -0800212 // Constrain the rotation to be around the localizer's, otherwise there can be
213 // multiple solutions. There shouldn't be too much roll or pitch
Milind Upadhyay1d9a9c72022-04-02 14:18:40 -0700214 if (FLAGS_freeze_roll) {
215 roll_ = roll_seed;
216 }
milind-ucafdd5d2022-03-01 19:58:57 -0800217 constexpr double kMaxRollDelta = 0.1;
218 SetBoundsOrFreeze(&roll_, FLAGS_freeze_roll, roll_seed - kMaxRollDelta,
219 roll_seed + kMaxRollDelta, &problem);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800220
Milind Upadhyay1d9a9c72022-04-02 14:18:40 -0700221 if (FLAGS_freeze_pitch) {
222 pitch_ = pitch_seed;
223 }
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800224 constexpr double kMaxPitchDelta = 0.15;
milind-ucafdd5d2022-03-01 19:58:57 -0800225 SetBoundsOrFreeze(&pitch_, FLAGS_freeze_pitch, pitch_seed - kMaxPitchDelta,
226 pitch_seed + kMaxPitchDelta, &problem);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800227 // Constrain the yaw to where the target would be visible
228 constexpr double kMaxYawDelta = M_PI / 4.0;
229 SetBoundsOrFreeze(&yaw_, FLAGS_freeze_yaw, M_PI - kMaxYawDelta,
230 M_PI + kMaxYawDelta, &problem);
231
232 constexpr double kMaxHeightDelta = 0.1;
233 SetBoundsOrFreeze(&camera_height_, FLAGS_freeze_camera_height,
234 camera_height_ - kMaxHeightDelta,
235 camera_height_ + kMaxHeightDelta, &problem);
236
237 // Distances shouldn't be too close to the target or too far
238 constexpr double kMinDistance = 1.0;
239 constexpr double kMaxDistance = 10.0;
240 SetBoundsOrFreeze(&distance_, false, kMinDistance, kMaxDistance, &problem);
241
242 // Keep the angle between +/- half of the angle between piece of tape
243 constexpr double kMaxAngle = ((2.0 * M_PI) / kNumPiecesOfTape) / 2.0;
244 SetBoundsOrFreeze(&angle_to_camera_, FLAGS_freeze_angle_to_camera, -kMaxAngle,
245 kMaxAngle, &problem);
246
247 ceres::Solver::Options options;
248 options.minimizer_progress_to_stdout = FLAGS_solver_output;
249 options.gradient_tolerance = 1e-12;
250 options.function_tolerance = 1e-16;
251 options.parameter_tolerance = 1e-12;
252 options.max_num_iterations = FLAGS_max_num_iterations;
253 ceres::Solver::Summary summary;
254 ceres::Solve(options, &problem, &summary);
255
256 auto end = aos::monotonic_clock::now();
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800257 VLOG(1) << "Target estimation elapsed time: "
258 << std::chrono::duration<double, std::milli>(end - start).count()
259 << " ms";
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800260
Milind Upadhyay1c76a042022-04-02 20:42:42 -0700261 // For computing the confidence, find the standard deviation in pixels.
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800262 std::vector<double> residual(num_residuals);
263 (*this)(&roll_, &pitch_, &yaw_, &distance_, &angle_to_camera_,
264 &camera_height_, residual.data());
265 double std_dev = 0.0;
266 for (auto it = residual.begin(); it < residual.end() - 2; it++) {
267 std_dev += std::pow(*it, 2);
Milind Upadhyay14279de2022-02-26 16:07:53 -0800268 }
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800269 std_dev /= num_residuals - 2;
270 std_dev = std::sqrt(std_dev);
271
272 // Use a sigmoid to convert the deviation into a confidence for the
273 // localizer. Fit a sigmoid to the points of (0, 1) and two other
274 // reasonable deviation-confidence combinations using
Milind Upadhyayda9a8292022-04-02 18:00:04 -0700275 // https://www.desmos.com/calculator/ha6fh9yw44
276 constexpr double kSigmoidCapacity = 1.065;
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800277 // Stretch the sigmoid out correctly.
Milind Upadhyayda9a8292022-04-02 18:00:04 -0700278 // Currently, good estimates have deviations of 1 or less pixels.
279 constexpr double kSigmoidScalar = 0.06496;
280 constexpr double kSigmoidGrowthRate = -0.6221;
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800281 confidence_ =
282 kSigmoidCapacity /
283 (1.0 + kSigmoidScalar * std::exp(-kSigmoidGrowthRate * std_dev));
Milind Upadhyay14279de2022-02-26 16:07:53 -0800284
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800285 if (FLAGS_solver_output) {
286 LOG(INFO) << summary.FullReport();
287
288 LOG(INFO) << "roll: " << roll_;
289 LOG(INFO) << "pitch: " << pitch_;
290 LOG(INFO) << "yaw: " << yaw_;
291 LOG(INFO) << "angle to target (based on yaw): " << angle_to_target();
292 LOG(INFO) << "angle to camera (polar): " << angle_to_camera_;
293 LOG(INFO) << "distance (polar): " << distance_;
294 LOG(INFO) << "camera height: " << camera_height_;
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800295 LOG(INFO) << "standard deviation (px): " << std_dev;
Milind Upadhyay14279de2022-02-26 16:07:53 -0800296 LOG(INFO) << "confidence: " << confidence_;
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800297 }
298}
299
300namespace {
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700301
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800302// Hacks to extract a double from a scalar, which is either a ceres jet or a
303// double. Only used for debugging and displaying.
304template <typename S>
305double ScalarToDouble(S s) {
306 const double *ptr = reinterpret_cast<double *>(&s);
307 return *ptr;
308}
309
310template <typename S>
311cv::Point2d ScalarPointToDouble(cv::Point_<S> p) {
312 return cv::Point2d(ScalarToDouble(p.x), ScalarToDouble(p.y));
313}
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700314
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800315} // namespace
316
317template <typename S>
318bool TargetEstimator::operator()(const S *const roll, const S *const pitch,
319 const S *const yaw, const S *const distance,
320 const S *const theta,
321 const S *const camera_height,
322 S *residual) const {
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700323 const auto H_hub_camera = ComputeHubCameraTransform(
324 *roll, *pitch, *yaw, *distance, *theta, *camera_height);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800325
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700326 // Project tape points
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800327 std::vector<cv::Point_<S>> tape_points_proj;
328 for (cv::Point3d tape_point_hub : kTapePoints) {
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800329 tape_points_proj.emplace_back(ProjectToImage(tape_point_hub, H_hub_camera));
330 VLOG(2) << "Projected tape point: "
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800331 << ScalarPointToDouble(
332 tape_points_proj[tape_points_proj.size() - 1]);
333 }
334
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800335 // Find the rectangle bounding the projected piece of tape
336 std::array<cv::Point_<S>, 4> middle_tape_piece_points_proj;
337 for (auto tape_piece_it = kMiddleTapePiecePoints.begin();
338 tape_piece_it < kMiddleTapePiecePoints.end(); tape_piece_it++) {
339 middle_tape_piece_points_proj[tape_piece_it -
340 kMiddleTapePiecePoints.begin()] =
341 ProjectToImage(*tape_piece_it, H_hub_camera);
342 }
343
Austin Schuha685b5d2022-04-02 14:53:54 -0700344 // Now, find the closest tape for each blob.
345 // We don't normally see tape without matching blobs in the center. So we
346 // want to compress any gaps in the matched tape blobs. This makes it so it
347 // doesn't want to make the goal super small and skip tape blobs. The
348 // resulting accuracy is then pretty good.
349
350 // Mapping from tape index to blob index.
351 std::vector<std::pair<size_t, size_t>> tape_indices;
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800352 for (size_t i = 0; i < blob_stats_.size(); i++) {
Austin Schuha685b5d2022-04-02 14:53:54 -0700353 tape_indices.emplace_back(ClosestTape(i, tape_points_proj), i);
354 VLOG(2) << "Tape indices were " << tape_indices.back().first;
355 }
356
357 std::sort(
358 tape_indices.begin(), tape_indices.end(),
359 [](const std::pair<size_t, size_t> &a,
360 const std::pair<size_t, size_t> &b) { return a.first < b.first; });
361
362 size_t middle_tape_index = 1000;
363 for (size_t i = 0; i < tape_indices.size(); ++i) {
364 if (tape_indices[i].second == middle_blob_index_) {
365 middle_tape_index = i;
366 }
367 }
368 CHECK_NE(middle_tape_index, 1000) << "Failed to find middle tape";
369
370 if (VLOG_IS_ON(2)) {
371 LOG(INFO) << "Middle tape is " << middle_tape_index << ", blob "
372 << middle_blob_index_;
373 for (size_t i = 0; i < tape_indices.size(); ++i) {
374 const auto distance = DistanceFromTapeIndex(
375 tape_indices[i].second, tape_indices[i].first, tape_points_proj);
376 LOG(INFO) << "Blob index " << tape_indices[i].second << " maps to "
377 << tape_indices[i].first << " distance " << distance.x << " "
378 << distance.y;
379 }
380 }
381
382 {
383 size_t offset = 0;
384 for (size_t i = middle_tape_index + 1; i < tape_indices.size(); ++i) {
385 tape_indices[i].first -= offset;
386
387 if (tape_indices[i].first > tape_indices[i - 1].first + 1) {
388 offset += tape_indices[i].first - (tape_indices[i - 1].first + 1);
389 VLOG(2) << "Offset now " << offset;
390 tape_indices[i].first = tape_indices[i - 1].first + 1;
391 }
392 }
393 }
394
395 if (VLOG_IS_ON(2)) {
396 LOG(INFO) << "Middle tape is " << middle_tape_index << ", blob "
397 << middle_blob_index_;
398 for (size_t i = 0; i < tape_indices.size(); ++i) {
399 const auto distance = DistanceFromTapeIndex(
400 tape_indices[i].second, tape_indices[i].first, tape_points_proj);
401 LOG(INFO) << "Blob index " << tape_indices[i].second << " maps to "
402 << tape_indices[i].first << " distance " << distance.x << " "
403 << distance.y;
404 }
405 }
406
407 {
408 size_t offset = 0;
409 for (size_t i = middle_tape_index; i > 0; --i) {
410 tape_indices[i - 1].first -= offset;
411
412 if (tape_indices[i - 1].first + 1 < tape_indices[i].first) {
413 VLOG(2) << "Too big a gap. " << tape_indices[i].first << " and "
414 << tape_indices[i - 1].first;
415
416 offset += tape_indices[i].first - (tape_indices[i - 1].first + 1);
417 tape_indices[i - 1].first = tape_indices[i].first - 1;
418 VLOG(2) << "Offset now " << offset;
419 }
420 }
421 }
422
423 if (VLOG_IS_ON(2)) {
424 LOG(INFO) << "Middle tape is " << middle_tape_index << ", blob "
425 << middle_blob_index_;
426 for (size_t i = 0; i < tape_indices.size(); ++i) {
427 const auto distance = DistanceFromTapeIndex(
428 tape_indices[i].second, tape_indices[i].first, tape_points_proj);
429 LOG(INFO) << "Blob index " << tape_indices[i].second << " maps to "
430 << tape_indices[i].first << " distance " << distance.x << " "
431 << distance.y;
432 }
433 }
434
435 for (size_t i = 0; i < tape_indices.size(); ++i) {
436 const auto distance = DistanceFromTapeIndex(
437 tape_indices[i].second, tape_indices[i].first, tape_points_proj);
Milind Upadhyay1c76a042022-04-02 20:42:42 -0700438 // Scale the distance based on the blob area: larger blobs have less noise.
439 const S distance_scalar =
440 S(blob_stats_[tape_indices[i].second].area / max_blob_area_);
Austin Schuha685b5d2022-04-02 14:53:54 -0700441 VLOG(2) << "Blob index " << tape_indices[i].second << " maps to "
442 << tape_indices[i].first << " distance " << distance.x << " "
Milind Upadhyay1c76a042022-04-02 20:42:42 -0700443 << distance.y << " distance scalar "
444 << ScalarToDouble(distance_scalar);
445
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800446 // Set the residual to the (x, y) distance of the centroid from the
Austin Schuha685b5d2022-04-02 14:53:54 -0700447 // matched projected piece of tape
Milind Upadhyay1c76a042022-04-02 20:42:42 -0700448 residual[i * 2] = distance_scalar * distance.x;
449 residual[(i * 2) + 1] = distance_scalar * distance.y;
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800450 }
451
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800452 // Penalize based on the difference between the size of the projected piece of
Austin Schuha685b5d2022-04-02 14:53:54 -0700453 // tape and that of the detected blobs.
454 const S middle_tape_piece_width = ceres::hypot(
455 middle_tape_piece_points_proj[2].x - middle_tape_piece_points_proj[3].x,
456 middle_tape_piece_points_proj[2].y - middle_tape_piece_points_proj[3].y);
457 const S middle_tape_piece_height = ceres::hypot(
458 middle_tape_piece_points_proj[1].x - middle_tape_piece_points_proj[2].x,
459 middle_tape_piece_points_proj[1].y - middle_tape_piece_points_proj[2].y);
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800460
Austin Schuha685b5d2022-04-02 14:53:54 -0700461 constexpr double kCenterBlobSizeScalar = 0.1;
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800462 residual[blob_stats_.size() * 2] =
Austin Schuha685b5d2022-04-02 14:53:54 -0700463 kCenterBlobSizeScalar *
464 (middle_tape_piece_width -
465 static_cast<S>(blob_stats_[middle_blob_index_].size.width));
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800466 residual[(blob_stats_.size() * 2) + 1] =
Austin Schuha685b5d2022-04-02 14:53:54 -0700467 kCenterBlobSizeScalar *
468 (middle_tape_piece_height -
469 static_cast<S>(blob_stats_[middle_blob_index_].size.height));
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800470
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800471 if (image_.has_value()) {
472 // Draw the current stage of the solving
473 cv::Mat image = image_->clone();
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700474 std::vector<cv::Point2d> tape_points_proj_double;
475 for (auto point : tape_points_proj) {
476 tape_points_proj_double.emplace_back(ScalarPointToDouble(point));
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800477 }
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700478 DrawProjectedHub(tape_points_proj_double, image);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800479 cv::imshow("image", image);
480 cv::waitKey(10);
481 }
482
483 return true;
484}
485
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800486template <typename S>
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700487Eigen::Transform<S, 3, Eigen::Affine>
488TargetEstimator::ComputeHubCameraTransform(S roll, S pitch, S yaw, S distance,
489 S theta, S camera_height) const {
490 using Vector3s = Eigen::Matrix<S, 3, 1>;
491 using Affine3s = Eigen::Transform<S, 3, Eigen::Affine>;
492
493 Eigen::AngleAxis<S> roll_angle(roll, Vector3s::UnitX());
494 Eigen::AngleAxis<S> pitch_angle(pitch, Vector3s::UnitY());
495 Eigen::AngleAxis<S> yaw_angle(yaw, Vector3s::UnitZ());
496 // Construct the rotation and translation of the camera in the hub's frame
497 Eigen::Quaternion<S> R_camera_hub = yaw_angle * pitch_angle * roll_angle;
498 Vector3s T_camera_hub(distance * ceres::cos(theta),
499 distance * ceres::sin(theta), camera_height);
500
501 Affine3s H_camera_hub = Eigen::Translation<S, 3>(T_camera_hub) * R_camera_hub;
502 Affine3s H_hub_camera = H_camera_hub.inverse();
503
504 return H_hub_camera;
505}
506
507template <typename S>
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800508cv::Point_<S> TargetEstimator::ProjectToImage(
509 cv::Point3d tape_point_hub,
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700510 const Eigen::Transform<S, 3, Eigen::Affine> &H_hub_camera) const {
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800511 using Vector3s = Eigen::Matrix<S, 3, 1>;
512
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800513 const Vector3s tape_point_hub_eigen =
514 Vector3s(S(tape_point_hub.x), S(tape_point_hub.y), S(tape_point_hub.z));
515 // Project the 3d tape point onto the image using the transformation and
516 // intrinsics
517 const Vector3s tape_point_proj =
milind-ucafdd5d2022-03-01 19:58:57 -0800518 intrinsics_ * (kHubToCameraAxes * (H_hub_camera * tape_point_hub_eigen));
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800519
520 // Normalize the projected point
521 return {tape_point_proj.x() / tape_point_proj.z(),
522 tape_point_proj.y() / tape_point_proj.z()};
523}
524
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800525namespace {
526template <typename S>
527cv::Point_<S> Distance(cv::Point p, cv::Point_<S> q) {
528 return cv::Point_<S>(S(p.x) - q.x, S(p.y) - q.y);
529}
530
531template <typename S>
532bool Less(cv::Point_<S> distance_1, cv::Point_<S> distance_2) {
533 return (ceres::pow(distance_1.x, 2) + ceres::pow(distance_1.y, 2) <
534 ceres::pow(distance_2.x, 2) + ceres::pow(distance_2.y, 2));
535}
536} // namespace
537
538template <typename S>
Austin Schuha685b5d2022-04-02 14:53:54 -0700539cv::Point_<S> TargetEstimator::DistanceFromTapeIndex(
540 size_t blob_index, size_t tape_index,
541 const std::vector<cv::Point_<S>> &tape_points) const {
542 return Distance(blob_stats_[blob_index].centroid, tape_points[tape_index]);
543}
544
545template <typename S>
546size_t TargetEstimator::ClosestTape(
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800547 size_t blob_index, const std::vector<cv::Point_<S>> &tape_points) const {
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800548 auto distance = cv::Point_<S>(std::numeric_limits<S>::infinity(),
549 std::numeric_limits<S>::infinity());
Austin Schuha685b5d2022-04-02 14:53:54 -0700550 size_t final_match = 255;
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800551 if (blob_index == middle_blob_index_) {
552 // Fix the middle blob so the solver can't go too far off
Austin Schuha685b5d2022-04-02 14:53:54 -0700553 final_match = tape_points.size() / 2;
554 distance = DistanceFromTapeIndex(blob_index, final_match, tape_points);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800555 } else {
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800556 // Give the other blob_stats some freedom in case some are split into pieces
557 for (auto it = tape_points.begin(); it < tape_points.end(); it++) {
Austin Schuha685b5d2022-04-02 14:53:54 -0700558 const size_t tape_index = std::distance(tape_points.begin(), it);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800559 const auto current_distance =
Austin Schuha685b5d2022-04-02 14:53:54 -0700560 DistanceFromTapeIndex(blob_index, tape_index, tape_points);
561 if ((tape_index != (tape_points.size() / 2)) &&
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800562 Less(current_distance, distance)) {
Austin Schuha685b5d2022-04-02 14:53:54 -0700563 final_match = tape_index;
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800564 distance = current_distance;
565 }
566 }
567 }
568
Austin Schuha685b5d2022-04-02 14:53:54 -0700569 VLOG(2) << "Matched index " << blob_index << " to " << final_match
570 << " distance " << distance.x << " " << distance.y;
571 CHECK_NE(final_match, 255);
572
573 return final_match;
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800574}
575
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700576void TargetEstimator::DrawProjectedHub(
577 const std::vector<cv::Point2d> &tape_points_proj,
578 cv::Mat view_image) const {
579 for (size_t i = 0; i < tape_points_proj.size() - 1; i++) {
580 cv::line(view_image, ScalarPointToDouble(tape_points_proj[i]),
581 ScalarPointToDouble(tape_points_proj[i + 1]),
582 cv::Scalar(255, 255, 255));
583 cv::circle(view_image, ScalarPointToDouble(tape_points_proj[i]), 2,
584 cv::Scalar(255, 20, 147), cv::FILLED);
585 cv::circle(view_image, ScalarPointToDouble(tape_points_proj[i + 1]), 2,
586 cv::Scalar(255, 20, 147), cv::FILLED);
587 }
588}
589
590void TargetEstimator::DrawEstimate(cv::Mat view_image) const {
591 if (FLAGS_draw_projected_hub) {
592 // Draw projected hub
593 const auto H_hub_camera = ComputeHubCameraTransform(
594 roll_, pitch_, yaw_, distance_, angle_to_camera_, camera_height_);
595 std::vector<cv::Point2d> tape_points_proj;
596 for (cv::Point3d tape_point_hub : kTapePoints) {
597 tape_points_proj.emplace_back(
598 ProjectToImage(tape_point_hub, H_hub_camera));
599 }
600 DrawProjectedHub(tape_points_proj, view_image);
601 }
602
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800603 constexpr int kTextX = 10;
Milind Upadhyay2da80bb2022-03-12 22:54:35 -0800604 int text_y = 0;
605 constexpr int kTextSpacing = 25;
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800606
607 const auto kTextColor = cv::Scalar(0, 255, 255);
Milind Upadhyay2da80bb2022-03-12 22:54:35 -0800608 constexpr double kFontScale = 0.6;
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800609
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700610 cv::putText(view_image, absl::StrFormat("Distance: %.3f", distance_),
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800611 cv::Point(kTextX, text_y += kTextSpacing),
612 cv::FONT_HERSHEY_DUPLEX, kFontScale, kTextColor, 2);
613 cv::putText(view_image,
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700614 absl::StrFormat("Angle to target: %.3f", angle_to_target()),
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800615 cv::Point(kTextX, text_y += kTextSpacing),
616 cv::FONT_HERSHEY_DUPLEX, kFontScale, kTextColor, 2);
617 cv::putText(view_image,
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700618 absl::StrFormat("Angle to camera: %.3f", angle_to_camera_),
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800619 cv::Point(kTextX, text_y += kTextSpacing),
620 cv::FONT_HERSHEY_DUPLEX, kFontScale, kTextColor, 2);
621
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700622 cv::putText(view_image,
623 absl::StrFormat("Roll: %.3f, pitch: %.3f, yaw: %.3f", roll_,
624 pitch_, yaw_),
Milind Upadhyay14279de2022-02-26 16:07:53 -0800625 cv::Point(kTextX, text_y += kTextSpacing),
626 cv::FONT_HERSHEY_DUPLEX, kFontScale, kTextColor, 2);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800627
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700628 cv::putText(view_image, absl::StrFormat("Confidence: %.3f", confidence_),
629 cv::Point(kTextX, text_y += kTextSpacing),
630 cv::FONT_HERSHEY_DUPLEX, kFontScale, kTextColor, 2);
milind-u92195982022-01-22 20:29:31 -0800631}
632
633} // namespace y2022::vision