blob: c78a1c66eac328b9bb5f930124de181299733131 [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"
13
Milind Upadhyay8f38ad82022-03-03 10:06:18 -080014DEFINE_bool(freeze_roll, false, "If true, don't solve for roll");
Milind Upadhyayf61e1482022-02-11 20:42:55 -080015DEFINE_bool(freeze_pitch, false, "If true, don't solve for pitch");
16DEFINE_bool(freeze_yaw, false, "If true, don't solve for yaw");
17DEFINE_bool(freeze_camera_height, true,
18 "If true, don't solve for camera height");
19DEFINE_bool(freeze_angle_to_camera, true,
20 "If true, don't solve for polar angle to camera");
21
22DEFINE_uint64(max_num_iterations, 200,
23 "Maximum number of iterations for the ceres solver");
24DEFINE_bool(solver_output, false,
25 "If true, log the solver progress and results");
26
milind-u92195982022-01-22 20:29:31 -080027namespace y2022::vision {
28
Milind Upadhyay8f38ad82022-03-03 10:06:18 -080029namespace {
30
31constexpr size_t kNumPiecesOfTape = 16;
32// Width and height of a piece of reflective tape
33constexpr double kTapePieceWidth = 0.13;
34constexpr double kTapePieceHeight = 0.05;
35// Height of the center of the tape (m)
36constexpr double kTapeCenterHeight = 2.58 + (kTapePieceHeight / 2);
37// Horizontal distance from tape to center of hub (m)
38constexpr double kUpperHubRadius = 1.22 / 2;
39
40std::vector<cv::Point3d> ComputeTapePoints() {
Milind Upadhyayf61e1482022-02-11 20:42:55 -080041 std::vector<cv::Point3d> tape_points;
milind-u92195982022-01-22 20:29:31 -080042
Milind Upadhyayf61e1482022-02-11 20:42:55 -080043 constexpr size_t kNumVisiblePiecesOfTape = 5;
44 for (size_t i = 0; i < kNumVisiblePiecesOfTape; i++) {
45 // The center piece of tape is at 0 rad, so the angle indices are offset
46 // by the number of pieces of tape on each side of it
47 const double theta_index =
48 static_cast<double>(i) - ((kNumVisiblePiecesOfTape - 1) / 2);
49 // The polar angle is a multiple of the angle between tape centers
50 double theta = theta_index * ((2.0 * M_PI) / kNumPiecesOfTape);
51 tape_points.emplace_back(kUpperHubRadius * std::cos(theta),
Milind Upadhyay8f38ad82022-03-03 10:06:18 -080052 kUpperHubRadius * std::sin(theta),
53 kTapeCenterHeight);
Milind Upadhyayf61e1482022-02-11 20:42:55 -080054 }
milind-u92195982022-01-22 20:29:31 -080055
Milind Upadhyayf61e1482022-02-11 20:42:55 -080056 return tape_points;
57}
milind-u92195982022-01-22 20:29:31 -080058
Milind Upadhyay8f38ad82022-03-03 10:06:18 -080059std::array<cv::Point3d, 4> ComputeMiddleTapePiecePoints() {
60 std::array<cv::Point3d, 4> tape_piece_points;
61
62 // Angle that each piece of tape occupies on the hub
63 constexpr double kTapePieceAngle =
64 (kTapePieceWidth / (2.0 * M_PI * kUpperHubRadius)) * (2.0 * M_PI);
65
66 constexpr double kThetaTapeLeft = -kTapePieceAngle / 2.0;
67 constexpr double kThetaTapeRight = kTapePieceAngle / 2.0;
68
69 constexpr double kTapeTopHeight =
70 kTapeCenterHeight + (kTapePieceHeight / 2.0);
71 constexpr double kTapeBottomHeight =
72 kTapeCenterHeight - (kTapePieceHeight / 2.0);
73
74 tape_piece_points[0] = {kUpperHubRadius * std::cos(kThetaTapeLeft),
75 kUpperHubRadius * std::sin(kThetaTapeLeft),
76 kTapeTopHeight};
77 tape_piece_points[1] = {kUpperHubRadius * std::cos(kThetaTapeRight),
78 kUpperHubRadius * std::sin(kThetaTapeRight),
79 kTapeTopHeight};
80
81 tape_piece_points[2] = {kUpperHubRadius * std::cos(kThetaTapeRight),
82 kUpperHubRadius * std::sin(kThetaTapeRight),
83 kTapeBottomHeight};
84 tape_piece_points[3] = {kUpperHubRadius * std::cos(kThetaTapeLeft),
85 kUpperHubRadius * std::sin(kThetaTapeLeft),
86 kTapeBottomHeight};
87
88 return tape_piece_points;
89}
90
91} // namespace
92
Milind Upadhyayf61e1482022-02-11 20:42:55 -080093const std::vector<cv::Point3d> TargetEstimator::kTapePoints =
94 ComputeTapePoints();
Milind Upadhyay8f38ad82022-03-03 10:06:18 -080095const std::array<cv::Point3d, 4> TargetEstimator::kMiddleTapePiecePoints =
96 ComputeMiddleTapePiecePoints();
Milind Upadhyayf61e1482022-02-11 20:42:55 -080097
98TargetEstimator::TargetEstimator(cv::Mat intrinsics, cv::Mat extrinsics)
Milind Upadhyay8f38ad82022-03-03 10:06:18 -080099 : blob_stats_(),
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800100 image_(std::nullopt),
101 roll_(0.0),
102 pitch_(0.0),
103 yaw_(M_PI),
104 distance_(3.0),
105 angle_to_camera_(0.0),
106 // TODO(milind): add IMU height
107 camera_height_(extrinsics.at<double>(2, 3)) {
108 cv::cv2eigen(intrinsics, intrinsics_);
109 cv::cv2eigen(extrinsics, extrinsics_);
110}
111
112namespace {
113void SetBoundsOrFreeze(double *param, bool freeze, double min, double max,
114 ceres::Problem *problem) {
115 if (freeze) {
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800116 problem->SetParameterBlockConstant(param);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800117 } else {
118 problem->SetParameterLowerBound(param, 0, min);
119 problem->SetParameterUpperBound(param, 0, max);
120 }
121}
122} // namespace
123
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800124void TargetEstimator::Solve(
125 const std::vector<BlobDetector::BlobStats> &blob_stats,
126 std::optional<cv::Mat> image) {
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800127 auto start = aos::monotonic_clock::now();
128
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800129 blob_stats_ = blob_stats;
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800130 image_ = image;
131
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800132 // Do nothing if no blobs were detected
133 if (blob_stats_.size() == 0) {
134 confidence_ = 0.0;
135 return;
136 }
137
138 CHECK_GE(blob_stats_.size(), 3) << "Expected at least 3 blobs";
139
140 const auto circle =
141 Circle::Fit({blob_stats_[0].centroid, blob_stats_[1].centroid,
142 blob_stats_[2].centroid});
143 CHECK(circle.has_value());
144
145 // Find the middle blob, which is the one with the angle closest to the
146 // average
147 double theta_avg = 0.0;
148 for (const auto &stats : blob_stats_) {
149 theta_avg += circle->AngleOf(stats.centroid);
150 }
151 theta_avg /= blob_stats_.size();
152
153 double min_diff = std::numeric_limits<double>::infinity();
154 for (auto it = blob_stats_.begin(); it < blob_stats_.end(); it++) {
155 const double diff = std::abs(circle->AngleOf(it->centroid) - theta_avg);
156 if (diff < min_diff) {
157 min_diff = diff;
158 middle_blob_index_ = it - blob_stats_.begin();
159 }
160 }
161
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800162 ceres::Problem problem;
163
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800164 // x and y differences between projected centroids and blob centroids, as well
165 // as width and height differences between middle projected piece and the
166 // detected blob
167 const size_t num_residuals = (blob_stats_.size() * 2) + 2;
168
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800169 // Set up the only cost function (also known as residual). This uses
170 // auto-differentiation to obtain the derivative (jacobian).
171 ceres::CostFunction *cost_function =
172 new ceres::AutoDiffCostFunction<TargetEstimator, ceres::DYNAMIC, 1, 1, 1,
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800173 1, 1, 1>(this, num_residuals,
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800174 ceres::DO_NOT_TAKE_OWNERSHIP);
175
176 // TODO(milind): add loss function when we get more noisy data
177 problem.AddResidualBlock(cost_function, nullptr, &roll_, &pitch_, &yaw_,
178 &distance_, &angle_to_camera_, &camera_height_);
179
180 // TODO(milind): seed values at localizer output, and constrain to be close to
181 // that.
182
183 // Constrain the rotation, otherwise there can be multiple solutions.
184 // There shouldn't be too much roll or pitch
185 constexpr double kMaxRoll = 0.1;
186 SetBoundsOrFreeze(&roll_, FLAGS_freeze_roll, -kMaxRoll, kMaxRoll, &problem);
187
188 constexpr double kPitch = -35.0 * M_PI / 180.0;
189 constexpr double kMaxPitchDelta = 0.15;
190 SetBoundsOrFreeze(&pitch_, FLAGS_freeze_pitch, kPitch - kMaxPitchDelta,
191 kPitch + kMaxPitchDelta, &problem);
192 // Constrain the yaw to where the target would be visible
193 constexpr double kMaxYawDelta = M_PI / 4.0;
194 SetBoundsOrFreeze(&yaw_, FLAGS_freeze_yaw, M_PI - kMaxYawDelta,
195 M_PI + kMaxYawDelta, &problem);
196
197 constexpr double kMaxHeightDelta = 0.1;
198 SetBoundsOrFreeze(&camera_height_, FLAGS_freeze_camera_height,
199 camera_height_ - kMaxHeightDelta,
200 camera_height_ + kMaxHeightDelta, &problem);
201
202 // Distances shouldn't be too close to the target or too far
203 constexpr double kMinDistance = 1.0;
204 constexpr double kMaxDistance = 10.0;
205 SetBoundsOrFreeze(&distance_, false, kMinDistance, kMaxDistance, &problem);
206
207 // Keep the angle between +/- half of the angle between piece of tape
208 constexpr double kMaxAngle = ((2.0 * M_PI) / kNumPiecesOfTape) / 2.0;
209 SetBoundsOrFreeze(&angle_to_camera_, FLAGS_freeze_angle_to_camera, -kMaxAngle,
210 kMaxAngle, &problem);
211
212 ceres::Solver::Options options;
213 options.minimizer_progress_to_stdout = FLAGS_solver_output;
214 options.gradient_tolerance = 1e-12;
215 options.function_tolerance = 1e-16;
216 options.parameter_tolerance = 1e-12;
217 options.max_num_iterations = FLAGS_max_num_iterations;
218 ceres::Solver::Summary summary;
219 ceres::Solve(options, &problem, &summary);
220
221 auto end = aos::monotonic_clock::now();
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800222 VLOG(1) << "Target estimation elapsed time: "
223 << std::chrono::duration<double, std::milli>(end - start).count()
224 << " ms";
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800225
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800226 // For computing the confidence, find the standard deviation in pixels
227 std::vector<double> residual(num_residuals);
228 (*this)(&roll_, &pitch_, &yaw_, &distance_, &angle_to_camera_,
229 &camera_height_, residual.data());
230 double std_dev = 0.0;
231 for (auto it = residual.begin(); it < residual.end() - 2; it++) {
232 std_dev += std::pow(*it, 2);
Milind Upadhyay14279de2022-02-26 16:07:53 -0800233 }
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800234 std_dev /= num_residuals - 2;
235 std_dev = std::sqrt(std_dev);
236
237 // Use a sigmoid to convert the deviation into a confidence for the
238 // localizer. Fit a sigmoid to the points of (0, 1) and two other
239 // reasonable deviation-confidence combinations using
240 // https://www.desmos.com/calculator/try0pgx1qw
241 constexpr double kSigmoidCapacity = 1.045;
242 // Stretch the sigmoid out correctly.
243 // Currently, good estimates have deviations of around 2 pixels.
244 constexpr double kSigmoidScalar = 0.04452;
245 constexpr double kSigmoidGrowthRate = -0.4021;
246 confidence_ =
247 kSigmoidCapacity /
248 (1.0 + kSigmoidScalar * std::exp(-kSigmoidGrowthRate * std_dev));
Milind Upadhyay14279de2022-02-26 16:07:53 -0800249
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800250 if (FLAGS_solver_output) {
251 LOG(INFO) << summary.FullReport();
252
253 LOG(INFO) << "roll: " << roll_;
254 LOG(INFO) << "pitch: " << pitch_;
255 LOG(INFO) << "yaw: " << yaw_;
256 LOG(INFO) << "angle to target (based on yaw): " << angle_to_target();
257 LOG(INFO) << "angle to camera (polar): " << angle_to_camera_;
258 LOG(INFO) << "distance (polar): " << distance_;
259 LOG(INFO) << "camera height: " << camera_height_;
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800260 LOG(INFO) << "standard deviation (px): " << std_dev;
Milind Upadhyay14279de2022-02-26 16:07:53 -0800261 LOG(INFO) << "confidence: " << confidence_;
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800262 }
263}
264
265namespace {
266// Hacks to extract a double from a scalar, which is either a ceres jet or a
267// double. Only used for debugging and displaying.
268template <typename S>
269double ScalarToDouble(S s) {
270 const double *ptr = reinterpret_cast<double *>(&s);
271 return *ptr;
272}
273
274template <typename S>
275cv::Point2d ScalarPointToDouble(cv::Point_<S> p) {
276 return cv::Point2d(ScalarToDouble(p.x), ScalarToDouble(p.y));
277}
278} // namespace
279
280template <typename S>
281bool TargetEstimator::operator()(const S *const roll, const S *const pitch,
282 const S *const yaw, const S *const distance,
283 const S *const theta,
284 const S *const camera_height,
285 S *residual) const {
286 using Vector3s = Eigen::Matrix<S, 3, 1>;
287 using Affine3s = Eigen::Transform<S, 3, Eigen::Affine>;
288
289 Eigen::AngleAxis<S> roll_angle(*roll, Vector3s::UnitX());
290 Eigen::AngleAxis<S> pitch_angle(*pitch, Vector3s::UnitY());
291 Eigen::AngleAxis<S> yaw_angle(*yaw, Vector3s::UnitZ());
292 // Construct the rotation and translation of the camera in the hub's frame
293 Eigen::Quaternion<S> R_camera_hub = yaw_angle * pitch_angle * roll_angle;
294 Vector3s T_camera_hub(*distance * ceres::cos(*theta),
295 *distance * ceres::sin(*theta), *camera_height);
296
297 Affine3s H_camera_hub = Eigen::Translation<S, 3>(T_camera_hub) * R_camera_hub;
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800298 Affine3s H_hub_camera = H_camera_hub.inverse();
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800299
300 std::vector<cv::Point_<S>> tape_points_proj;
301 for (cv::Point3d tape_point_hub : kTapePoints) {
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800302 tape_points_proj.emplace_back(ProjectToImage(tape_point_hub, H_hub_camera));
303 VLOG(2) << "Projected tape point: "
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800304 << ScalarPointToDouble(
305 tape_points_proj[tape_points_proj.size() - 1]);
306 }
307
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800308 // Find the rectangle bounding the projected piece of tape
309 std::array<cv::Point_<S>, 4> middle_tape_piece_points_proj;
310 for (auto tape_piece_it = kMiddleTapePiecePoints.begin();
311 tape_piece_it < kMiddleTapePiecePoints.end(); tape_piece_it++) {
312 middle_tape_piece_points_proj[tape_piece_it -
313 kMiddleTapePiecePoints.begin()] =
314 ProjectToImage(*tape_piece_it, H_hub_camera);
315 }
316
317 for (size_t i = 0; i < blob_stats_.size(); i++) {
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800318 const auto distance = DistanceFromTape(i, tape_points_proj);
319 // Set the residual to the (x, y) distance of the centroid from the
320 // nearest projected piece of tape
321 residual[i * 2] = distance.x;
322 residual[(i * 2) + 1] = distance.y;
323 }
324
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800325 // Penalize based on the difference between the size of the projected piece of
326 // tape and that of the detected blobs. Use the squared size to avoid taking a
327 // norm, which ceres can't handle well
328 const S middle_tape_piece_width_squared =
329 ceres::pow(middle_tape_piece_points_proj[2].x -
330 middle_tape_piece_points_proj[3].x,
331 2) +
332 ceres::pow(middle_tape_piece_points_proj[2].y -
333 middle_tape_piece_points_proj[3].y,
334 2);
335 const S middle_tape_piece_height_squared =
336 ceres::pow(middle_tape_piece_points_proj[1].x -
337 middle_tape_piece_points_proj[2].x,
338 2) +
339 ceres::pow(middle_tape_piece_points_proj[1].y -
340 middle_tape_piece_points_proj[2].y,
341 2);
342
343 residual[blob_stats_.size() * 2] =
344 middle_tape_piece_width_squared -
345 std::pow(blob_stats_[middle_blob_index_].size.width, 2);
346 residual[(blob_stats_.size() * 2) + 1] =
347 middle_tape_piece_height_squared -
348 std::pow(blob_stats_[middle_blob_index_].size.height, 2);
349
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800350 if (image_.has_value()) {
351 // Draw the current stage of the solving
352 cv::Mat image = image_->clone();
353 for (size_t i = 0; i < tape_points_proj.size() - 1; i++) {
354 cv::line(image, ScalarPointToDouble(tape_points_proj[i]),
355 ScalarPointToDouble(tape_points_proj[i + 1]),
356 cv::Scalar(255, 255, 255));
357 cv::circle(image, ScalarPointToDouble(tape_points_proj[i]), 2,
358 cv::Scalar(255, 20, 147), cv::FILLED);
359 cv::circle(image, ScalarPointToDouble(tape_points_proj[i + 1]), 2,
360 cv::Scalar(255, 20, 147), cv::FILLED);
361 }
362 cv::imshow("image", image);
363 cv::waitKey(10);
364 }
365
366 return true;
367}
368
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800369template <typename S>
370cv::Point_<S> TargetEstimator::ProjectToImage(
371 cv::Point3d tape_point_hub,
372 Eigen::Transform<S, 3, Eigen::Affine> &H_hub_camera) const {
373 using Vector3s = Eigen::Matrix<S, 3, 1>;
374
375 // With X, Y, Z being world axes and x, y, z being camera axes,
376 // x = Y, y = Z, z = -X
377 static const Eigen::Matrix3d kCameraAxisConversion =
378 (Eigen::Matrix3d() << 0.0, 1.0, 0.0, 0.0, 0.0, 1.0, -1.0, 0.0, 0.0)
379 .finished();
380 const Vector3s tape_point_hub_eigen =
381 Vector3s(S(tape_point_hub.x), S(tape_point_hub.y), S(tape_point_hub.z));
382 // Project the 3d tape point onto the image using the transformation and
383 // intrinsics
384 const Vector3s tape_point_proj =
385 intrinsics_ *
386 (kCameraAxisConversion * (H_hub_camera * tape_point_hub_eigen));
387
388 // Normalize the projected point
389 return {tape_point_proj.x() / tape_point_proj.z(),
390 tape_point_proj.y() / tape_point_proj.z()};
391}
392
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800393namespace {
394template <typename S>
395cv::Point_<S> Distance(cv::Point p, cv::Point_<S> q) {
396 return cv::Point_<S>(S(p.x) - q.x, S(p.y) - q.y);
397}
398
399template <typename S>
400bool Less(cv::Point_<S> distance_1, cv::Point_<S> distance_2) {
401 return (ceres::pow(distance_1.x, 2) + ceres::pow(distance_1.y, 2) <
402 ceres::pow(distance_2.x, 2) + ceres::pow(distance_2.y, 2));
403}
404} // namespace
405
406template <typename S>
407cv::Point_<S> TargetEstimator::DistanceFromTape(
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800408 size_t blob_index, const std::vector<cv::Point_<S>> &tape_points) const {
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800409 auto distance = cv::Point_<S>(std::numeric_limits<S>::infinity(),
410 std::numeric_limits<S>::infinity());
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800411 if (blob_index == middle_blob_index_) {
412 // Fix the middle blob so the solver can't go too far off
413 distance = Distance(blob_stats_[middle_blob_index_].centroid,
414 tape_points[tape_points.size() / 2]);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800415 } else {
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800416 // Give the other blob_stats some freedom in case some are split into pieces
417 for (auto it = tape_points.begin(); it < tape_points.end(); it++) {
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800418 const auto current_distance =
Milind Upadhyay8f38ad82022-03-03 10:06:18 -0800419 Distance(blob_stats_[blob_index].centroid, *it);
420 if ((it != tape_points.begin() + (tape_points.size() / 2)) &&
421 Less(current_distance, distance)) {
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800422 distance = current_distance;
423 }
424 }
425 }
426
427 return distance;
428}
429
430namespace {
431void DrawEstimateValues(double distance, double angle_to_target,
432 double angle_to_camera, double roll, double pitch,
Milind Upadhyay14279de2022-02-26 16:07:53 -0800433 double yaw, double confidence, cv::Mat view_image) {
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800434 constexpr int kTextX = 10;
Milind Upadhyay14279de2022-02-26 16:07:53 -0800435 int text_y = 250;
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800436 constexpr int kTextSpacing = 35;
437
438 const auto kTextColor = cv::Scalar(0, 255, 255);
439 constexpr double kFontScale = 1.0;
440
441 cv::putText(view_image, absl::StrFormat("Distance: %.3f", distance),
442 cv::Point(kTextX, text_y += kTextSpacing),
443 cv::FONT_HERSHEY_DUPLEX, kFontScale, kTextColor, 2);
444 cv::putText(view_image,
445 absl::StrFormat("Angle to target: %.3f", angle_to_target),
446 cv::Point(kTextX, text_y += kTextSpacing),
447 cv::FONT_HERSHEY_DUPLEX, kFontScale, kTextColor, 2);
448 cv::putText(view_image,
449 absl::StrFormat("Angle to camera: %.3f", angle_to_camera),
450 cv::Point(kTextX, text_y += kTextSpacing),
451 cv::FONT_HERSHEY_DUPLEX, kFontScale, kTextColor, 2);
452
453 cv::putText(
454 view_image,
455 absl::StrFormat("Roll: %.3f, pitch: %.3f, yaw: %.3f", roll, pitch, yaw),
456 cv::Point(kTextX, text_y += kTextSpacing), cv::FONT_HERSHEY_DUPLEX,
457 kFontScale, kTextColor, 2);
Milind Upadhyay14279de2022-02-26 16:07:53 -0800458
459 cv::putText(view_image, absl::StrFormat("Confidence: %.3f", confidence),
460 cv::Point(kTextX, text_y += kTextSpacing),
461 cv::FONT_HERSHEY_DUPLEX, kFontScale, kTextColor, 2);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800462}
463} // namespace
464
465void TargetEstimator::DrawEstimate(const TargetEstimate &target_estimate,
466 cv::Mat view_image) {
467 DrawEstimateValues(target_estimate.distance(),
468 target_estimate.angle_to_target(),
469 target_estimate.angle_to_camera(),
470 target_estimate.rotation_camera_hub()->roll(),
471 target_estimate.rotation_camera_hub()->pitch(),
Milind Upadhyay14279de2022-02-26 16:07:53 -0800472 target_estimate.rotation_camera_hub()->yaw(),
473 target_estimate.confidence(), view_image);
Milind Upadhyayf61e1482022-02-11 20:42:55 -0800474}
475
476void TargetEstimator::DrawEstimate(cv::Mat view_image) const {
477 DrawEstimateValues(distance_, angle_to_target(), angle_to_camera_, roll_,
Milind Upadhyay14279de2022-02-26 16:07:53 -0800478 pitch_, yaw_, confidence_, view_image);
milind-u92195982022-01-22 20:29:31 -0800479}
480
481} // namespace y2022::vision