blob: 622c871c62eb9cad922755465cff3c6e5fe9add3 [file] [log] [blame]
Austin Schuhdcb6b362022-02-25 18:06:21 -08001#include "frc971/vision/charuco_lib.h"
Austin Schuh25837f22021-06-27 15:49:14 -07002
3#include <chrono>
4#include <functional>
Austin Schuh25837f22021-06-27 15:49:14 -07005#include <opencv2/core/eigen.hpp>
6#include <opencv2/highgui/highgui.hpp>
7#include <opencv2/imgproc.hpp>
Austin Schuhdcb6b362022-02-25 18:06:21 -08008#include <string_view>
9
Austin Schuh25837f22021-06-27 15:49:14 -070010#include "aos/events/event_loop.h"
11#include "aos/flatbuffers.h"
12#include "aos/network/team_number.h"
13#include "frc971/control_loops/quaternion_utils.h"
Jim Ostrowski977850f2022-01-22 21:04:22 -080014#include "frc971/vision/vision_generated.h"
Austin Schuh25837f22021-06-27 15:49:14 -070015#include "glog/logging.h"
16#include "y2020/vision/sift/sift_generated.h"
17#include "y2020/vision/sift/sift_training_generated.h"
18#include "y2020/vision/tools/python_code/sift_training_data.h"
Austin Schuh25837f22021-06-27 15:49:14 -070019
Austin Schuh25837f22021-06-27 15:49:14 -070020DEFINE_string(board_template_path, "",
21 "If specified, write an image to the specified path for the "
22 "charuco board pattern.");
Jim Ostrowskib3cab972022-12-03 15:47:00 -080023DEFINE_bool(coarse_pattern, true, "If true, use coarse arucos; else, use fine");
24DEFINE_bool(large_board, true, "If true, use the large calibration board.");
25DEFINE_uint32(
26 min_charucos, 10,
27 "The mininum number of aruco targets in charuco board required to match.");
Jim Ostrowskib3cab972022-12-03 15:47:00 -080028DEFINE_bool(visualize, false, "Whether to visualize the resulting data.");
Austin Schuh25837f22021-06-27 15:49:14 -070029
Austin Schuhc3419862023-01-08 13:54:36 -080030DEFINE_uint32(disable_delay, 100, "Time after an issue to disable tracing at.");
31
32DECLARE_bool(enable_ftrace);
33
Austin Schuh25837f22021-06-27 15:49:14 -070034namespace frc971 {
35namespace vision {
36namespace chrono = std::chrono;
Austin Schuhea7b0142021-10-08 22:04:53 -070037using aos::monotonic_clock;
Austin Schuh25837f22021-06-27 15:49:14 -070038
39CameraCalibration::CameraCalibration(
40 const absl::Span<const uint8_t> training_data_bfbs, std::string_view pi) {
41 const aos::FlatbufferSpan<sift::TrainingData> training_data(
42 training_data_bfbs);
43 CHECK(training_data.Verify());
44 camera_calibration_ = FindCameraCalibration(&training_data.message(), pi);
45}
46
47cv::Mat CameraCalibration::CameraIntrinsics() const {
48 const cv::Mat result(3, 3, CV_32F,
49 const_cast<void *>(static_cast<const void *>(
50 camera_calibration_->intrinsics()->data())));
51 CHECK_EQ(result.total(), camera_calibration_->intrinsics()->size());
52 return result;
53}
54
55Eigen::Matrix3d CameraCalibration::CameraIntrinsicsEigen() const {
56 cv::Mat camera_intrinsics = CameraIntrinsics();
57 Eigen::Matrix3d result;
58 cv::cv2eigen(camera_intrinsics, result);
59 return result;
60}
61
62cv::Mat CameraCalibration::CameraDistCoeffs() const {
63 const cv::Mat result(5, 1, CV_32F,
64 const_cast<void *>(static_cast<const void *>(
65 camera_calibration_->dist_coeffs()->data())));
66 CHECK_EQ(result.total(), camera_calibration_->dist_coeffs()->size());
67 return result;
68}
69
70const sift::CameraCalibration *CameraCalibration::FindCameraCalibration(
71 const sift::TrainingData *const training_data, std::string_view pi) const {
72 std::optional<uint16_t> pi_number = aos::network::ParsePiNumber(pi);
73 std::optional<uint16_t> team_number =
74 aos::network::team_number_internal::ParsePiTeamNumber(pi);
75 CHECK(pi_number);
76 CHECK(team_number);
77 const std::string node_name = absl::StrFormat("pi%d", pi_number.value());
78 LOG(INFO) << "Looking for node name " << node_name << " team number "
79 << team_number.value();
80 for (const sift::CameraCalibration *candidate :
81 *training_data->camera_calibrations()) {
82 if (candidate->node_name()->string_view() != node_name) {
83 continue;
84 }
85 if (candidate->team_number() != team_number.value()) {
86 continue;
87 }
88 return candidate;
89 }
90 LOG(FATAL) << ": Failed to find camera calibration for " << node_name
91 << " on " << team_number.value();
92}
93
Austin Schuhea7b0142021-10-08 22:04:53 -070094ImageCallback::ImageCallback(
95 aos::EventLoop *event_loop, std::string_view channel,
milind-u0cb53112023-02-03 20:32:55 -080096 std::function<void(cv::Mat, monotonic_clock::time_point)> &&handle_image_fn,
97 monotonic_clock::duration max_age)
Austin Schuhea7b0142021-10-08 22:04:53 -070098 : event_loop_(event_loop),
99 server_fetcher_(
100 event_loop_->MakeFetcher<aos::message_bridge::ServerStatistics>(
101 "/aos")),
102 source_node_(aos::configuration::GetNode(
103 event_loop_->configuration(),
104 event_loop_->GetChannel<CameraImage>(channel)
105 ->source_node()
106 ->string_view())),
Austin Schuhc3419862023-01-08 13:54:36 -0800107 handle_image_(std::move(handle_image_fn)),
milind-u0cb53112023-02-03 20:32:55 -0800108 timer_fn_(event_loop->AddTimer([this]() { DisableTracing(); })),
109 max_age_(max_age) {
Austin Schuh25837f22021-06-27 15:49:14 -0700110 event_loop_->MakeWatcher(channel, [this](const CameraImage &image) {
Austin Schuhea7b0142021-10-08 22:04:53 -0700111 const monotonic_clock::time_point eof_source_node =
112 monotonic_clock::time_point(
113 chrono::nanoseconds(image.monotonic_timestamp_ns()));
Austin Schuhea7b0142021-10-08 22:04:53 -0700114 chrono::nanoseconds offset{0};
115 if (source_node_ != event_loop_->node()) {
Austin Schuhee8bc1e2021-11-20 16:23:41 -0800116 server_fetcher_.Fetch();
117 if (!server_fetcher_.get()) {
118 return;
119 }
120
Austin Schuhea7b0142021-10-08 22:04:53 -0700121 // If we are viewing this image from another node, convert to our
122 // monotonic clock.
123 const aos::message_bridge::ServerConnection *server_connection = nullptr;
124
125 for (const aos::message_bridge::ServerConnection *connection :
126 *server_fetcher_->connections()) {
127 CHECK(connection->has_node());
128 if (connection->node()->name()->string_view() ==
129 source_node_->name()->string_view()) {
130 server_connection = connection;
131 break;
132 }
133 }
134
135 CHECK(server_connection != nullptr) << ": Failed to find client";
136 if (!server_connection->has_monotonic_offset()) {
137 VLOG(1) << "No offset yet.";
138 return;
139 }
140 offset = chrono::nanoseconds(server_connection->monotonic_offset());
141 }
142
143 const monotonic_clock::time_point eof = eof_source_node - offset;
144
Jim Ostrowski977850f2022-01-22 21:04:22 -0800145 const monotonic_clock::duration age = event_loop_->monotonic_now() - eof;
Austin Schuh25837f22021-06-27 15:49:14 -0700146 const double age_double =
147 std::chrono::duration_cast<std::chrono::duration<double>>(age).count();
milind-u0cb53112023-02-03 20:32:55 -0800148 if (age > max_age_) {
Austin Schuhc3419862023-01-08 13:54:36 -0800149 if (FLAGS_enable_ftrace) {
150 ftrace_.FormatMessage("Too late receiving image, age: %f\n",
151 age_double);
152 if (FLAGS_disable_delay > 0) {
153 if (!disabling_) {
154 timer_fn_->Setup(event_loop_->monotonic_now() +
155 chrono::milliseconds(FLAGS_disable_delay));
156 disabling_ = true;
157 }
158 } else {
159 DisableTracing();
160 }
161 }
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800162 VLOG(2) << "Age: " << age_double << ", getting behind, skipping";
Austin Schuh25837f22021-06-27 15:49:14 -0700163 return;
164 }
165 // Create color image:
166 cv::Mat image_color_mat(cv::Size(image.cols(), image.rows()), CV_8UC2,
167 (void *)image.data()->data());
168 const cv::Size image_size(image.cols(), image.rows());
Austin Schuhac402e92023-01-08 13:56:20 -0800169 switch (format_) {
170 case Format::GRAYSCALE: {
171 ftrace_.FormatMessage("Starting yuyv->greyscale\n");
172 cv::Mat gray_image(image_size, CV_8UC3);
173 cv::cvtColor(image_color_mat, gray_image, cv::COLOR_YUV2GRAY_YUYV);
174 handle_image_(gray_image, eof);
175 } break;
176 case Format::BGR: {
177 cv::Mat rgb_image(image_size, CV_8UC3);
178 cv::cvtColor(image_color_mat, rgb_image, cv::COLOR_YUV2BGR_YUYV);
179 handle_image_(rgb_image, eof);
180 } break;
181 case Format::YUYV2: {
182 handle_image_(image_color_mat, eof);
183 };
184 }
Austin Schuh25837f22021-06-27 15:49:14 -0700185 });
186}
187
Austin Schuhc3419862023-01-08 13:54:36 -0800188void ImageCallback::DisableTracing() {
189 disabling_ = false;
190 ftrace_.TurnOffOrDie();
191}
192
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800193void CharucoExtractor::SetupTargetData() {
194 // TODO(Jim): Put correct values here
195 marker_length_ = 0.15;
196 square_length_ = 0.1651;
197
198 // Only charuco board has a board associated with it
199 board_ = static_cast<cv::Ptr<cv::aruco::CharucoBoard>>(NULL);
200
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800201 if (target_type_ == TargetType::kCharuco ||
202 target_type_ == TargetType::kAruco) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800203 dictionary_ = cv::aruco::getPredefinedDictionary(
204 FLAGS_large_board ? cv::aruco::DICT_5X5_250 : cv::aruco::DICT_6X6_250);
205
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800206 if (target_type_ == TargetType::kCharuco) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800207 LOG(INFO) << "Using " << (FLAGS_large_board ? " large " : " small ")
208 << " charuco board with "
209 << (FLAGS_coarse_pattern ? "coarse" : "fine") << " pattern";
210 board_ =
211 (FLAGS_large_board
212 ? (FLAGS_coarse_pattern ? cv::aruco::CharucoBoard::create(
213 12, 9, 0.06, 0.04666, dictionary_)
214 : cv::aruco::CharucoBoard::create(
215 25, 18, 0.03, 0.0233, dictionary_))
216 : (FLAGS_coarse_pattern ? cv::aruco::CharucoBoard::create(
217 7, 5, 0.04, 0.025, dictionary_)
218 // TODO(jim): Need to figure out what
219 // size is for small board, fine pattern
220 : cv::aruco::CharucoBoard::create(
221 7, 5, 0.03, 0.0233, dictionary_)));
222 if (!FLAGS_board_template_path.empty()) {
223 cv::Mat board_image;
224 board_->draw(cv::Size(600, 500), board_image, 10, 1);
225 cv::imwrite(FLAGS_board_template_path, board_image);
226 }
227 }
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800228 } else if (target_type_ == TargetType::kCharucoDiamond) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800229 // TODO<Jim>: Measure this
230 marker_length_ = 0.15;
231 square_length_ = 0.1651;
232 dictionary_ = cv::aruco::getPredefinedDictionary(cv::aruco::DICT_4X4_250);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800233 } else {
234 // Bail out if it's not a supported target
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800235 LOG(FATAL) << "Target type undefined: "
236 << static_cast<uint8_t>(target_type_);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800237 }
238}
239
240void CharucoExtractor::DrawTargetPoses(cv::Mat rgb_image,
241 std::vector<cv::Vec3d> rvecs,
242 std::vector<cv::Vec3d> tvecs) {
243 const Eigen::Matrix<double, 3, 4> camera_projection =
244 Eigen::Matrix<double, 3, 4>::Identity();
245
246 int x_coord = 10;
247 int y_coord = 0;
248 // draw axis for each marker
249 for (uint i = 0; i < rvecs.size(); i++) {
250 Eigen::Vector3d rvec_eigen, tvec_eigen;
251 cv::cv2eigen(rvecs[i], rvec_eigen);
252 cv::cv2eigen(tvecs[i], tvec_eigen);
253
254 Eigen::Quaternion<double> rotation(
255 frc971::controls::ToQuaternionFromRotationVector(rvec_eigen));
256 Eigen::Translation3d translation(tvec_eigen);
257
258 const Eigen::Affine3d board_to_camera = translation * rotation;
259
260 Eigen::Vector3d result = eigen_camera_matrix_ * camera_projection *
261 board_to_camera * Eigen::Vector3d::Zero();
262
263 // Found that drawAxis hangs if you try to draw with z values too
264 // small (trying to draw axes at inifinity)
265 // TODO<Jim>: Explore what real thresholds for this should be;
266 // likely Don't need to get rid of negative values
267 if (result.z() < 0.01) {
268 LOG(INFO) << "Skipping, due to z value too small: " << result.z();
269 } else {
270 result /= result.z();
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800271 if (target_type_ == TargetType::kCharuco) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800272 cv::aruco::drawAxis(rgb_image, camera_matrix_, dist_coeffs_, rvecs[i],
273 tvecs[i], 0.1);
274 } else {
275 cv::drawFrameAxes(rgb_image, camera_matrix_, dist_coeffs_, rvecs[i],
276 tvecs[i], 0.1);
277 }
278 }
279 std::stringstream ss;
280 ss << "tvec[" << i << "] = " << tvecs[i];
281 y_coord += 25;
282 cv::putText(rgb_image, ss.str(), cv::Point(x_coord, y_coord),
283 cv::FONT_HERSHEY_PLAIN, 1.0, cv::Scalar(255, 255, 255));
284 ss.str("");
285 ss << "rvec[" << i << "] = " << rvecs[i];
286 y_coord += 25;
287 cv::putText(rgb_image, ss.str(), cv::Point(x_coord, y_coord),
288 cv::FONT_HERSHEY_PLAIN, 1.0, cv::Scalar(255, 255, 255));
289 }
290}
291
292void CharucoExtractor::PackPoseResults(
293 std::vector<cv::Vec3d> &rvecs, std::vector<cv::Vec3d> &tvecs,
294 std::vector<Eigen::Vector3d> *rvecs_eigen,
295 std::vector<Eigen::Vector3d> *tvecs_eigen) {
296 for (cv::Vec3d rvec : rvecs) {
297 Eigen::Vector3d rvec_eigen = Eigen::Vector3d::Zero();
298 cv::cv2eigen(rvec, rvec_eigen);
299 rvecs_eigen->emplace_back(rvec_eigen);
300 }
301
302 for (cv::Vec3d tvec : tvecs) {
303 Eigen::Vector3d tvec_eigen = Eigen::Vector3d::Zero();
304 cv::cv2eigen(tvec, tvec_eigen);
305 tvecs_eigen->emplace_back(tvec_eigen);
306 }
307}
308
Austin Schuh25837f22021-06-27 15:49:14 -0700309CharucoExtractor::CharucoExtractor(
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800310 aos::EventLoop *event_loop, std::string_view pi, TargetType target_type,
311 std::string_view image_channel,
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800312 std::function<void(cv::Mat, monotonic_clock::time_point,
313 std::vector<cv::Vec4i>,
314 std::vector<std::vector<cv::Point2f>>, bool,
315 std::vector<Eigen::Vector3d>,
316 std::vector<Eigen::Vector3d>)> &&handle_charuco_fn)
Austin Schuhea7b0142021-10-08 22:04:53 -0700317 : event_loop_(event_loop),
318 calibration_(SiftTrainingData(), pi),
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800319 target_type_(target_type),
320 image_channel_(image_channel),
Austin Schuh25837f22021-06-27 15:49:14 -0700321 camera_matrix_(calibration_.CameraIntrinsics()),
322 eigen_camera_matrix_(calibration_.CameraIntrinsicsEigen()),
323 dist_coeffs_(calibration_.CameraDistCoeffs()),
324 pi_number_(aos::network::ParsePiNumber(pi)),
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800325 handle_charuco_(std::move(handle_charuco_fn)) {
326 SetupTargetData();
Austin Schuh25837f22021-06-27 15:49:14 -0700327
328 LOG(INFO) << "Camera matrix " << camera_matrix_;
329 LOG(INFO) << "Distortion Coefficients " << dist_coeffs_;
330
331 CHECK(pi_number_) << ": Invalid pi number " << pi
332 << ", failed to parse pi number";
333
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800334 LOG(INFO) << "Connecting to channel " << image_channel_;
Austin Schuh25837f22021-06-27 15:49:14 -0700335}
336
Austin Schuhea7b0142021-10-08 22:04:53 -0700337void CharucoExtractor::HandleImage(cv::Mat rgb_image,
338 const monotonic_clock::time_point eof) {
339 const double age_double =
340 std::chrono::duration_cast<std::chrono::duration<double>>(
341 event_loop_->monotonic_now() - eof)
342 .count();
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800343
344 // Set up the variables we'll use in the callback function
345 bool valid = false;
346 // Return a list of poses; for Charuco Board there will be just one
347 std::vector<Eigen::Vector3d> rvecs_eigen;
348 std::vector<Eigen::Vector3d> tvecs_eigen;
349
350 // ids and corners for initial aruco marker detections
Austin Schuh25837f22021-06-27 15:49:14 -0700351 std::vector<int> marker_ids;
352 std::vector<std::vector<cv::Point2f>> marker_corners;
353
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800354 // ids and corners for final, refined board / marker detections
355 // Using Vec4i type since it supports Charuco Diamonds
356 // And overloading it using 1st int in Vec4i for others target types
357 std::vector<cv::Vec4i> result_ids;
358 std::vector<std::vector<cv::Point2f>> result_corners;
Austin Schuh25837f22021-06-27 15:49:14 -0700359
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800360 // Do initial marker detection; this is the same for all target types
361 cv::aruco::detectMarkers(rgb_image, dictionary_, marker_corners, marker_ids);
362 cv::aruco::drawDetectedMarkers(rgb_image, marker_corners, marker_ids);
Austin Schuhea7b0142021-10-08 22:04:53 -0700363
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800364 VLOG(2) << "Handle Image, with target type = "
365 << static_cast<uint8_t>(target_type_) << " and " << marker_ids.size()
366 << " markers detected initially";
Austin Schuh25837f22021-06-27 15:49:14 -0700367
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800368 if (marker_ids.size() == 0) {
369 VLOG(2) << "Didn't find any markers";
370 } else {
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800371 if (target_type_ == TargetType::kCharuco) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800372 std::vector<int> charuco_ids;
373 std::vector<cv::Point2f> charuco_corners;
Austin Schuh25837f22021-06-27 15:49:14 -0700374
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800375 // If enough aruco markers detected for the Charuco board
376 if (marker_ids.size() >= FLAGS_min_charucos) {
377 // Run everything twice, once with the calibration, and once
378 // without. This lets us both collect data to calibrate the
379 // intrinsics of the camera (to determine the intrinsics from
380 // multiple samples), and also to use data from a previous/stored
381 // calibration to determine a more accurate pose in real time (used
382 // for extrinsics calibration)
383 cv::aruco::interpolateCornersCharuco(marker_corners, marker_ids,
384 rgb_image, board_, charuco_corners,
385 charuco_ids);
Austin Schuh25837f22021-06-27 15:49:14 -0700386
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800387 std::vector<cv::Point2f> charuco_corners_with_calibration;
388 std::vector<int> charuco_ids_with_calibration;
Austin Schuh25837f22021-06-27 15:49:14 -0700389
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800390 // This call uses a previous intrinsic calibration to get more
391 // accurate marker locations, for a better pose estimate
392 cv::aruco::interpolateCornersCharuco(
393 marker_corners, marker_ids, rgb_image, board_,
394 charuco_corners_with_calibration, charuco_ids_with_calibration,
395 camera_matrix_, dist_coeffs_);
Austin Schuh25837f22021-06-27 15:49:14 -0700396
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800397 if (charuco_ids.size() >= FLAGS_min_charucos) {
398 cv::aruco::drawDetectedCornersCharuco(
399 rgb_image, charuco_corners, charuco_ids, cv::Scalar(255, 0, 0));
Austin Schuh25837f22021-06-27 15:49:14 -0700400
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800401 cv::Vec3d rvec, tvec;
402 valid = cv::aruco::estimatePoseCharucoBoard(
403 charuco_corners_with_calibration, charuco_ids_with_calibration,
404 board_, camera_matrix_, dist_coeffs_, rvec, tvec);
Austin Schuh25837f22021-06-27 15:49:14 -0700405
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800406 // if charuco pose is valid, return pose, with ids and corners
407 if (valid) {
408 std::vector<cv::Vec3d> rvecs, tvecs;
409 rvecs.emplace_back(rvec);
410 tvecs.emplace_back(tvec);
411 DrawTargetPoses(rgb_image, rvecs, tvecs);
Austin Schuh25837f22021-06-27 15:49:14 -0700412
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800413 PackPoseResults(rvecs, tvecs, &rvecs_eigen, &tvecs_eigen);
414 // Store the corners without calibration, since we use them to
415 // do calibration
416 result_corners.emplace_back(charuco_corners);
417 for (auto id : charuco_ids) {
418 result_ids.emplace_back(cv::Vec4i{id, 0, 0, 0});
419 }
420 } else {
421 VLOG(2) << "Age: " << age_double << ", invalid charuco board pose";
422 }
Jim Ostrowski634b2652022-03-04 02:10:53 -0800423 } else {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800424 VLOG(2) << "Age: " << age_double << ", not enough charuco IDs, got "
425 << charuco_ids.size() << ", needed " << FLAGS_min_charucos;
Jim Ostrowski634b2652022-03-04 02:10:53 -0800426 }
Austin Schuh25837f22021-06-27 15:49:14 -0700427 } else {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800428 VLOG(2) << "Age: " << age_double
429 << ", not enough marker IDs for charuco board, got "
430 << marker_ids.size() << ", needed " << FLAGS_min_charucos;
431 }
milind-u09fb1252023-01-28 19:21:41 -0800432 } else if (target_type_ == TargetType::kAruco) {
433 // estimate pose for arucos doesn't return valid, so marking true
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800434 valid = true;
435 std::vector<cv::Vec3d> rvecs, tvecs;
436 cv::aruco::estimatePoseSingleMarkers(marker_corners, square_length_,
437 camera_matrix_, dist_coeffs_, rvecs,
438 tvecs);
439 DrawTargetPoses(rgb_image, rvecs, tvecs);
440
441 PackPoseResults(rvecs, tvecs, &rvecs_eigen, &tvecs_eigen);
442 for (uint i = 0; i < marker_ids.size(); i++) {
443 result_ids.emplace_back(cv::Vec4i{marker_ids[i], 0, 0, 0});
444 }
445 result_corners = marker_corners;
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800446 } else if (target_type_ == TargetType::kCharucoDiamond) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800447 // Extract the diamonds associated with the markers
448 std::vector<cv::Vec4i> diamond_ids;
449 std::vector<std::vector<cv::Point2f>> diamond_corners;
450 cv::aruco::detectCharucoDiamond(rgb_image, marker_corners, marker_ids,
451 square_length_ / marker_length_,
452 diamond_corners, diamond_ids);
453
454 // Check to see if we found any diamond targets
455 if (diamond_ids.size() > 0) {
456 cv::aruco::drawDetectedDiamonds(rgb_image, diamond_corners,
457 diamond_ids);
458
459 // estimate pose for diamonds doesn't return valid, so marking true
460 valid = true;
461 std::vector<cv::Vec3d> rvecs, tvecs;
462 cv::aruco::estimatePoseSingleMarkers(diamond_corners, square_length_,
463 camera_matrix_, dist_coeffs_,
464 rvecs, tvecs);
465 DrawTargetPoses(rgb_image, rvecs, tvecs);
466
467 PackPoseResults(rvecs, tvecs, &rvecs_eigen, &tvecs_eigen);
468 result_ids = diamond_ids;
469 result_corners = diamond_corners;
470 } else {
471 VLOG(2) << "Found aruco markers, but no charuco diamond targets";
Austin Schuh25837f22021-06-27 15:49:14 -0700472 }
473 } else {
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800474 LOG(FATAL) << "Unknown target type: "
475 << static_cast<uint8_t>(target_type_);
Austin Schuh25837f22021-06-27 15:49:14 -0700476 }
Austin Schuh25837f22021-06-27 15:49:14 -0700477 }
Austin Schuhea7b0142021-10-08 22:04:53 -0700478
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800479 handle_charuco_(rgb_image, eof, result_ids, result_corners, valid,
480 rvecs_eigen, tvecs_eigen);
Austin Schuh25837f22021-06-27 15:49:14 -0700481}
482
483} // namespace vision
484} // namespace frc971