blob: 65ee4adace87a92eb165e26e648ab0252ef9c6cc [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
30namespace frc971 {
31namespace vision {
32namespace chrono = std::chrono;
Austin Schuhea7b0142021-10-08 22:04:53 -070033using aos::monotonic_clock;
Austin Schuh25837f22021-06-27 15:49:14 -070034
35CameraCalibration::CameraCalibration(
36 const absl::Span<const uint8_t> training_data_bfbs, std::string_view pi) {
37 const aos::FlatbufferSpan<sift::TrainingData> training_data(
38 training_data_bfbs);
39 CHECK(training_data.Verify());
40 camera_calibration_ = FindCameraCalibration(&training_data.message(), pi);
41}
42
43cv::Mat CameraCalibration::CameraIntrinsics() const {
44 const cv::Mat result(3, 3, CV_32F,
45 const_cast<void *>(static_cast<const void *>(
46 camera_calibration_->intrinsics()->data())));
47 CHECK_EQ(result.total(), camera_calibration_->intrinsics()->size());
48 return result;
49}
50
51Eigen::Matrix3d CameraCalibration::CameraIntrinsicsEigen() const {
52 cv::Mat camera_intrinsics = CameraIntrinsics();
53 Eigen::Matrix3d result;
54 cv::cv2eigen(camera_intrinsics, result);
55 return result;
56}
57
58cv::Mat CameraCalibration::CameraDistCoeffs() const {
59 const cv::Mat result(5, 1, CV_32F,
60 const_cast<void *>(static_cast<const void *>(
61 camera_calibration_->dist_coeffs()->data())));
62 CHECK_EQ(result.total(), camera_calibration_->dist_coeffs()->size());
63 return result;
64}
65
66const sift::CameraCalibration *CameraCalibration::FindCameraCalibration(
67 const sift::TrainingData *const training_data, std::string_view pi) const {
68 std::optional<uint16_t> pi_number = aos::network::ParsePiNumber(pi);
69 std::optional<uint16_t> team_number =
70 aos::network::team_number_internal::ParsePiTeamNumber(pi);
71 CHECK(pi_number);
72 CHECK(team_number);
73 const std::string node_name = absl::StrFormat("pi%d", pi_number.value());
74 LOG(INFO) << "Looking for node name " << node_name << " team number "
75 << team_number.value();
76 for (const sift::CameraCalibration *candidate :
77 *training_data->camera_calibrations()) {
78 if (candidate->node_name()->string_view() != node_name) {
79 continue;
80 }
81 if (candidate->team_number() != team_number.value()) {
82 continue;
83 }
84 return candidate;
85 }
86 LOG(FATAL) << ": Failed to find camera calibration for " << node_name
87 << " on " << team_number.value();
88}
89
Austin Schuhea7b0142021-10-08 22:04:53 -070090ImageCallback::ImageCallback(
91 aos::EventLoop *event_loop, std::string_view channel,
Jim Ostrowskib3cab972022-12-03 15:47:00 -080092 std::function<void(cv::Mat, monotonic_clock::time_point)> &&handle_image_fn)
93
Austin Schuhea7b0142021-10-08 22:04:53 -070094 : event_loop_(event_loop),
95 server_fetcher_(
96 event_loop_->MakeFetcher<aos::message_bridge::ServerStatistics>(
97 "/aos")),
98 source_node_(aos::configuration::GetNode(
99 event_loop_->configuration(),
100 event_loop_->GetChannel<CameraImage>(channel)
101 ->source_node()
102 ->string_view())),
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800103 handle_image_(std::move(handle_image_fn)) {
Austin Schuh25837f22021-06-27 15:49:14 -0700104 event_loop_->MakeWatcher(channel, [this](const CameraImage &image) {
Austin Schuhea7b0142021-10-08 22:04:53 -0700105 const monotonic_clock::time_point eof_source_node =
106 monotonic_clock::time_point(
107 chrono::nanoseconds(image.monotonic_timestamp_ns()));
Austin Schuhea7b0142021-10-08 22:04:53 -0700108 chrono::nanoseconds offset{0};
109 if (source_node_ != event_loop_->node()) {
Austin Schuhee8bc1e2021-11-20 16:23:41 -0800110 server_fetcher_.Fetch();
111 if (!server_fetcher_.get()) {
112 return;
113 }
114
Austin Schuhea7b0142021-10-08 22:04:53 -0700115 // If we are viewing this image from another node, convert to our
116 // monotonic clock.
117 const aos::message_bridge::ServerConnection *server_connection = nullptr;
118
119 for (const aos::message_bridge::ServerConnection *connection :
120 *server_fetcher_->connections()) {
121 CHECK(connection->has_node());
122 if (connection->node()->name()->string_view() ==
123 source_node_->name()->string_view()) {
124 server_connection = connection;
125 break;
126 }
127 }
128
129 CHECK(server_connection != nullptr) << ": Failed to find client";
130 if (!server_connection->has_monotonic_offset()) {
131 VLOG(1) << "No offset yet.";
132 return;
133 }
134 offset = chrono::nanoseconds(server_connection->monotonic_offset());
135 }
136
137 const monotonic_clock::time_point eof = eof_source_node - offset;
138
Jim Ostrowski977850f2022-01-22 21:04:22 -0800139 const monotonic_clock::duration age = event_loop_->monotonic_now() - eof;
Austin Schuh25837f22021-06-27 15:49:14 -0700140 const double age_double =
141 std::chrono::duration_cast<std::chrono::duration<double>>(age).count();
142 if (age > std::chrono::milliseconds(100)) {
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800143 VLOG(2) << "Age: " << age_double << ", getting behind, skipping";
Austin Schuh25837f22021-06-27 15:49:14 -0700144 return;
145 }
146 // Create color image:
147 cv::Mat image_color_mat(cv::Size(image.cols(), image.rows()), CV_8UC2,
148 (void *)image.data()->data());
149 const cv::Size image_size(image.cols(), image.rows());
150 cv::Mat rgb_image(image_size, CV_8UC3);
Brian Silverman4c7235a2021-11-17 19:04:37 -0800151 cv::cvtColor(image_color_mat, rgb_image, cv::COLOR_YUV2BGR_YUYV);
Austin Schuhea7b0142021-10-08 22:04:53 -0700152 handle_image_(rgb_image, eof);
Austin Schuh25837f22021-06-27 15:49:14 -0700153 });
154}
155
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800156void CharucoExtractor::SetupTargetData() {
157 // TODO(Jim): Put correct values here
158 marker_length_ = 0.15;
159 square_length_ = 0.1651;
160
161 // Only charuco board has a board associated with it
162 board_ = static_cast<cv::Ptr<cv::aruco::CharucoBoard>>(NULL);
163
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800164 if (target_type_ == TargetType::kCharuco ||
165 target_type_ == TargetType::kAruco) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800166 dictionary_ = cv::aruco::getPredefinedDictionary(
167 FLAGS_large_board ? cv::aruco::DICT_5X5_250 : cv::aruco::DICT_6X6_250);
168
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800169 if (target_type_ == TargetType::kCharuco) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800170 LOG(INFO) << "Using " << (FLAGS_large_board ? " large " : " small ")
171 << " charuco board with "
172 << (FLAGS_coarse_pattern ? "coarse" : "fine") << " pattern";
173 board_ =
174 (FLAGS_large_board
175 ? (FLAGS_coarse_pattern ? cv::aruco::CharucoBoard::create(
176 12, 9, 0.06, 0.04666, dictionary_)
177 : cv::aruco::CharucoBoard::create(
178 25, 18, 0.03, 0.0233, dictionary_))
179 : (FLAGS_coarse_pattern ? cv::aruco::CharucoBoard::create(
180 7, 5, 0.04, 0.025, dictionary_)
181 // TODO(jim): Need to figure out what
182 // size is for small board, fine pattern
183 : cv::aruco::CharucoBoard::create(
184 7, 5, 0.03, 0.0233, dictionary_)));
185 if (!FLAGS_board_template_path.empty()) {
186 cv::Mat board_image;
187 board_->draw(cv::Size(600, 500), board_image, 10, 1);
188 cv::imwrite(FLAGS_board_template_path, board_image);
189 }
190 }
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800191 } else if (target_type_ == TargetType::kCharucoDiamond) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800192 // TODO<Jim>: Measure this
193 marker_length_ = 0.15;
194 square_length_ = 0.1651;
195 dictionary_ = cv::aruco::getPredefinedDictionary(cv::aruco::DICT_4X4_250);
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800196 } else if (target_type_ == TargetType::kAprilTag) {
Yash Chainanib31b0b12022-12-03 17:27:09 -0800197 // Tag will be 6 in (15.24 cm) according to
198 // https://www.firstinspires.org/robotics/frc/blog/2022-2023-approved-devices-rules-preview-and-vision-target-update
199 square_length_ = 0.1524;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800200 dictionary_ =
Yash Chainanib31b0b12022-12-03 17:27:09 -0800201 cv::aruco::getPredefinedDictionary(cv::aruco::DICT_APRILTAG_16h5);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800202 } else {
203 // Bail out if it's not a supported target
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800204 LOG(FATAL) << "Target type undefined: "
205 << static_cast<uint8_t>(target_type_);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800206 }
207}
208
209void CharucoExtractor::DrawTargetPoses(cv::Mat rgb_image,
210 std::vector<cv::Vec3d> rvecs,
211 std::vector<cv::Vec3d> tvecs) {
212 const Eigen::Matrix<double, 3, 4> camera_projection =
213 Eigen::Matrix<double, 3, 4>::Identity();
214
215 int x_coord = 10;
216 int y_coord = 0;
217 // draw axis for each marker
218 for (uint i = 0; i < rvecs.size(); i++) {
219 Eigen::Vector3d rvec_eigen, tvec_eigen;
220 cv::cv2eigen(rvecs[i], rvec_eigen);
221 cv::cv2eigen(tvecs[i], tvec_eigen);
222
223 Eigen::Quaternion<double> rotation(
224 frc971::controls::ToQuaternionFromRotationVector(rvec_eigen));
225 Eigen::Translation3d translation(tvec_eigen);
226
227 const Eigen::Affine3d board_to_camera = translation * rotation;
228
229 Eigen::Vector3d result = eigen_camera_matrix_ * camera_projection *
230 board_to_camera * Eigen::Vector3d::Zero();
231
232 // Found that drawAxis hangs if you try to draw with z values too
233 // small (trying to draw axes at inifinity)
234 // TODO<Jim>: Explore what real thresholds for this should be;
235 // likely Don't need to get rid of negative values
236 if (result.z() < 0.01) {
237 LOG(INFO) << "Skipping, due to z value too small: " << result.z();
238 } else {
239 result /= result.z();
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800240 if (target_type_ == TargetType::kCharuco) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800241 cv::aruco::drawAxis(rgb_image, camera_matrix_, dist_coeffs_, rvecs[i],
242 tvecs[i], 0.1);
243 } else {
244 cv::drawFrameAxes(rgb_image, camera_matrix_, dist_coeffs_, rvecs[i],
245 tvecs[i], 0.1);
246 }
247 }
248 std::stringstream ss;
249 ss << "tvec[" << i << "] = " << tvecs[i];
250 y_coord += 25;
251 cv::putText(rgb_image, ss.str(), cv::Point(x_coord, y_coord),
252 cv::FONT_HERSHEY_PLAIN, 1.0, cv::Scalar(255, 255, 255));
253 ss.str("");
254 ss << "rvec[" << i << "] = " << rvecs[i];
255 y_coord += 25;
256 cv::putText(rgb_image, ss.str(), cv::Point(x_coord, y_coord),
257 cv::FONT_HERSHEY_PLAIN, 1.0, cv::Scalar(255, 255, 255));
258 }
259}
260
261void CharucoExtractor::PackPoseResults(
262 std::vector<cv::Vec3d> &rvecs, std::vector<cv::Vec3d> &tvecs,
263 std::vector<Eigen::Vector3d> *rvecs_eigen,
264 std::vector<Eigen::Vector3d> *tvecs_eigen) {
265 for (cv::Vec3d rvec : rvecs) {
266 Eigen::Vector3d rvec_eigen = Eigen::Vector3d::Zero();
267 cv::cv2eigen(rvec, rvec_eigen);
268 rvecs_eigen->emplace_back(rvec_eigen);
269 }
270
271 for (cv::Vec3d tvec : tvecs) {
272 Eigen::Vector3d tvec_eigen = Eigen::Vector3d::Zero();
273 cv::cv2eigen(tvec, tvec_eigen);
274 tvecs_eigen->emplace_back(tvec_eigen);
275 }
276}
277
Austin Schuh25837f22021-06-27 15:49:14 -0700278CharucoExtractor::CharucoExtractor(
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800279 aos::EventLoop *event_loop, std::string_view pi, TargetType target_type,
280 std::string_view image_channel,
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800281 std::function<void(cv::Mat, monotonic_clock::time_point,
282 std::vector<cv::Vec4i>,
283 std::vector<std::vector<cv::Point2f>>, bool,
284 std::vector<Eigen::Vector3d>,
285 std::vector<Eigen::Vector3d>)> &&handle_charuco_fn)
Austin Schuhea7b0142021-10-08 22:04:53 -0700286 : event_loop_(event_loop),
287 calibration_(SiftTrainingData(), pi),
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800288 target_type_(target_type),
289 image_channel_(image_channel),
Austin Schuh25837f22021-06-27 15:49:14 -0700290 camera_matrix_(calibration_.CameraIntrinsics()),
291 eigen_camera_matrix_(calibration_.CameraIntrinsicsEigen()),
292 dist_coeffs_(calibration_.CameraDistCoeffs()),
293 pi_number_(aos::network::ParsePiNumber(pi)),
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800294 handle_charuco_(std::move(handle_charuco_fn)) {
295 SetupTargetData();
Austin Schuh25837f22021-06-27 15:49:14 -0700296
297 LOG(INFO) << "Camera matrix " << camera_matrix_;
298 LOG(INFO) << "Distortion Coefficients " << dist_coeffs_;
299
300 CHECK(pi_number_) << ": Invalid pi number " << pi
301 << ", failed to parse pi number";
302
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800303 LOG(INFO) << "Connecting to channel " << image_channel_;
Austin Schuh25837f22021-06-27 15:49:14 -0700304}
305
Austin Schuhea7b0142021-10-08 22:04:53 -0700306void CharucoExtractor::HandleImage(cv::Mat rgb_image,
307 const monotonic_clock::time_point eof) {
308 const double age_double =
309 std::chrono::duration_cast<std::chrono::duration<double>>(
310 event_loop_->monotonic_now() - eof)
311 .count();
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800312
313 // Set up the variables we'll use in the callback function
314 bool valid = false;
315 // Return a list of poses; for Charuco Board there will be just one
316 std::vector<Eigen::Vector3d> rvecs_eigen;
317 std::vector<Eigen::Vector3d> tvecs_eigen;
318
319 // ids and corners for initial aruco marker detections
Austin Schuh25837f22021-06-27 15:49:14 -0700320 std::vector<int> marker_ids;
321 std::vector<std::vector<cv::Point2f>> marker_corners;
322
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800323 // ids and corners for final, refined board / marker detections
324 // Using Vec4i type since it supports Charuco Diamonds
325 // And overloading it using 1st int in Vec4i for others target types
326 std::vector<cv::Vec4i> result_ids;
327 std::vector<std::vector<cv::Point2f>> result_corners;
Austin Schuh25837f22021-06-27 15:49:14 -0700328
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800329 // Do initial marker detection; this is the same for all target types
330 cv::aruco::detectMarkers(rgb_image, dictionary_, marker_corners, marker_ids);
331 cv::aruco::drawDetectedMarkers(rgb_image, marker_corners, marker_ids);
Austin Schuhea7b0142021-10-08 22:04:53 -0700332
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800333 VLOG(2) << "Handle Image, with target type = "
334 << static_cast<uint8_t>(target_type_) << " and " << marker_ids.size()
335 << " markers detected initially";
Austin Schuh25837f22021-06-27 15:49:14 -0700336
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800337 if (marker_ids.size() == 0) {
338 VLOG(2) << "Didn't find any markers";
339 } else {
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800340 if (target_type_ == TargetType::kCharuco) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800341 std::vector<int> charuco_ids;
342 std::vector<cv::Point2f> charuco_corners;
Austin Schuh25837f22021-06-27 15:49:14 -0700343
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800344 // If enough aruco markers detected for the Charuco board
345 if (marker_ids.size() >= FLAGS_min_charucos) {
346 // Run everything twice, once with the calibration, and once
347 // without. This lets us both collect data to calibrate the
348 // intrinsics of the camera (to determine the intrinsics from
349 // multiple samples), and also to use data from a previous/stored
350 // calibration to determine a more accurate pose in real time (used
351 // for extrinsics calibration)
352 cv::aruco::interpolateCornersCharuco(marker_corners, marker_ids,
353 rgb_image, board_, charuco_corners,
354 charuco_ids);
Austin Schuh25837f22021-06-27 15:49:14 -0700355
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800356 std::vector<cv::Point2f> charuco_corners_with_calibration;
357 std::vector<int> charuco_ids_with_calibration;
Austin Schuh25837f22021-06-27 15:49:14 -0700358
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800359 // This call uses a previous intrinsic calibration to get more
360 // accurate marker locations, for a better pose estimate
361 cv::aruco::interpolateCornersCharuco(
362 marker_corners, marker_ids, rgb_image, board_,
363 charuco_corners_with_calibration, charuco_ids_with_calibration,
364 camera_matrix_, dist_coeffs_);
Austin Schuh25837f22021-06-27 15:49:14 -0700365
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800366 if (charuco_ids.size() >= FLAGS_min_charucos) {
367 cv::aruco::drawDetectedCornersCharuco(
368 rgb_image, charuco_corners, charuco_ids, cv::Scalar(255, 0, 0));
Austin Schuh25837f22021-06-27 15:49:14 -0700369
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800370 cv::Vec3d rvec, tvec;
371 valid = cv::aruco::estimatePoseCharucoBoard(
372 charuco_corners_with_calibration, charuco_ids_with_calibration,
373 board_, camera_matrix_, dist_coeffs_, rvec, tvec);
Austin Schuh25837f22021-06-27 15:49:14 -0700374
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800375 // if charuco pose is valid, return pose, with ids and corners
376 if (valid) {
377 std::vector<cv::Vec3d> rvecs, tvecs;
378 rvecs.emplace_back(rvec);
379 tvecs.emplace_back(tvec);
380 DrawTargetPoses(rgb_image, rvecs, tvecs);
Austin Schuh25837f22021-06-27 15:49:14 -0700381
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800382 PackPoseResults(rvecs, tvecs, &rvecs_eigen, &tvecs_eigen);
383 // Store the corners without calibration, since we use them to
384 // do calibration
385 result_corners.emplace_back(charuco_corners);
386 for (auto id : charuco_ids) {
387 result_ids.emplace_back(cv::Vec4i{id, 0, 0, 0});
388 }
389 } else {
390 VLOG(2) << "Age: " << age_double << ", invalid charuco board pose";
391 }
Jim Ostrowski634b2652022-03-04 02:10:53 -0800392 } else {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800393 VLOG(2) << "Age: " << age_double << ", not enough charuco IDs, got "
394 << charuco_ids.size() << ", needed " << FLAGS_min_charucos;
Jim Ostrowski634b2652022-03-04 02:10:53 -0800395 }
Austin Schuh25837f22021-06-27 15:49:14 -0700396 } else {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800397 VLOG(2) << "Age: " << age_double
398 << ", not enough marker IDs for charuco board, got "
399 << marker_ids.size() << ", needed " << FLAGS_min_charucos;
400 }
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800401 } else if (target_type_ == TargetType::kAprilTag ||
402 target_type_ == TargetType::kAruco) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800403 // estimate pose for april tags doesn't return valid, so marking true
404 valid = true;
405 std::vector<cv::Vec3d> rvecs, tvecs;
406 cv::aruco::estimatePoseSingleMarkers(marker_corners, square_length_,
407 camera_matrix_, dist_coeffs_, rvecs,
408 tvecs);
409 DrawTargetPoses(rgb_image, rvecs, tvecs);
410
411 PackPoseResults(rvecs, tvecs, &rvecs_eigen, &tvecs_eigen);
412 for (uint i = 0; i < marker_ids.size(); i++) {
413 result_ids.emplace_back(cv::Vec4i{marker_ids[i], 0, 0, 0});
414 }
415 result_corners = marker_corners;
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800416 } else if (target_type_ == TargetType::kCharucoDiamond) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800417 // Extract the diamonds associated with the markers
418 std::vector<cv::Vec4i> diamond_ids;
419 std::vector<std::vector<cv::Point2f>> diamond_corners;
420 cv::aruco::detectCharucoDiamond(rgb_image, marker_corners, marker_ids,
421 square_length_ / marker_length_,
422 diamond_corners, diamond_ids);
423
424 // Check to see if we found any diamond targets
425 if (diamond_ids.size() > 0) {
426 cv::aruco::drawDetectedDiamonds(rgb_image, diamond_corners,
427 diamond_ids);
428
429 // estimate pose for diamonds doesn't return valid, so marking true
430 valid = true;
431 std::vector<cv::Vec3d> rvecs, tvecs;
432 cv::aruco::estimatePoseSingleMarkers(diamond_corners, square_length_,
433 camera_matrix_, dist_coeffs_,
434 rvecs, tvecs);
435 DrawTargetPoses(rgb_image, rvecs, tvecs);
436
437 PackPoseResults(rvecs, tvecs, &rvecs_eigen, &tvecs_eigen);
438 result_ids = diamond_ids;
439 result_corners = diamond_corners;
440 } else {
441 VLOG(2) << "Found aruco markers, but no charuco diamond targets";
Austin Schuh25837f22021-06-27 15:49:14 -0700442 }
443 } else {
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800444 LOG(FATAL) << "Unknown target type: "
445 << static_cast<uint8_t>(target_type_);
Austin Schuh25837f22021-06-27 15:49:14 -0700446 }
Austin Schuh25837f22021-06-27 15:49:14 -0700447 }
Austin Schuhea7b0142021-10-08 22:04:53 -0700448
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800449 handle_charuco_(rgb_image, eof, result_ids, result_corners, valid,
450 rvecs_eigen, tvecs_eigen);
Austin Schuh25837f22021-06-27 15:49:14 -0700451}
452
453} // namespace vision
454} // namespace frc971