blob: 2bee98f2099c9edb9fb2406ace80ec43cf0947a4 [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 Upadhyayf61e1482022-02-11 20:42:55 -0800103 image_(std::nullopt),
104 roll_(0.0),
105 pitch_(0.0),
106 yaw_(M_PI),
107 distance_(3.0),
108 angle_to_camera_(0.0),
milind-ucafdd5d2022-03-01 19:58:57 -0800109 // Seed camera height
110 camera_height_(extrinsics.at<double>(2, 3) +
111 constants::Values::kImuHeight()) {
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800112 cv::cv2eigen(intrinsics, intrinsics_);
113 cv::cv2eigen(extrinsics, extrinsics_);
114}
115
116namespace {
117void SetBoundsOrFreeze(double *param, bool freeze, double min, double max,
118 ceres::Problem *problem) {
119 if (freeze) {
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800120 problem->SetParameterBlockConstant(param);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800121 } else {
122 problem->SetParameterLowerBound(param, 0, min);
123 problem->SetParameterUpperBound(param, 0, max);
124 }
125}
milind-ucafdd5d2022-03-01 19:58:57 -0800126
127// With X, Y, Z being hub axes and x, y, z being camera axes,
128// x = -Y, y = -Z, z = X
129const Eigen::Matrix3d kHubToCameraAxes =
130 (Eigen::Matrix3d() << 0.0, -1.0, 0.0, 0.0, 0.0, -1.0, 1.0, 0.0, 0.0)
131 .finished();
132
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800133} // namespace
134
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800135void TargetEstimator::Solve(
136 const std::vector<BlobDetector::BlobStats> &blob_stats,
137 std::optional<cv::Mat> image) {
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800138 auto start = aos::monotonic_clock::now();
139
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800140 blob_stats_ = blob_stats;
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800141 image_ = image;
142
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800143 // Do nothing if no blobs were detected
144 if (blob_stats_.size() == 0) {
145 confidence_ = 0.0;
146 return;
147 }
148
149 CHECK_GE(blob_stats_.size(), 3) << "Expected at least 3 blobs";
150
151 const auto circle =
152 Circle::Fit({blob_stats_[0].centroid, blob_stats_[1].centroid,
153 blob_stats_[2].centroid});
154 CHECK(circle.has_value());
155
156 // Find the middle blob, which is the one with the angle closest to the
157 // average
158 double theta_avg = 0.0;
159 for (const auto &stats : blob_stats_) {
160 theta_avg += circle->AngleOf(stats.centroid);
161 }
162 theta_avg /= blob_stats_.size();
163
164 double min_diff = std::numeric_limits<double>::infinity();
165 for (auto it = blob_stats_.begin(); it < blob_stats_.end(); it++) {
166 const double diff = std::abs(circle->AngleOf(it->centroid) - theta_avg);
167 if (diff < min_diff) {
168 min_diff = diff;
169 middle_blob_index_ = it - blob_stats_.begin();
170 }
171 }
172
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800173 ceres::Problem problem;
174
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800175 // x and y differences between projected centroids and blob centroids, as well
176 // as width and height differences between middle projected piece and the
177 // detected blob
178 const size_t num_residuals = (blob_stats_.size() * 2) + 2;
179
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800180 // Set up the only cost function (also known as residual). This uses
181 // auto-differentiation to obtain the derivative (jacobian).
182 ceres::CostFunction *cost_function =
183 new ceres::AutoDiffCostFunction<TargetEstimator, ceres::DYNAMIC, 1, 1, 1,
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800184 1, 1, 1>(this, num_residuals,
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800185 ceres::DO_NOT_TAKE_OWNERSHIP);
186
187 // TODO(milind): add loss function when we get more noisy data
Austin Schuha685b5d2022-04-02 14:53:54 -0700188 problem.AddResidualBlock(cost_function, new ceres::HuberLoss(2.0), &roll_,
189 &pitch_, &yaw_, &distance_, &angle_to_camera_,
190 &camera_height_);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800191
milind-ucafdd5d2022-03-01 19:58:57 -0800192 // Compute the estimated rotation of the camera using the robot rotation.
Milind Upadhyayda042bb2022-03-26 16:01:45 -0700193 const Eigen::Matrix3d extrinsics_rot =
194 Eigen::Affine3d(extrinsics_).rotation() * kHubToCameraAxes;
195 // asin returns a pitch in [-pi/2, pi/2] so this will be the correct euler
196 // angles.
197 const double pitch_seed = -std::asin(extrinsics_rot(2, 0));
198 const double roll_seed =
199 std::atan2(extrinsics_rot(2, 1) / std::cos(pitch_seed),
200 extrinsics_rot(2, 2) / std::cos(pitch_seed));
201
milind-ucafdd5d2022-03-01 19:58:57 -0800202 // TODO(milind): seed with localizer output as well
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800203
milind-ucafdd5d2022-03-01 19:58:57 -0800204 // Constrain the rotation to be around the localizer's, otherwise there can be
205 // multiple solutions. There shouldn't be too much roll or pitch
Milind Upadhyay1d9a9c72022-04-02 14:18:40 -0700206 if (FLAGS_freeze_roll) {
207 roll_ = roll_seed;
208 }
milind-ucafdd5d2022-03-01 19:58:57 -0800209 constexpr double kMaxRollDelta = 0.1;
210 SetBoundsOrFreeze(&roll_, FLAGS_freeze_roll, roll_seed - kMaxRollDelta,
211 roll_seed + kMaxRollDelta, &problem);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800212
Milind Upadhyay1d9a9c72022-04-02 14:18:40 -0700213 if (FLAGS_freeze_pitch) {
214 pitch_ = pitch_seed;
215 }
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800216 constexpr double kMaxPitchDelta = 0.15;
milind-ucafdd5d2022-03-01 19:58:57 -0800217 SetBoundsOrFreeze(&pitch_, FLAGS_freeze_pitch, pitch_seed - kMaxPitchDelta,
218 pitch_seed + kMaxPitchDelta, &problem);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800219 // Constrain the yaw to where the target would be visible
220 constexpr double kMaxYawDelta = M_PI / 4.0;
221 SetBoundsOrFreeze(&yaw_, FLAGS_freeze_yaw, M_PI - kMaxYawDelta,
222 M_PI + kMaxYawDelta, &problem);
223
224 constexpr double kMaxHeightDelta = 0.1;
225 SetBoundsOrFreeze(&camera_height_, FLAGS_freeze_camera_height,
226 camera_height_ - kMaxHeightDelta,
227 camera_height_ + kMaxHeightDelta, &problem);
228
229 // Distances shouldn't be too close to the target or too far
230 constexpr double kMinDistance = 1.0;
231 constexpr double kMaxDistance = 10.0;
232 SetBoundsOrFreeze(&distance_, false, kMinDistance, kMaxDistance, &problem);
233
234 // Keep the angle between +/- half of the angle between piece of tape
235 constexpr double kMaxAngle = ((2.0 * M_PI) / kNumPiecesOfTape) / 2.0;
236 SetBoundsOrFreeze(&angle_to_camera_, FLAGS_freeze_angle_to_camera, -kMaxAngle,
237 kMaxAngle, &problem);
238
239 ceres::Solver::Options options;
240 options.minimizer_progress_to_stdout = FLAGS_solver_output;
241 options.gradient_tolerance = 1e-12;
242 options.function_tolerance = 1e-16;
243 options.parameter_tolerance = 1e-12;
244 options.max_num_iterations = FLAGS_max_num_iterations;
245 ceres::Solver::Summary summary;
246 ceres::Solve(options, &problem, &summary);
247
248 auto end = aos::monotonic_clock::now();
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800249 VLOG(1) << "Target estimation elapsed time: "
250 << std::chrono::duration<double, std::milli>(end - start).count()
251 << " ms";
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800252
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800253 // For computing the confidence, find the standard deviation in pixels
254 std::vector<double> residual(num_residuals);
255 (*this)(&roll_, &pitch_, &yaw_, &distance_, &angle_to_camera_,
256 &camera_height_, residual.data());
257 double std_dev = 0.0;
258 for (auto it = residual.begin(); it < residual.end() - 2; it++) {
259 std_dev += std::pow(*it, 2);
Milind Upadhyay14279de2022-02-26 16:07:53 -0800260 }
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800261 std_dev /= num_residuals - 2;
262 std_dev = std::sqrt(std_dev);
263
264 // Use a sigmoid to convert the deviation into a confidence for the
265 // localizer. Fit a sigmoid to the points of (0, 1) and two other
266 // reasonable deviation-confidence combinations using
Milind Upadhyayda9a8292022-04-02 18:00:04 -0700267 // https://www.desmos.com/calculator/ha6fh9yw44
268 constexpr double kSigmoidCapacity = 1.065;
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800269 // Stretch the sigmoid out correctly.
Milind Upadhyayda9a8292022-04-02 18:00:04 -0700270 // Currently, good estimates have deviations of 1 or less pixels.
271 constexpr double kSigmoidScalar = 0.06496;
272 constexpr double kSigmoidGrowthRate = -0.6221;
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800273 confidence_ =
274 kSigmoidCapacity /
275 (1.0 + kSigmoidScalar * std::exp(-kSigmoidGrowthRate * std_dev));
Milind Upadhyay14279de2022-02-26 16:07:53 -0800276
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800277 if (FLAGS_solver_output) {
278 LOG(INFO) << summary.FullReport();
279
280 LOG(INFO) << "roll: " << roll_;
281 LOG(INFO) << "pitch: " << pitch_;
282 LOG(INFO) << "yaw: " << yaw_;
283 LOG(INFO) << "angle to target (based on yaw): " << angle_to_target();
284 LOG(INFO) << "angle to camera (polar): " << angle_to_camera_;
285 LOG(INFO) << "distance (polar): " << distance_;
286 LOG(INFO) << "camera height: " << camera_height_;
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800287 LOG(INFO) << "standard deviation (px): " << std_dev;
Milind Upadhyay14279de2022-02-26 16:07:53 -0800288 LOG(INFO) << "confidence: " << confidence_;
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800289 }
290}
291
292namespace {
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700293
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800294// Hacks to extract a double from a scalar, which is either a ceres jet or a
295// double. Only used for debugging and displaying.
296template <typename S>
297double ScalarToDouble(S s) {
298 const double *ptr = reinterpret_cast<double *>(&s);
299 return *ptr;
300}
301
302template <typename S>
303cv::Point2d ScalarPointToDouble(cv::Point_<S> p) {
304 return cv::Point2d(ScalarToDouble(p.x), ScalarToDouble(p.y));
305}
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700306
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800307} // namespace
308
309template <typename S>
310bool TargetEstimator::operator()(const S *const roll, const S *const pitch,
311 const S *const yaw, const S *const distance,
312 const S *const theta,
313 const S *const camera_height,
314 S *residual) const {
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700315 const auto H_hub_camera = ComputeHubCameraTransform(
316 *roll, *pitch, *yaw, *distance, *theta, *camera_height);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800317
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700318 // Project tape points
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800319 std::vector<cv::Point_<S>> tape_points_proj;
320 for (cv::Point3d tape_point_hub : kTapePoints) {
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800321 tape_points_proj.emplace_back(ProjectToImage(tape_point_hub, H_hub_camera));
322 VLOG(2) << "Projected tape point: "
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800323 << ScalarPointToDouble(
324 tape_points_proj[tape_points_proj.size() - 1]);
325 }
326
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800327 // Find the rectangle bounding the projected piece of tape
328 std::array<cv::Point_<S>, 4> middle_tape_piece_points_proj;
329 for (auto tape_piece_it = kMiddleTapePiecePoints.begin();
330 tape_piece_it < kMiddleTapePiecePoints.end(); tape_piece_it++) {
331 middle_tape_piece_points_proj[tape_piece_it -
332 kMiddleTapePiecePoints.begin()] =
333 ProjectToImage(*tape_piece_it, H_hub_camera);
334 }
335
Austin Schuha685b5d2022-04-02 14:53:54 -0700336 // Now, find the closest tape for each blob.
337 // We don't normally see tape without matching blobs in the center. So we
338 // want to compress any gaps in the matched tape blobs. This makes it so it
339 // doesn't want to make the goal super small and skip tape blobs. The
340 // resulting accuracy is then pretty good.
341
342 // Mapping from tape index to blob index.
343 std::vector<std::pair<size_t, size_t>> tape_indices;
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800344 for (size_t i = 0; i < blob_stats_.size(); i++) {
Austin Schuha685b5d2022-04-02 14:53:54 -0700345 tape_indices.emplace_back(ClosestTape(i, tape_points_proj), i);
346 VLOG(2) << "Tape indices were " << tape_indices.back().first;
347 }
348
349 std::sort(
350 tape_indices.begin(), tape_indices.end(),
351 [](const std::pair<size_t, size_t> &a,
352 const std::pair<size_t, size_t> &b) { return a.first < b.first; });
353
354 size_t middle_tape_index = 1000;
355 for (size_t i = 0; i < tape_indices.size(); ++i) {
356 if (tape_indices[i].second == middle_blob_index_) {
357 middle_tape_index = i;
358 }
359 }
360 CHECK_NE(middle_tape_index, 1000) << "Failed to find middle tape";
361
362 if (VLOG_IS_ON(2)) {
363 LOG(INFO) << "Middle tape is " << middle_tape_index << ", blob "
364 << middle_blob_index_;
365 for (size_t i = 0; i < tape_indices.size(); ++i) {
366 const auto distance = DistanceFromTapeIndex(
367 tape_indices[i].second, tape_indices[i].first, tape_points_proj);
368 LOG(INFO) << "Blob index " << tape_indices[i].second << " maps to "
369 << tape_indices[i].first << " distance " << distance.x << " "
370 << distance.y;
371 }
372 }
373
374 {
375 size_t offset = 0;
376 for (size_t i = middle_tape_index + 1; i < tape_indices.size(); ++i) {
377 tape_indices[i].first -= offset;
378
379 if (tape_indices[i].first > tape_indices[i - 1].first + 1) {
380 offset += tape_indices[i].first - (tape_indices[i - 1].first + 1);
381 VLOG(2) << "Offset now " << offset;
382 tape_indices[i].first = tape_indices[i - 1].first + 1;
383 }
384 }
385 }
386
387 if (VLOG_IS_ON(2)) {
388 LOG(INFO) << "Middle tape is " << middle_tape_index << ", blob "
389 << middle_blob_index_;
390 for (size_t i = 0; i < tape_indices.size(); ++i) {
391 const auto distance = DistanceFromTapeIndex(
392 tape_indices[i].second, tape_indices[i].first, tape_points_proj);
393 LOG(INFO) << "Blob index " << tape_indices[i].second << " maps to "
394 << tape_indices[i].first << " distance " << distance.x << " "
395 << distance.y;
396 }
397 }
398
399 {
400 size_t offset = 0;
401 for (size_t i = middle_tape_index; i > 0; --i) {
402 tape_indices[i - 1].first -= offset;
403
404 if (tape_indices[i - 1].first + 1 < tape_indices[i].first) {
405 VLOG(2) << "Too big a gap. " << tape_indices[i].first << " and "
406 << tape_indices[i - 1].first;
407
408 offset += tape_indices[i].first - (tape_indices[i - 1].first + 1);
409 tape_indices[i - 1].first = tape_indices[i].first - 1;
410 VLOG(2) << "Offset now " << offset;
411 }
412 }
413 }
414
415 if (VLOG_IS_ON(2)) {
416 LOG(INFO) << "Middle tape is " << middle_tape_index << ", blob "
417 << middle_blob_index_;
418 for (size_t i = 0; i < tape_indices.size(); ++i) {
419 const auto distance = DistanceFromTapeIndex(
420 tape_indices[i].second, tape_indices[i].first, tape_points_proj);
421 LOG(INFO) << "Blob index " << tape_indices[i].second << " maps to "
422 << tape_indices[i].first << " distance " << distance.x << " "
423 << distance.y;
424 }
425 }
426
427 for (size_t i = 0; i < tape_indices.size(); ++i) {
428 const auto distance = DistanceFromTapeIndex(
429 tape_indices[i].second, tape_indices[i].first, tape_points_proj);
430 VLOG(2) << "Blob index " << tape_indices[i].second << " maps to "
431 << tape_indices[i].first << " distance " << distance.x << " "
432 << distance.y;
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800433 // Set the residual to the (x, y) distance of the centroid from the
Austin Schuha685b5d2022-04-02 14:53:54 -0700434 // matched projected piece of tape
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800435 residual[i * 2] = distance.x;
436 residual[(i * 2) + 1] = distance.y;
437 }
438
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800439 // Penalize based on the difference between the size of the projected piece of
Austin Schuha685b5d2022-04-02 14:53:54 -0700440 // tape and that of the detected blobs.
441 const S middle_tape_piece_width = ceres::hypot(
442 middle_tape_piece_points_proj[2].x - middle_tape_piece_points_proj[3].x,
443 middle_tape_piece_points_proj[2].y - middle_tape_piece_points_proj[3].y);
444 const S middle_tape_piece_height = ceres::hypot(
445 middle_tape_piece_points_proj[1].x - middle_tape_piece_points_proj[2].x,
446 middle_tape_piece_points_proj[1].y - middle_tape_piece_points_proj[2].y);
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800447
Austin Schuha685b5d2022-04-02 14:53:54 -0700448 constexpr double kCenterBlobSizeScalar = 0.1;
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800449 residual[blob_stats_.size() * 2] =
Austin Schuha685b5d2022-04-02 14:53:54 -0700450 kCenterBlobSizeScalar *
451 (middle_tape_piece_width -
452 static_cast<S>(blob_stats_[middle_blob_index_].size.width));
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800453 residual[(blob_stats_.size() * 2) + 1] =
Austin Schuha685b5d2022-04-02 14:53:54 -0700454 kCenterBlobSizeScalar *
455 (middle_tape_piece_height -
456 static_cast<S>(blob_stats_[middle_blob_index_].size.height));
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800457
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800458 if (image_.has_value()) {
459 // Draw the current stage of the solving
460 cv::Mat image = image_->clone();
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700461 std::vector<cv::Point2d> tape_points_proj_double;
462 for (auto point : tape_points_proj) {
463 tape_points_proj_double.emplace_back(ScalarPointToDouble(point));
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800464 }
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700465 DrawProjectedHub(tape_points_proj_double, image);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800466 cv::imshow("image", image);
467 cv::waitKey(10);
468 }
469
470 return true;
471}
472
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800473template <typename S>
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700474Eigen::Transform<S, 3, Eigen::Affine>
475TargetEstimator::ComputeHubCameraTransform(S roll, S pitch, S yaw, S distance,
476 S theta, S camera_height) const {
477 using Vector3s = Eigen::Matrix<S, 3, 1>;
478 using Affine3s = Eigen::Transform<S, 3, Eigen::Affine>;
479
480 Eigen::AngleAxis<S> roll_angle(roll, Vector3s::UnitX());
481 Eigen::AngleAxis<S> pitch_angle(pitch, Vector3s::UnitY());
482 Eigen::AngleAxis<S> yaw_angle(yaw, Vector3s::UnitZ());
483 // Construct the rotation and translation of the camera in the hub's frame
484 Eigen::Quaternion<S> R_camera_hub = yaw_angle * pitch_angle * roll_angle;
485 Vector3s T_camera_hub(distance * ceres::cos(theta),
486 distance * ceres::sin(theta), camera_height);
487
488 Affine3s H_camera_hub = Eigen::Translation<S, 3>(T_camera_hub) * R_camera_hub;
489 Affine3s H_hub_camera = H_camera_hub.inverse();
490
491 return H_hub_camera;
492}
493
494template <typename S>
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800495cv::Point_<S> TargetEstimator::ProjectToImage(
496 cv::Point3d tape_point_hub,
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700497 const Eigen::Transform<S, 3, Eigen::Affine> &H_hub_camera) const {
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800498 using Vector3s = Eigen::Matrix<S, 3, 1>;
499
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800500 const Vector3s tape_point_hub_eigen =
501 Vector3s(S(tape_point_hub.x), S(tape_point_hub.y), S(tape_point_hub.z));
502 // Project the 3d tape point onto the image using the transformation and
503 // intrinsics
504 const Vector3s tape_point_proj =
milind-ucafdd5d2022-03-01 19:58:57 -0800505 intrinsics_ * (kHubToCameraAxes * (H_hub_camera * tape_point_hub_eigen));
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800506
507 // Normalize the projected point
508 return {tape_point_proj.x() / tape_point_proj.z(),
509 tape_point_proj.y() / tape_point_proj.z()};
510}
511
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800512namespace {
513template <typename S>
514cv::Point_<S> Distance(cv::Point p, cv::Point_<S> q) {
515 return cv::Point_<S>(S(p.x) - q.x, S(p.y) - q.y);
516}
517
518template <typename S>
519bool Less(cv::Point_<S> distance_1, cv::Point_<S> distance_2) {
520 return (ceres::pow(distance_1.x, 2) + ceres::pow(distance_1.y, 2) <
521 ceres::pow(distance_2.x, 2) + ceres::pow(distance_2.y, 2));
522}
523} // namespace
524
525template <typename S>
Austin Schuha685b5d2022-04-02 14:53:54 -0700526cv::Point_<S> TargetEstimator::DistanceFromTapeIndex(
527 size_t blob_index, size_t tape_index,
528 const std::vector<cv::Point_<S>> &tape_points) const {
529 return Distance(blob_stats_[blob_index].centroid, tape_points[tape_index]);
530}
531
532template <typename S>
533size_t TargetEstimator::ClosestTape(
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800534 size_t blob_index, const std::vector<cv::Point_<S>> &tape_points) const {
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800535 auto distance = cv::Point_<S>(std::numeric_limits<S>::infinity(),
536 std::numeric_limits<S>::infinity());
Austin Schuha685b5d2022-04-02 14:53:54 -0700537 size_t final_match = 255;
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800538 if (blob_index == middle_blob_index_) {
539 // Fix the middle blob so the solver can't go too far off
Austin Schuha685b5d2022-04-02 14:53:54 -0700540 final_match = tape_points.size() / 2;
541 distance = DistanceFromTapeIndex(blob_index, final_match, tape_points);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800542 } else {
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800543 // Give the other blob_stats some freedom in case some are split into pieces
544 for (auto it = tape_points.begin(); it < tape_points.end(); it++) {
Austin Schuha685b5d2022-04-02 14:53:54 -0700545 const size_t tape_index = std::distance(tape_points.begin(), it);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800546 const auto current_distance =
Austin Schuha685b5d2022-04-02 14:53:54 -0700547 DistanceFromTapeIndex(blob_index, tape_index, tape_points);
548 if ((tape_index != (tape_points.size() / 2)) &&
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800549 Less(current_distance, distance)) {
Austin Schuha685b5d2022-04-02 14:53:54 -0700550 final_match = tape_index;
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800551 distance = current_distance;
552 }
553 }
554 }
555
Austin Schuha685b5d2022-04-02 14:53:54 -0700556 VLOG(2) << "Matched index " << blob_index << " to " << final_match
557 << " distance " << distance.x << " " << distance.y;
558 CHECK_NE(final_match, 255);
559
560 return final_match;
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800561}
562
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700563void TargetEstimator::DrawProjectedHub(
564 const std::vector<cv::Point2d> &tape_points_proj,
565 cv::Mat view_image) const {
566 for (size_t i = 0; i < tape_points_proj.size() - 1; i++) {
567 cv::line(view_image, ScalarPointToDouble(tape_points_proj[i]),
568 ScalarPointToDouble(tape_points_proj[i + 1]),
569 cv::Scalar(255, 255, 255));
570 cv::circle(view_image, ScalarPointToDouble(tape_points_proj[i]), 2,
571 cv::Scalar(255, 20, 147), cv::FILLED);
572 cv::circle(view_image, ScalarPointToDouble(tape_points_proj[i + 1]), 2,
573 cv::Scalar(255, 20, 147), cv::FILLED);
574 }
575}
576
577void TargetEstimator::DrawEstimate(cv::Mat view_image) const {
578 if (FLAGS_draw_projected_hub) {
579 // Draw projected hub
580 const auto H_hub_camera = ComputeHubCameraTransform(
581 roll_, pitch_, yaw_, distance_, angle_to_camera_, camera_height_);
582 std::vector<cv::Point2d> tape_points_proj;
583 for (cv::Point3d tape_point_hub : kTapePoints) {
584 tape_points_proj.emplace_back(
585 ProjectToImage(tape_point_hub, H_hub_camera));
586 }
587 DrawProjectedHub(tape_points_proj, view_image);
588 }
589
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800590 constexpr int kTextX = 10;
Milind Upadhyay2da80bb2022-03-12 22:54:35 -0800591 int text_y = 0;
592 constexpr int kTextSpacing = 25;
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800593
594 const auto kTextColor = cv::Scalar(0, 255, 255);
Milind Upadhyay2da80bb2022-03-12 22:54:35 -0800595 constexpr double kFontScale = 0.6;
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800596
Jim Ostrowskib3d5f582022-04-02 20:22:49 -0700597 cv::putText(view_image,
598 absl::StrFormat("Distance: %.3f m (%.3f in)", distance_,
599 distance_ / 0.0254),
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800600 cv::Point(kTextX, text_y += kTextSpacing),
601 cv::FONT_HERSHEY_DUPLEX, kFontScale, kTextColor, 2);
602 cv::putText(view_image,
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700603 absl::StrFormat("Angle to target: %.3f", angle_to_target()),
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800604 cv::Point(kTextX, text_y += kTextSpacing),
605 cv::FONT_HERSHEY_DUPLEX, kFontScale, kTextColor, 2);
606 cv::putText(view_image,
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700607 absl::StrFormat("Angle to camera: %.3f", angle_to_camera_),
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800608 cv::Point(kTextX, text_y += kTextSpacing),
609 cv::FONT_HERSHEY_DUPLEX, kFontScale, kTextColor, 2);
610
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700611 cv::putText(view_image,
612 absl::StrFormat("Roll: %.3f, pitch: %.3f, yaw: %.3f", roll_,
613 pitch_, yaw_),
Milind Upadhyay14279de2022-02-26 16:07:53 -0800614 cv::Point(kTextX, text_y += kTextSpacing),
615 cv::FONT_HERSHEY_DUPLEX, kFontScale, kTextColor, 2);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800616
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700617 cv::putText(view_image, absl::StrFormat("Confidence: %.3f", confidence_),
618 cv::Point(kTextX, text_y += kTextSpacing),
619 cv::FONT_HERSHEY_DUPLEX, kFontScale, kTextColor, 2);
milind-u92195982022-01-22 20:29:31 -0800620}
621
622} // namespace y2022::vision