blob: ecff719771c759048c048eae48b21b920c34c5da [file] [log] [blame]
milind-u92195982022-01-22 20:29:31 -08001#include "y2022/vision/target_estimator.h"
2
Austin Schuh99f7c6a2024-06-25 22:07:44 -07003#include "absl/flags/flag.h"
Milind Upadhyayf61e1482022-02-11 20:42:55 -08004#include "absl/strings/str_format.h"
Milind Upadhyayf61e1482022-02-11 20:42:55 -08005#include "ceres/ceres.h"
Milind Upadhyayf61e1482022-02-11 20:42:55 -08006#include "opencv2/core/core.hpp"
7#include "opencv2/core/eigen.hpp"
8#include "opencv2/features2d.hpp"
9#include "opencv2/highgui/highgui.hpp"
10#include "opencv2/imgproc.hpp"
Philipp Schrader790cb542023-07-05 21:06:52 -070011
12#include "aos/time/time.h"
13#include "frc971/control_loops/quaternion_utils.h"
14#include "frc971/vision/geometry.h"
milind-ucafdd5d2022-03-01 19:58:57 -080015#include "y2022/constants.h"
Milind Upadhyayf61e1482022-02-11 20:42:55 -080016
Austin Schuh99f7c6a2024-06-25 22:07:44 -070017ABSL_FLAG(bool, freeze_roll, false, "If true, don't solve for roll");
18ABSL_FLAG(bool, freeze_pitch, false, "If true, don't solve for pitch");
19ABSL_FLAG(bool, freeze_yaw, false, "If true, don't solve for yaw");
20ABSL_FLAG(bool, freeze_camera_height, true,
21 "If true, don't solve for camera height");
22ABSL_FLAG(bool, freeze_angle_to_camera, true,
23 "If true, don't solve for polar angle to camera");
Milind Upadhyayf61e1482022-02-11 20:42:55 -080024
Austin Schuh99f7c6a2024-06-25 22:07:44 -070025ABSL_FLAG(uint64_t, max_solver_iterations, 200,
26 "Maximum number of iterations for the ceres solver");
27ABSL_FLAG(bool, solver_output, false,
28 "If true, log the solver progress and results");
29ABSL_FLAG(bool, draw_projected_hub, true,
30 "If true, draw the projected hub when drawing an estimate");
Milind Upadhyayf61e1482022-02-11 20:42:55 -080031
milind-u92195982022-01-22 20:29:31 -080032namespace y2022::vision {
33
Milind Upadhyay8f38ad82022-03-03 10:06:18 -080034namespace {
35
36constexpr size_t kNumPiecesOfTape = 16;
37// Width and height of a piece of reflective tape
38constexpr double kTapePieceWidth = 0.13;
39constexpr double kTapePieceHeight = 0.05;
40// Height of the center of the tape (m)
41constexpr double kTapeCenterHeight = 2.58 + (kTapePieceHeight / 2);
42// Horizontal distance from tape to center of hub (m)
Austin Schuha685b5d2022-04-02 14:53:54 -070043constexpr double kUpperHubRadius = 1.36 / 2;
Milind Upadhyay8f38ad82022-03-03 10:06:18 -080044
45std::vector<cv::Point3d> ComputeTapePoints() {
Milind Upadhyayf61e1482022-02-11 20:42:55 -080046 std::vector<cv::Point3d> tape_points;
milind-u92195982022-01-22 20:29:31 -080047
Milind Upadhyayf61e1482022-02-11 20:42:55 -080048 constexpr size_t kNumVisiblePiecesOfTape = 5;
49 for (size_t i = 0; i < kNumVisiblePiecesOfTape; i++) {
50 // The center piece of tape is at 0 rad, so the angle indices are offset
51 // by the number of pieces of tape on each side of it
52 const double theta_index =
53 static_cast<double>(i) - ((kNumVisiblePiecesOfTape - 1) / 2);
54 // The polar angle is a multiple of the angle between tape centers
55 double theta = theta_index * ((2.0 * M_PI) / kNumPiecesOfTape);
56 tape_points.emplace_back(kUpperHubRadius * std::cos(theta),
Milind Upadhyay8f38ad82022-03-03 10:06:18 -080057 kUpperHubRadius * std::sin(theta),
58 kTapeCenterHeight);
Milind Upadhyayf61e1482022-02-11 20:42:55 -080059 }
milind-u92195982022-01-22 20:29:31 -080060
Milind Upadhyayf61e1482022-02-11 20:42:55 -080061 return tape_points;
62}
milind-u92195982022-01-22 20:29:31 -080063
Milind Upadhyay8f38ad82022-03-03 10:06:18 -080064std::array<cv::Point3d, 4> ComputeMiddleTapePiecePoints() {
65 std::array<cv::Point3d, 4> tape_piece_points;
66
67 // Angle that each piece of tape occupies on the hub
68 constexpr double kTapePieceAngle =
69 (kTapePieceWidth / (2.0 * M_PI * kUpperHubRadius)) * (2.0 * M_PI);
70
71 constexpr double kThetaTapeLeft = -kTapePieceAngle / 2.0;
72 constexpr double kThetaTapeRight = kTapePieceAngle / 2.0;
73
74 constexpr double kTapeTopHeight =
75 kTapeCenterHeight + (kTapePieceHeight / 2.0);
76 constexpr double kTapeBottomHeight =
77 kTapeCenterHeight - (kTapePieceHeight / 2.0);
78
79 tape_piece_points[0] = {kUpperHubRadius * std::cos(kThetaTapeLeft),
80 kUpperHubRadius * std::sin(kThetaTapeLeft),
81 kTapeTopHeight};
82 tape_piece_points[1] = {kUpperHubRadius * std::cos(kThetaTapeRight),
83 kUpperHubRadius * std::sin(kThetaTapeRight),
84 kTapeTopHeight};
85
86 tape_piece_points[2] = {kUpperHubRadius * std::cos(kThetaTapeRight),
87 kUpperHubRadius * std::sin(kThetaTapeRight),
88 kTapeBottomHeight};
89 tape_piece_points[3] = {kUpperHubRadius * std::cos(kThetaTapeLeft),
90 kUpperHubRadius * std::sin(kThetaTapeLeft),
91 kTapeBottomHeight};
92
93 return tape_piece_points;
94}
95
96} // namespace
97
Milind Upadhyayf61e1482022-02-11 20:42:55 -080098const std::vector<cv::Point3d> TargetEstimator::kTapePoints =
99 ComputeTapePoints();
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800100const std::array<cv::Point3d, 4> TargetEstimator::kMiddleTapePiecePoints =
101 ComputeMiddleTapePiecePoints();
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800102
Milind Upadhyaye5003102022-04-02 22:16:39 -0700103namespace {
104constexpr double kDefaultDistance = 3.0;
105constexpr double kDefaultYaw = M_PI;
106constexpr double kDefaultAngleToCamera = 0.0;
107} // namespace
108
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800109TargetEstimator::TargetEstimator(cv::Mat intrinsics, cv::Mat extrinsics)
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800110 : blob_stats_(),
Milind Upadhyay1c76a042022-04-02 20:42:42 -0700111 middle_blob_index_(0),
112 max_blob_area_(0.0),
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800113 image_(std::nullopt),
114 roll_(0.0),
115 pitch_(0.0),
Milind Upadhyaye5003102022-04-02 22:16:39 -0700116 yaw_(kDefaultYaw),
117 distance_(kDefaultDistance),
118 angle_to_camera_(kDefaultAngleToCamera),
milind-ucafdd5d2022-03-01 19:58:57 -0800119 // Seed camera height
120 camera_height_(extrinsics.at<double>(2, 3) +
121 constants::Values::kImuHeight()) {
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800122 cv::cv2eigen(intrinsics, intrinsics_);
123 cv::cv2eigen(extrinsics, extrinsics_);
124}
125
126namespace {
127void SetBoundsOrFreeze(double *param, bool freeze, double min, double max,
128 ceres::Problem *problem) {
129 if (freeze) {
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800130 problem->SetParameterBlockConstant(param);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800131 } else {
132 problem->SetParameterLowerBound(param, 0, min);
133 problem->SetParameterUpperBound(param, 0, max);
134 }
135}
milind-ucafdd5d2022-03-01 19:58:57 -0800136
137// With X, Y, Z being hub axes and x, y, z being camera axes,
138// x = -Y, y = -Z, z = X
139const Eigen::Matrix3d kHubToCameraAxes =
140 (Eigen::Matrix3d() << 0.0, -1.0, 0.0, 0.0, 0.0, -1.0, 1.0, 0.0, 0.0)
141 .finished();
142
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800143} // namespace
144
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800145void TargetEstimator::Solve(
146 const std::vector<BlobDetector::BlobStats> &blob_stats,
147 std::optional<cv::Mat> image) {
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800148 auto start = aos::monotonic_clock::now();
149
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800150 blob_stats_ = blob_stats;
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800151 image_ = image;
152
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800153 // Do nothing if no blobs were detected
154 if (blob_stats_.size() == 0) {
155 confidence_ = 0.0;
156 return;
157 }
158
159 CHECK_GE(blob_stats_.size(), 3) << "Expected at least 3 blobs";
160
Milind Upadhyayb67c6182022-10-22 13:45:45 -0700161 const auto circle = frc971::vision::Circle::Fit({blob_stats_[0].centroid,
162 blob_stats_[1].centroid,
163 blob_stats_[2].centroid});
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800164 CHECK(circle.has_value());
165
Milind Upadhyay1c76a042022-04-02 20:42:42 -0700166 max_blob_area_ = 0.0;
167
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800168 // Find the middle blob, which is the one with the angle closest to the
169 // average
170 double theta_avg = 0.0;
171 for (const auto &stats : blob_stats_) {
172 theta_avg += circle->AngleOf(stats.centroid);
Milind Upadhyay1c76a042022-04-02 20:42:42 -0700173
174 if (stats.area > max_blob_area_) {
175 max_blob_area_ = stats.area;
176 }
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800177 }
178 theta_avg /= blob_stats_.size();
179
180 double min_diff = std::numeric_limits<double>::infinity();
181 for (auto it = blob_stats_.begin(); it < blob_stats_.end(); it++) {
182 const double diff = std::abs(circle->AngleOf(it->centroid) - theta_avg);
183 if (diff < min_diff) {
184 min_diff = diff;
185 middle_blob_index_ = it - blob_stats_.begin();
186 }
187 }
188
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800189 ceres::Problem problem;
190
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800191 // x and y differences between projected centroids and blob centroids, as well
192 // as width and height differences between middle projected piece and the
193 // detected blob
194 const size_t num_residuals = (blob_stats_.size() * 2) + 2;
195
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800196 // Set up the only cost function (also known as residual). This uses
197 // auto-differentiation to obtain the derivative (jacobian).
198 ceres::CostFunction *cost_function =
199 new ceres::AutoDiffCostFunction<TargetEstimator, ceres::DYNAMIC, 1, 1, 1,
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800200 1, 1, 1>(this, num_residuals,
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800201 ceres::DO_NOT_TAKE_OWNERSHIP);
202
203 // TODO(milind): add loss function when we get more noisy data
Austin Schuha685b5d2022-04-02 14:53:54 -0700204 problem.AddResidualBlock(cost_function, new ceres::HuberLoss(2.0), &roll_,
205 &pitch_, &yaw_, &distance_, &angle_to_camera_,
206 &camera_height_);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800207
milind-ucafdd5d2022-03-01 19:58:57 -0800208 // Compute the estimated rotation of the camera using the robot rotation.
Milind Upadhyayda042bb2022-03-26 16:01:45 -0700209 const Eigen::Matrix3d extrinsics_rot =
210 Eigen::Affine3d(extrinsics_).rotation() * kHubToCameraAxes;
211 // asin returns a pitch in [-pi/2, pi/2] so this will be the correct euler
212 // angles.
213 const double pitch_seed = -std::asin(extrinsics_rot(2, 0));
214 const double roll_seed =
215 std::atan2(extrinsics_rot(2, 1) / std::cos(pitch_seed),
216 extrinsics_rot(2, 2) / std::cos(pitch_seed));
217
milind-ucafdd5d2022-03-01 19:58:57 -0800218 // TODO(milind): seed with localizer output as well
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800219
Milind Upadhyaye5003102022-04-02 22:16:39 -0700220 // If we didn't solve well last time, seed everything at the defaults so we
221 // don't get stuck in a bad state.
222 // Copied from localizer.cc
223 constexpr double kMinConfidence = 0.75;
224 if (confidence_ < kMinConfidence) {
225 roll_ = roll_seed;
226 pitch_ = pitch_seed;
227 yaw_ = kDefaultYaw;
228 distance_ = kDefaultDistance;
229 angle_to_camera_ = kDefaultAngleToCamera;
230 camera_height_ = extrinsics_(2, 3) + constants::Values::kImuHeight();
231 }
232
milind-ucafdd5d2022-03-01 19:58:57 -0800233 // Constrain the rotation to be around the localizer's, otherwise there can be
234 // multiple solutions. There shouldn't be too much roll or pitch
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700235 if (absl::GetFlag(FLAGS_freeze_roll)) {
Milind Upadhyay1d9a9c72022-04-02 14:18:40 -0700236 roll_ = roll_seed;
237 }
milind-ucafdd5d2022-03-01 19:58:57 -0800238 constexpr double kMaxRollDelta = 0.1;
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700239 SetBoundsOrFreeze(&roll_, absl::GetFlag(FLAGS_freeze_roll),
240 roll_seed - kMaxRollDelta, roll_seed + kMaxRollDelta,
241 &problem);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800242
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700243 if (absl::GetFlag(FLAGS_freeze_pitch)) {
Milind Upadhyay1d9a9c72022-04-02 14:18:40 -0700244 pitch_ = pitch_seed;
245 }
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800246 constexpr double kMaxPitchDelta = 0.15;
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700247 SetBoundsOrFreeze(&pitch_, absl::GetFlag(FLAGS_freeze_pitch),
248 pitch_seed - kMaxPitchDelta, pitch_seed + kMaxPitchDelta,
249 &problem);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800250 // Constrain the yaw to where the target would be visible
251 constexpr double kMaxYawDelta = M_PI / 4.0;
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700252 SetBoundsOrFreeze(&yaw_, absl::GetFlag(FLAGS_freeze_yaw), M_PI - kMaxYawDelta,
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800253 M_PI + kMaxYawDelta, &problem);
254
255 constexpr double kMaxHeightDelta = 0.1;
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700256 SetBoundsOrFreeze(&camera_height_, absl::GetFlag(FLAGS_freeze_camera_height),
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800257 camera_height_ - kMaxHeightDelta,
258 camera_height_ + kMaxHeightDelta, &problem);
259
260 // Distances shouldn't be too close to the target or too far
261 constexpr double kMinDistance = 1.0;
262 constexpr double kMaxDistance = 10.0;
263 SetBoundsOrFreeze(&distance_, false, kMinDistance, kMaxDistance, &problem);
264
265 // Keep the angle between +/- half of the angle between piece of tape
266 constexpr double kMaxAngle = ((2.0 * M_PI) / kNumPiecesOfTape) / 2.0;
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700267 SetBoundsOrFreeze(&angle_to_camera_,
268 absl::GetFlag(FLAGS_freeze_angle_to_camera), -kMaxAngle,
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800269 kMaxAngle, &problem);
270
271 ceres::Solver::Options options;
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700272 options.minimizer_progress_to_stdout = absl::GetFlag(FLAGS_solver_output);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800273 options.gradient_tolerance = 1e-12;
274 options.function_tolerance = 1e-16;
275 options.parameter_tolerance = 1e-12;
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700276 options.max_num_iterations = absl::GetFlag(FLAGS_max_solver_iterations);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800277 ceres::Solver::Summary summary;
278 ceres::Solve(options, &problem, &summary);
279
280 auto end = aos::monotonic_clock::now();
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800281 VLOG(1) << "Target estimation elapsed time: "
282 << std::chrono::duration<double, std::milli>(end - start).count()
283 << " ms";
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800284
Milind Upadhyay1c76a042022-04-02 20:42:42 -0700285 // For computing the confidence, find the standard deviation in pixels.
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800286 std::vector<double> residual(num_residuals);
287 (*this)(&roll_, &pitch_, &yaw_, &distance_, &angle_to_camera_,
288 &camera_height_, residual.data());
289 double std_dev = 0.0;
290 for (auto it = residual.begin(); it < residual.end() - 2; it++) {
291 std_dev += std::pow(*it, 2);
Milind Upadhyay14279de2022-02-26 16:07:53 -0800292 }
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800293 std_dev /= num_residuals - 2;
294 std_dev = std::sqrt(std_dev);
295
296 // Use a sigmoid to convert the deviation into a confidence for the
297 // localizer. Fit a sigmoid to the points of (0, 1) and two other
298 // reasonable deviation-confidence combinations using
Milind Upadhyayda9a8292022-04-02 18:00:04 -0700299 // https://www.desmos.com/calculator/ha6fh9yw44
300 constexpr double kSigmoidCapacity = 1.065;
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800301 // Stretch the sigmoid out correctly.
Milind Upadhyayda9a8292022-04-02 18:00:04 -0700302 // Currently, good estimates have deviations of 1 or less pixels.
303 constexpr double kSigmoidScalar = 0.06496;
304 constexpr double kSigmoidGrowthRate = -0.6221;
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800305 confidence_ =
306 kSigmoidCapacity /
307 (1.0 + kSigmoidScalar * std::exp(-kSigmoidGrowthRate * std_dev));
Milind Upadhyay14279de2022-02-26 16:07:53 -0800308
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700309 if (absl::GetFlag(FLAGS_solver_output)) {
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800310 LOG(INFO) << summary.FullReport();
311
312 LOG(INFO) << "roll: " << roll_;
313 LOG(INFO) << "pitch: " << pitch_;
314 LOG(INFO) << "yaw: " << yaw_;
315 LOG(INFO) << "angle to target (based on yaw): " << angle_to_target();
316 LOG(INFO) << "angle to camera (polar): " << angle_to_camera_;
317 LOG(INFO) << "distance (polar): " << distance_;
318 LOG(INFO) << "camera height: " << camera_height_;
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800319 LOG(INFO) << "standard deviation (px): " << std_dev;
Milind Upadhyay14279de2022-02-26 16:07:53 -0800320 LOG(INFO) << "confidence: " << confidence_;
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800321 }
322}
323
324namespace {
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700325
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800326// Hacks to extract a double from a scalar, which is either a ceres jet or a
327// double. Only used for debugging and displaying.
328template <typename S>
329double ScalarToDouble(S s) {
330 const double *ptr = reinterpret_cast<double *>(&s);
331 return *ptr;
332}
333
334template <typename S>
335cv::Point2d ScalarPointToDouble(cv::Point_<S> p) {
336 return cv::Point2d(ScalarToDouble(p.x), ScalarToDouble(p.y));
337}
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700338
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800339} // namespace
340
341template <typename S>
342bool TargetEstimator::operator()(const S *const roll, const S *const pitch,
343 const S *const yaw, const S *const distance,
344 const S *const theta,
345 const S *const camera_height,
346 S *residual) const {
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700347 const auto H_hub_camera = ComputeHubCameraTransform(
348 *roll, *pitch, *yaw, *distance, *theta, *camera_height);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800349
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700350 // Project tape points
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800351 std::vector<cv::Point_<S>> tape_points_proj;
352 for (cv::Point3d tape_point_hub : kTapePoints) {
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800353 tape_points_proj.emplace_back(ProjectToImage(tape_point_hub, H_hub_camera));
354 VLOG(2) << "Projected tape point: "
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800355 << ScalarPointToDouble(
356 tape_points_proj[tape_points_proj.size() - 1]);
357 }
358
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800359 // Find the rectangle bounding the projected piece of tape
360 std::array<cv::Point_<S>, 4> middle_tape_piece_points_proj;
361 for (auto tape_piece_it = kMiddleTapePiecePoints.begin();
362 tape_piece_it < kMiddleTapePiecePoints.end(); tape_piece_it++) {
363 middle_tape_piece_points_proj[tape_piece_it -
364 kMiddleTapePiecePoints.begin()] =
365 ProjectToImage(*tape_piece_it, H_hub_camera);
366 }
367
Austin Schuha685b5d2022-04-02 14:53:54 -0700368 // Now, find the closest tape for each blob.
369 // We don't normally see tape without matching blobs in the center. So we
370 // want to compress any gaps in the matched tape blobs. This makes it so it
371 // doesn't want to make the goal super small and skip tape blobs. The
372 // resulting accuracy is then pretty good.
373
374 // Mapping from tape index to blob index.
375 std::vector<std::pair<size_t, size_t>> tape_indices;
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800376 for (size_t i = 0; i < blob_stats_.size(); i++) {
Austin Schuha685b5d2022-04-02 14:53:54 -0700377 tape_indices.emplace_back(ClosestTape(i, tape_points_proj), i);
378 VLOG(2) << "Tape indices were " << tape_indices.back().first;
379 }
380
381 std::sort(
382 tape_indices.begin(), tape_indices.end(),
383 [](const std::pair<size_t, size_t> &a,
384 const std::pair<size_t, size_t> &b) { return a.first < b.first; });
385
Milind Upadhyaya31f0272022-04-03 13:55:22 -0700386 std::optional<size_t> middle_tape_index = std::nullopt;
Austin Schuha685b5d2022-04-02 14:53:54 -0700387 for (size_t i = 0; i < tape_indices.size(); ++i) {
388 if (tape_indices[i].second == middle_blob_index_) {
389 middle_tape_index = i;
390 }
391 }
Milind Upadhyaya31f0272022-04-03 13:55:22 -0700392 CHECK(middle_tape_index.has_value()) << "Failed to find middle tape";
Austin Schuha685b5d2022-04-02 14:53:54 -0700393
394 if (VLOG_IS_ON(2)) {
Milind Upadhyaya31f0272022-04-03 13:55:22 -0700395 LOG(INFO) << "Middle tape is " << *middle_tape_index << ", blob "
Austin Schuha685b5d2022-04-02 14:53:54 -0700396 << middle_blob_index_;
397 for (size_t i = 0; i < tape_indices.size(); ++i) {
398 const auto distance = DistanceFromTapeIndex(
399 tape_indices[i].second, tape_indices[i].first, tape_points_proj);
400 LOG(INFO) << "Blob index " << tape_indices[i].second << " maps to "
401 << tape_indices[i].first << " distance " << distance.x << " "
402 << distance.y;
403 }
404 }
405
406 {
407 size_t offset = 0;
Milind Upadhyaya31f0272022-04-03 13:55:22 -0700408 for (size_t i = *middle_tape_index + 1; i < tape_indices.size(); ++i) {
Austin Schuha685b5d2022-04-02 14:53:54 -0700409 tape_indices[i].first -= offset;
410
411 if (tape_indices[i].first > tape_indices[i - 1].first + 1) {
412 offset += tape_indices[i].first - (tape_indices[i - 1].first + 1);
413 VLOG(2) << "Offset now " << offset;
414 tape_indices[i].first = tape_indices[i - 1].first + 1;
415 }
416 }
417 }
418
419 if (VLOG_IS_ON(2)) {
Milind Upadhyaya31f0272022-04-03 13:55:22 -0700420 LOG(INFO) << "Middle tape is " << *middle_tape_index << ", blob "
Austin Schuha685b5d2022-04-02 14:53:54 -0700421 << middle_blob_index_;
422 for (size_t i = 0; i < tape_indices.size(); ++i) {
423 const auto distance = DistanceFromTapeIndex(
424 tape_indices[i].second, tape_indices[i].first, tape_points_proj);
425 LOG(INFO) << "Blob index " << tape_indices[i].second << " maps to "
426 << tape_indices[i].first << " distance " << distance.x << " "
427 << distance.y;
428 }
429 }
430
431 {
432 size_t offset = 0;
Milind Upadhyaya31f0272022-04-03 13:55:22 -0700433 for (size_t i = *middle_tape_index; i > 0; --i) {
Austin Schuha685b5d2022-04-02 14:53:54 -0700434 tape_indices[i - 1].first -= offset;
435
436 if (tape_indices[i - 1].first + 1 < tape_indices[i].first) {
437 VLOG(2) << "Too big a gap. " << tape_indices[i].first << " and "
438 << tape_indices[i - 1].first;
439
440 offset += tape_indices[i].first - (tape_indices[i - 1].first + 1);
441 tape_indices[i - 1].first = tape_indices[i].first - 1;
442 VLOG(2) << "Offset now " << offset;
443 }
444 }
445 }
446
447 if (VLOG_IS_ON(2)) {
Milind Upadhyaya31f0272022-04-03 13:55:22 -0700448 LOG(INFO) << "Middle tape is " << *middle_tape_index << ", blob "
Austin Schuha685b5d2022-04-02 14:53:54 -0700449 << middle_blob_index_;
450 for (size_t i = 0; i < tape_indices.size(); ++i) {
451 const auto distance = DistanceFromTapeIndex(
452 tape_indices[i].second, tape_indices[i].first, tape_points_proj);
453 LOG(INFO) << "Blob index " << tape_indices[i].second << " maps to "
454 << tape_indices[i].first << " distance " << distance.x << " "
455 << distance.y;
456 }
457 }
458
459 for (size_t i = 0; i < tape_indices.size(); ++i) {
460 const auto distance = DistanceFromTapeIndex(
461 tape_indices[i].second, tape_indices[i].first, tape_points_proj);
Milind Upadhyay1c76a042022-04-02 20:42:42 -0700462 // Scale the distance based on the blob area: larger blobs have less noise.
463 const S distance_scalar =
464 S(blob_stats_[tape_indices[i].second].area / max_blob_area_);
Austin Schuha685b5d2022-04-02 14:53:54 -0700465 VLOG(2) << "Blob index " << tape_indices[i].second << " maps to "
466 << tape_indices[i].first << " distance " << distance.x << " "
Milind Upadhyay1c76a042022-04-02 20:42:42 -0700467 << distance.y << " distance scalar "
468 << ScalarToDouble(distance_scalar);
469
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800470 // Set the residual to the (x, y) distance of the centroid from the
Austin Schuha685b5d2022-04-02 14:53:54 -0700471 // matched projected piece of tape
Milind Upadhyay1c76a042022-04-02 20:42:42 -0700472 residual[i * 2] = distance_scalar * distance.x;
473 residual[(i * 2) + 1] = distance_scalar * distance.y;
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800474 }
475
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800476 // Penalize based on the difference between the size of the projected piece of
Austin Schuha685b5d2022-04-02 14:53:54 -0700477 // tape and that of the detected blobs.
478 const S middle_tape_piece_width = ceres::hypot(
479 middle_tape_piece_points_proj[2].x - middle_tape_piece_points_proj[3].x,
480 middle_tape_piece_points_proj[2].y - middle_tape_piece_points_proj[3].y);
481 const S middle_tape_piece_height = ceres::hypot(
482 middle_tape_piece_points_proj[1].x - middle_tape_piece_points_proj[2].x,
483 middle_tape_piece_points_proj[1].y - middle_tape_piece_points_proj[2].y);
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800484
Austin Schuha685b5d2022-04-02 14:53:54 -0700485 constexpr double kCenterBlobSizeScalar = 0.1;
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800486 residual[blob_stats_.size() * 2] =
Austin Schuha685b5d2022-04-02 14:53:54 -0700487 kCenterBlobSizeScalar *
488 (middle_tape_piece_width -
489 static_cast<S>(blob_stats_[middle_blob_index_].size.width));
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800490 residual[(blob_stats_.size() * 2) + 1] =
Austin Schuha685b5d2022-04-02 14:53:54 -0700491 kCenterBlobSizeScalar *
492 (middle_tape_piece_height -
493 static_cast<S>(blob_stats_[middle_blob_index_].size.height));
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800494
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800495 if (image_.has_value()) {
496 // Draw the current stage of the solving
497 cv::Mat image = image_->clone();
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700498 std::vector<cv::Point2d> tape_points_proj_double;
499 for (auto point : tape_points_proj) {
500 tape_points_proj_double.emplace_back(ScalarPointToDouble(point));
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800501 }
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700502 DrawProjectedHub(tape_points_proj_double, image);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800503 cv::imshow("image", image);
504 cv::waitKey(10);
505 }
506
507 return true;
508}
509
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800510template <typename S>
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700511Eigen::Transform<S, 3, Eigen::Affine>
512TargetEstimator::ComputeHubCameraTransform(S roll, S pitch, S yaw, S distance,
513 S theta, S camera_height) const {
514 using Vector3s = Eigen::Matrix<S, 3, 1>;
515 using Affine3s = Eigen::Transform<S, 3, Eigen::Affine>;
516
517 Eigen::AngleAxis<S> roll_angle(roll, Vector3s::UnitX());
518 Eigen::AngleAxis<S> pitch_angle(pitch, Vector3s::UnitY());
519 Eigen::AngleAxis<S> yaw_angle(yaw, Vector3s::UnitZ());
520 // Construct the rotation and translation of the camera in the hub's frame
521 Eigen::Quaternion<S> R_camera_hub = yaw_angle * pitch_angle * roll_angle;
522 Vector3s T_camera_hub(distance * ceres::cos(theta),
523 distance * ceres::sin(theta), camera_height);
524
525 Affine3s H_camera_hub = Eigen::Translation<S, 3>(T_camera_hub) * R_camera_hub;
526 Affine3s H_hub_camera = H_camera_hub.inverse();
527
528 return H_hub_camera;
529}
530
531template <typename S>
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800532cv::Point_<S> TargetEstimator::ProjectToImage(
533 cv::Point3d tape_point_hub,
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700534 const Eigen::Transform<S, 3, Eigen::Affine> &H_hub_camera) const {
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800535 using Vector3s = Eigen::Matrix<S, 3, 1>;
536
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800537 const Vector3s tape_point_hub_eigen =
538 Vector3s(S(tape_point_hub.x), S(tape_point_hub.y), S(tape_point_hub.z));
539 // Project the 3d tape point onto the image using the transformation and
540 // intrinsics
541 const Vector3s tape_point_proj =
milind-ucafdd5d2022-03-01 19:58:57 -0800542 intrinsics_ * (kHubToCameraAxes * (H_hub_camera * tape_point_hub_eigen));
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800543
544 // Normalize the projected point
545 return {tape_point_proj.x() / tape_point_proj.z(),
546 tape_point_proj.y() / tape_point_proj.z()};
547}
548
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800549namespace {
550template <typename S>
551cv::Point_<S> Distance(cv::Point p, cv::Point_<S> q) {
552 return cv::Point_<S>(S(p.x) - q.x, S(p.y) - q.y);
553}
554
555template <typename S>
556bool Less(cv::Point_<S> distance_1, cv::Point_<S> distance_2) {
557 return (ceres::pow(distance_1.x, 2) + ceres::pow(distance_1.y, 2) <
558 ceres::pow(distance_2.x, 2) + ceres::pow(distance_2.y, 2));
559}
560} // namespace
561
562template <typename S>
Austin Schuha685b5d2022-04-02 14:53:54 -0700563cv::Point_<S> TargetEstimator::DistanceFromTapeIndex(
564 size_t blob_index, size_t tape_index,
565 const std::vector<cv::Point_<S>> &tape_points) const {
566 return Distance(blob_stats_[blob_index].centroid, tape_points[tape_index]);
567}
568
569template <typename S>
570size_t TargetEstimator::ClosestTape(
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800571 size_t blob_index, const std::vector<cv::Point_<S>> &tape_points) const {
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800572 auto distance = cv::Point_<S>(std::numeric_limits<S>::infinity(),
573 std::numeric_limits<S>::infinity());
Milind Upadhyaya31f0272022-04-03 13:55:22 -0700574 std::optional<size_t> final_match = std::nullopt;
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800575 if (blob_index == middle_blob_index_) {
576 // Fix the middle blob so the solver can't go too far off
Austin Schuha685b5d2022-04-02 14:53:54 -0700577 final_match = tape_points.size() / 2;
Milind Upadhyaya31f0272022-04-03 13:55:22 -0700578 distance = DistanceFromTapeIndex(blob_index, *final_match, tape_points);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800579 } else {
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800580 // Give the other blob_stats some freedom in case some are split into pieces
581 for (auto it = tape_points.begin(); it < tape_points.end(); it++) {
Austin Schuha685b5d2022-04-02 14:53:54 -0700582 const size_t tape_index = std::distance(tape_points.begin(), it);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800583 const auto current_distance =
Austin Schuha685b5d2022-04-02 14:53:54 -0700584 DistanceFromTapeIndex(blob_index, tape_index, tape_points);
585 if ((tape_index != (tape_points.size() / 2)) &&
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800586 Less(current_distance, distance)) {
Austin Schuha685b5d2022-04-02 14:53:54 -0700587 final_match = tape_index;
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800588 distance = current_distance;
589 }
590 }
591 }
592
Milind Upadhyaya31f0272022-04-03 13:55:22 -0700593 CHECK(final_match.has_value());
594 VLOG(2) << "Matched index " << blob_index << " to " << *final_match
Austin Schuha685b5d2022-04-02 14:53:54 -0700595 << " distance " << distance.x << " " << distance.y;
Austin Schuha685b5d2022-04-02 14:53:54 -0700596
Milind Upadhyaya31f0272022-04-03 13:55:22 -0700597 return *final_match;
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800598}
599
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700600void TargetEstimator::DrawProjectedHub(
601 const std::vector<cv::Point2d> &tape_points_proj,
602 cv::Mat view_image) const {
603 for (size_t i = 0; i < tape_points_proj.size() - 1; i++) {
604 cv::line(view_image, ScalarPointToDouble(tape_points_proj[i]),
605 ScalarPointToDouble(tape_points_proj[i + 1]),
606 cv::Scalar(255, 255, 255));
607 cv::circle(view_image, ScalarPointToDouble(tape_points_proj[i]), 2,
608 cv::Scalar(255, 20, 147), cv::FILLED);
609 cv::circle(view_image, ScalarPointToDouble(tape_points_proj[i + 1]), 2,
610 cv::Scalar(255, 20, 147), cv::FILLED);
611 }
612}
613
614void TargetEstimator::DrawEstimate(cv::Mat view_image) const {
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700615 if (absl::GetFlag(FLAGS_draw_projected_hub)) {
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700616 // Draw projected hub
617 const auto H_hub_camera = ComputeHubCameraTransform(
618 roll_, pitch_, yaw_, distance_, angle_to_camera_, camera_height_);
619 std::vector<cv::Point2d> tape_points_proj;
620 for (cv::Point3d tape_point_hub : kTapePoints) {
621 tape_points_proj.emplace_back(
622 ProjectToImage(tape_point_hub, H_hub_camera));
623 }
624 DrawProjectedHub(tape_points_proj, view_image);
625 }
626
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800627 constexpr int kTextX = 10;
Milind Upadhyay2da80bb2022-03-12 22:54:35 -0800628 int text_y = 0;
629 constexpr int kTextSpacing = 25;
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800630
631 const auto kTextColor = cv::Scalar(0, 255, 255);
Milind Upadhyay2da80bb2022-03-12 22:54:35 -0800632 constexpr double kFontScale = 0.6;
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800633
Jim Ostrowskib3d5f582022-04-02 20:22:49 -0700634 cv::putText(view_image,
635 absl::StrFormat("Distance: %.3f m (%.3f in)", distance_,
636 distance_ / 0.0254),
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800637 cv::Point(kTextX, text_y += kTextSpacing),
638 cv::FONT_HERSHEY_DUPLEX, kFontScale, kTextColor, 2);
639 cv::putText(view_image,
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700640 absl::StrFormat("Angle to target: %.3f", angle_to_target()),
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800641 cv::Point(kTextX, text_y += kTextSpacing),
642 cv::FONT_HERSHEY_DUPLEX, kFontScale, kTextColor, 2);
643 cv::putText(view_image,
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700644 absl::StrFormat("Angle to camera: %.3f", angle_to_camera_),
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800645 cv::Point(kTextX, text_y += kTextSpacing),
646 cv::FONT_HERSHEY_DUPLEX, kFontScale, kTextColor, 2);
647
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700648 cv::putText(view_image,
649 absl::StrFormat("Roll: %.3f, pitch: %.3f, yaw: %.3f", roll_,
650 pitch_, yaw_),
Milind Upadhyay14279de2022-02-26 16:07:53 -0800651 cv::Point(kTextX, text_y += kTextSpacing),
652 cv::FONT_HERSHEY_DUPLEX, kFontScale, kTextColor, 2);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800653
Milind Upadhyay3336f3a2022-04-01 21:45:57 -0700654 cv::putText(view_image, absl::StrFormat("Confidence: %.3f", confidence_),
655 cv::Point(kTextX, text_y += kTextSpacing),
656 cv::FONT_HERSHEY_DUPLEX, kFontScale, kTextColor, 2);
milind-u92195982022-01-22 20:29:31 -0800657}
658
659} // namespace y2022::vision