blob: 82cf56bf824d95d511adb031722457626325e799 [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.");
28DEFINE_string(target_type, "charuco",
29 "Type of target: april_tag|aruco|charuco|charuco_diamond");
30DEFINE_bool(visualize, false, "Whether to visualize the resulting data.");
Austin Schuh25837f22021-06-27 15:49:14 -070031
32namespace frc971 {
33namespace vision {
34namespace chrono = std::chrono;
Austin Schuhea7b0142021-10-08 22:04:53 -070035using aos::monotonic_clock;
Austin Schuh25837f22021-06-27 15:49:14 -070036
37CameraCalibration::CameraCalibration(
38 const absl::Span<const uint8_t> training_data_bfbs, std::string_view pi) {
39 const aos::FlatbufferSpan<sift::TrainingData> training_data(
40 training_data_bfbs);
41 CHECK(training_data.Verify());
42 camera_calibration_ = FindCameraCalibration(&training_data.message(), pi);
43}
44
45cv::Mat CameraCalibration::CameraIntrinsics() const {
46 const cv::Mat result(3, 3, CV_32F,
47 const_cast<void *>(static_cast<const void *>(
48 camera_calibration_->intrinsics()->data())));
49 CHECK_EQ(result.total(), camera_calibration_->intrinsics()->size());
50 return result;
51}
52
53Eigen::Matrix3d CameraCalibration::CameraIntrinsicsEigen() const {
54 cv::Mat camera_intrinsics = CameraIntrinsics();
55 Eigen::Matrix3d result;
56 cv::cv2eigen(camera_intrinsics, result);
57 return result;
58}
59
60cv::Mat CameraCalibration::CameraDistCoeffs() const {
61 const cv::Mat result(5, 1, CV_32F,
62 const_cast<void *>(static_cast<const void *>(
63 camera_calibration_->dist_coeffs()->data())));
64 CHECK_EQ(result.total(), camera_calibration_->dist_coeffs()->size());
65 return result;
66}
67
68const sift::CameraCalibration *CameraCalibration::FindCameraCalibration(
69 const sift::TrainingData *const training_data, std::string_view pi) const {
70 std::optional<uint16_t> pi_number = aos::network::ParsePiNumber(pi);
71 std::optional<uint16_t> team_number =
72 aos::network::team_number_internal::ParsePiTeamNumber(pi);
73 CHECK(pi_number);
74 CHECK(team_number);
75 const std::string node_name = absl::StrFormat("pi%d", pi_number.value());
76 LOG(INFO) << "Looking for node name " << node_name << " team number "
77 << team_number.value();
78 for (const sift::CameraCalibration *candidate :
79 *training_data->camera_calibrations()) {
80 if (candidate->node_name()->string_view() != node_name) {
81 continue;
82 }
83 if (candidate->team_number() != team_number.value()) {
84 continue;
85 }
86 return candidate;
87 }
88 LOG(FATAL) << ": Failed to find camera calibration for " << node_name
89 << " on " << team_number.value();
90}
91
Austin Schuhea7b0142021-10-08 22:04:53 -070092ImageCallback::ImageCallback(
93 aos::EventLoop *event_loop, std::string_view channel,
Jim Ostrowskib3cab972022-12-03 15:47:00 -080094 std::function<void(cv::Mat, monotonic_clock::time_point)> &&handle_image_fn)
95
Austin Schuhea7b0142021-10-08 22:04:53 -070096 : event_loop_(event_loop),
97 server_fetcher_(
98 event_loop_->MakeFetcher<aos::message_bridge::ServerStatistics>(
99 "/aos")),
100 source_node_(aos::configuration::GetNode(
101 event_loop_->configuration(),
102 event_loop_->GetChannel<CameraImage>(channel)
103 ->source_node()
104 ->string_view())),
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800105 handle_image_(std::move(handle_image_fn)) {
Austin Schuh25837f22021-06-27 15:49:14 -0700106 event_loop_->MakeWatcher(channel, [this](const CameraImage &image) {
Austin Schuhea7b0142021-10-08 22:04:53 -0700107 const monotonic_clock::time_point eof_source_node =
108 monotonic_clock::time_point(
109 chrono::nanoseconds(image.monotonic_timestamp_ns()));
Austin Schuhea7b0142021-10-08 22:04:53 -0700110 chrono::nanoseconds offset{0};
111 if (source_node_ != event_loop_->node()) {
Austin Schuhee8bc1e2021-11-20 16:23:41 -0800112 server_fetcher_.Fetch();
113 if (!server_fetcher_.get()) {
114 return;
115 }
116
Austin Schuhea7b0142021-10-08 22:04:53 -0700117 // If we are viewing this image from another node, convert to our
118 // monotonic clock.
119 const aos::message_bridge::ServerConnection *server_connection = nullptr;
120
121 for (const aos::message_bridge::ServerConnection *connection :
122 *server_fetcher_->connections()) {
123 CHECK(connection->has_node());
124 if (connection->node()->name()->string_view() ==
125 source_node_->name()->string_view()) {
126 server_connection = connection;
127 break;
128 }
129 }
130
131 CHECK(server_connection != nullptr) << ": Failed to find client";
132 if (!server_connection->has_monotonic_offset()) {
133 VLOG(1) << "No offset yet.";
134 return;
135 }
136 offset = chrono::nanoseconds(server_connection->monotonic_offset());
137 }
138
139 const monotonic_clock::time_point eof = eof_source_node - offset;
140
Jim Ostrowski977850f2022-01-22 21:04:22 -0800141 const monotonic_clock::duration age = event_loop_->monotonic_now() - eof;
Austin Schuh25837f22021-06-27 15:49:14 -0700142 const double age_double =
143 std::chrono::duration_cast<std::chrono::duration<double>>(age).count();
144 if (age > std::chrono::milliseconds(100)) {
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800145 VLOG(2) << "Age: " << age_double << ", getting behind, skipping";
Austin Schuh25837f22021-06-27 15:49:14 -0700146 return;
147 }
148 // Create color image:
149 cv::Mat image_color_mat(cv::Size(image.cols(), image.rows()), CV_8UC2,
150 (void *)image.data()->data());
151 const cv::Size image_size(image.cols(), image.rows());
152 cv::Mat rgb_image(image_size, CV_8UC3);
Brian Silverman4c7235a2021-11-17 19:04:37 -0800153 cv::cvtColor(image_color_mat, rgb_image, cv::COLOR_YUV2BGR_YUYV);
Austin Schuhea7b0142021-10-08 22:04:53 -0700154 handle_image_(rgb_image, eof);
Austin Schuh25837f22021-06-27 15:49:14 -0700155 });
156}
157
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800158void CharucoExtractor::SetupTargetData() {
159 // TODO(Jim): Put correct values here
160 marker_length_ = 0.15;
161 square_length_ = 0.1651;
162
163 // Only charuco board has a board associated with it
164 board_ = static_cast<cv::Ptr<cv::aruco::CharucoBoard>>(NULL);
165
166 if (FLAGS_target_type == "charuco" || FLAGS_target_type == "aruco") {
167 dictionary_ = cv::aruco::getPredefinedDictionary(
168 FLAGS_large_board ? cv::aruco::DICT_5X5_250 : cv::aruco::DICT_6X6_250);
169
170 if (FLAGS_target_type == "charuco") {
171 LOG(INFO) << "Using " << (FLAGS_large_board ? " large " : " small ")
172 << " charuco board with "
173 << (FLAGS_coarse_pattern ? "coarse" : "fine") << " pattern";
174 board_ =
175 (FLAGS_large_board
176 ? (FLAGS_coarse_pattern ? cv::aruco::CharucoBoard::create(
177 12, 9, 0.06, 0.04666, dictionary_)
178 : cv::aruco::CharucoBoard::create(
179 25, 18, 0.03, 0.0233, dictionary_))
180 : (FLAGS_coarse_pattern ? cv::aruco::CharucoBoard::create(
181 7, 5, 0.04, 0.025, dictionary_)
182 // TODO(jim): Need to figure out what
183 // size is for small board, fine pattern
184 : cv::aruco::CharucoBoard::create(
185 7, 5, 0.03, 0.0233, dictionary_)));
186 if (!FLAGS_board_template_path.empty()) {
187 cv::Mat board_image;
188 board_->draw(cv::Size(600, 500), board_image, 10, 1);
189 cv::imwrite(FLAGS_board_template_path, board_image);
190 }
191 }
192 } else if (FLAGS_target_type == "charuco_diamond") {
193 // TODO<Jim>: Measure this
194 marker_length_ = 0.15;
195 square_length_ = 0.1651;
196 dictionary_ = cv::aruco::getPredefinedDictionary(cv::aruco::DICT_4X4_250);
197 } else if (FLAGS_target_type == "april_tag") {
Yash Chainanib31b0b12022-12-03 17:27:09 -0800198 // Tag will be 6 in (15.24 cm) according to
199 // https://www.firstinspires.org/robotics/frc/blog/2022-2023-approved-devices-rules-preview-and-vision-target-update
200 square_length_ = 0.1524;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800201 dictionary_ =
Yash Chainanib31b0b12022-12-03 17:27:09 -0800202 cv::aruco::getPredefinedDictionary(cv::aruco::DICT_APRILTAG_16h5);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800203 } else {
204 // Bail out if it's not a supported target
205 LOG(FATAL) << "Target type undefined: " << FLAGS_target_type
206 << " vs. april_tag|aruco|charuco|charuco_diamond";
207 }
208}
209
210void CharucoExtractor::DrawTargetPoses(cv::Mat rgb_image,
211 std::vector<cv::Vec3d> rvecs,
212 std::vector<cv::Vec3d> tvecs) {
213 const Eigen::Matrix<double, 3, 4> camera_projection =
214 Eigen::Matrix<double, 3, 4>::Identity();
215
216 int x_coord = 10;
217 int y_coord = 0;
218 // draw axis for each marker
219 for (uint i = 0; i < rvecs.size(); i++) {
220 Eigen::Vector3d rvec_eigen, tvec_eigen;
221 cv::cv2eigen(rvecs[i], rvec_eigen);
222 cv::cv2eigen(tvecs[i], tvec_eigen);
223
224 Eigen::Quaternion<double> rotation(
225 frc971::controls::ToQuaternionFromRotationVector(rvec_eigen));
226 Eigen::Translation3d translation(tvec_eigen);
227
228 const Eigen::Affine3d board_to_camera = translation * rotation;
229
230 Eigen::Vector3d result = eigen_camera_matrix_ * camera_projection *
231 board_to_camera * Eigen::Vector3d::Zero();
232
233 // Found that drawAxis hangs if you try to draw with z values too
234 // small (trying to draw axes at inifinity)
235 // TODO<Jim>: Explore what real thresholds for this should be;
236 // likely Don't need to get rid of negative values
237 if (result.z() < 0.01) {
238 LOG(INFO) << "Skipping, due to z value too small: " << result.z();
239 } else {
240 result /= result.z();
241 if (FLAGS_target_type == "charuco") {
242 cv::aruco::drawAxis(rgb_image, camera_matrix_, dist_coeffs_, rvecs[i],
243 tvecs[i], 0.1);
244 } else {
245 cv::drawFrameAxes(rgb_image, camera_matrix_, dist_coeffs_, rvecs[i],
246 tvecs[i], 0.1);
247 }
248 }
249 std::stringstream ss;
250 ss << "tvec[" << i << "] = " << tvecs[i];
251 y_coord += 25;
252 cv::putText(rgb_image, ss.str(), cv::Point(x_coord, y_coord),
253 cv::FONT_HERSHEY_PLAIN, 1.0, cv::Scalar(255, 255, 255));
254 ss.str("");
255 ss << "rvec[" << i << "] = " << rvecs[i];
256 y_coord += 25;
257 cv::putText(rgb_image, ss.str(), cv::Point(x_coord, y_coord),
258 cv::FONT_HERSHEY_PLAIN, 1.0, cv::Scalar(255, 255, 255));
259 }
260}
261
262void CharucoExtractor::PackPoseResults(
263 std::vector<cv::Vec3d> &rvecs, std::vector<cv::Vec3d> &tvecs,
264 std::vector<Eigen::Vector3d> *rvecs_eigen,
265 std::vector<Eigen::Vector3d> *tvecs_eigen) {
266 for (cv::Vec3d rvec : rvecs) {
267 Eigen::Vector3d rvec_eigen = Eigen::Vector3d::Zero();
268 cv::cv2eigen(rvec, rvec_eigen);
269 rvecs_eigen->emplace_back(rvec_eigen);
270 }
271
272 for (cv::Vec3d tvec : tvecs) {
273 Eigen::Vector3d tvec_eigen = Eigen::Vector3d::Zero();
274 cv::cv2eigen(tvec, tvec_eigen);
275 tvecs_eigen->emplace_back(tvec_eigen);
276 }
277}
278
Austin Schuh25837f22021-06-27 15:49:14 -0700279CharucoExtractor::CharucoExtractor(
280 aos::EventLoop *event_loop, std::string_view pi,
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),
Austin Schuh25837f22021-06-27 15:49:14 -0700288 camera_matrix_(calibration_.CameraIntrinsics()),
289 eigen_camera_matrix_(calibration_.CameraIntrinsicsEigen()),
290 dist_coeffs_(calibration_.CameraDistCoeffs()),
291 pi_number_(aos::network::ParsePiNumber(pi)),
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800292 handle_charuco_(std::move(handle_charuco_fn)) {
293 SetupTargetData();
Austin Schuh25837f22021-06-27 15:49:14 -0700294
295 LOG(INFO) << "Camera matrix " << camera_matrix_;
296 LOG(INFO) << "Distortion Coefficients " << dist_coeffs_;
297
298 CHECK(pi_number_) << ": Invalid pi number " << pi
299 << ", failed to parse pi number";
300
301 LOG(INFO) << "Connecting to channel /pi" << pi_number_.value() << "/camera";
302}
303
Austin Schuhea7b0142021-10-08 22:04:53 -0700304void CharucoExtractor::HandleImage(cv::Mat rgb_image,
305 const monotonic_clock::time_point eof) {
306 const double age_double =
307 std::chrono::duration_cast<std::chrono::duration<double>>(
308 event_loop_->monotonic_now() - eof)
309 .count();
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800310
311 // Set up the variables we'll use in the callback function
312 bool valid = false;
313 // Return a list of poses; for Charuco Board there will be just one
314 std::vector<Eigen::Vector3d> rvecs_eigen;
315 std::vector<Eigen::Vector3d> tvecs_eigen;
316
317 // ids and corners for initial aruco marker detections
Austin Schuh25837f22021-06-27 15:49:14 -0700318 std::vector<int> marker_ids;
319 std::vector<std::vector<cv::Point2f>> marker_corners;
320
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800321 // ids and corners for final, refined board / marker detections
322 // Using Vec4i type since it supports Charuco Diamonds
323 // And overloading it using 1st int in Vec4i for others target types
324 std::vector<cv::Vec4i> result_ids;
325 std::vector<std::vector<cv::Point2f>> result_corners;
Austin Schuh25837f22021-06-27 15:49:14 -0700326
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800327 // Do initial marker detection; this is the same for all target types
328 cv::aruco::detectMarkers(rgb_image, dictionary_, marker_corners, marker_ids);
329 cv::aruco::drawDetectedMarkers(rgb_image, marker_corners, marker_ids);
Austin Schuhea7b0142021-10-08 22:04:53 -0700330
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800331 VLOG(2) << "Handle Image, with target type = " << FLAGS_target_type << " and "
332 << marker_ids.size() << " markers detected initially";
Austin Schuh25837f22021-06-27 15:49:14 -0700333
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800334 if (marker_ids.size() == 0) {
335 VLOG(2) << "Didn't find any markers";
336 } else {
337 if (FLAGS_target_type == "charuco") {
338 std::vector<int> charuco_ids;
339 std::vector<cv::Point2f> charuco_corners;
Austin Schuh25837f22021-06-27 15:49:14 -0700340
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800341 // If enough aruco markers detected for the Charuco board
342 if (marker_ids.size() >= FLAGS_min_charucos) {
343 // Run everything twice, once with the calibration, and once
344 // without. This lets us both collect data to calibrate the
345 // intrinsics of the camera (to determine the intrinsics from
346 // multiple samples), and also to use data from a previous/stored
347 // calibration to determine a more accurate pose in real time (used
348 // for extrinsics calibration)
349 cv::aruco::interpolateCornersCharuco(marker_corners, marker_ids,
350 rgb_image, board_, charuco_corners,
351 charuco_ids);
Austin Schuh25837f22021-06-27 15:49:14 -0700352
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800353 std::vector<cv::Point2f> charuco_corners_with_calibration;
354 std::vector<int> charuco_ids_with_calibration;
Austin Schuh25837f22021-06-27 15:49:14 -0700355
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800356 // This call uses a previous intrinsic calibration to get more
357 // accurate marker locations, for a better pose estimate
358 cv::aruco::interpolateCornersCharuco(
359 marker_corners, marker_ids, rgb_image, board_,
360 charuco_corners_with_calibration, charuco_ids_with_calibration,
361 camera_matrix_, dist_coeffs_);
Austin Schuh25837f22021-06-27 15:49:14 -0700362
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800363 if (charuco_ids.size() >= FLAGS_min_charucos) {
364 cv::aruco::drawDetectedCornersCharuco(
365 rgb_image, charuco_corners, charuco_ids, cv::Scalar(255, 0, 0));
Austin Schuh25837f22021-06-27 15:49:14 -0700366
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800367 cv::Vec3d rvec, tvec;
368 valid = cv::aruco::estimatePoseCharucoBoard(
369 charuco_corners_with_calibration, charuco_ids_with_calibration,
370 board_, camera_matrix_, dist_coeffs_, rvec, tvec);
Austin Schuh25837f22021-06-27 15:49:14 -0700371
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800372 // if charuco pose is valid, return pose, with ids and corners
373 if (valid) {
374 std::vector<cv::Vec3d> rvecs, tvecs;
375 rvecs.emplace_back(rvec);
376 tvecs.emplace_back(tvec);
377 DrawTargetPoses(rgb_image, rvecs, tvecs);
Austin Schuh25837f22021-06-27 15:49:14 -0700378
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800379 PackPoseResults(rvecs, tvecs, &rvecs_eigen, &tvecs_eigen);
380 // Store the corners without calibration, since we use them to
381 // do calibration
382 result_corners.emplace_back(charuco_corners);
383 for (auto id : charuco_ids) {
384 result_ids.emplace_back(cv::Vec4i{id, 0, 0, 0});
385 }
386 } else {
387 VLOG(2) << "Age: " << age_double << ", invalid charuco board pose";
388 }
Jim Ostrowski634b2652022-03-04 02:10:53 -0800389 } else {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800390 VLOG(2) << "Age: " << age_double << ", not enough charuco IDs, got "
391 << charuco_ids.size() << ", needed " << FLAGS_min_charucos;
Jim Ostrowski634b2652022-03-04 02:10:53 -0800392 }
Austin Schuh25837f22021-06-27 15:49:14 -0700393 } else {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800394 VLOG(2) << "Age: " << age_double
395 << ", not enough marker IDs for charuco board, got "
396 << marker_ids.size() << ", needed " << FLAGS_min_charucos;
397 }
398 } else if (FLAGS_target_type == "april_tag" ||
399 FLAGS_target_type == "aruco") {
400 // estimate pose for april tags doesn't return valid, so marking true
401 valid = true;
402 std::vector<cv::Vec3d> rvecs, tvecs;
403 cv::aruco::estimatePoseSingleMarkers(marker_corners, square_length_,
404 camera_matrix_, dist_coeffs_, rvecs,
405 tvecs);
406 DrawTargetPoses(rgb_image, rvecs, tvecs);
407
408 PackPoseResults(rvecs, tvecs, &rvecs_eigen, &tvecs_eigen);
409 for (uint i = 0; i < marker_ids.size(); i++) {
410 result_ids.emplace_back(cv::Vec4i{marker_ids[i], 0, 0, 0});
411 }
412 result_corners = marker_corners;
413 } else if (FLAGS_target_type == "charuco_diamond") {
414 // Extract the diamonds associated with the markers
415 std::vector<cv::Vec4i> diamond_ids;
416 std::vector<std::vector<cv::Point2f>> diamond_corners;
417 cv::aruco::detectCharucoDiamond(rgb_image, marker_corners, marker_ids,
418 square_length_ / marker_length_,
419 diamond_corners, diamond_ids);
420
421 // Check to see if we found any diamond targets
422 if (diamond_ids.size() > 0) {
423 cv::aruco::drawDetectedDiamonds(rgb_image, diamond_corners,
424 diamond_ids);
425
426 // estimate pose for diamonds doesn't return valid, so marking true
427 valid = true;
428 std::vector<cv::Vec3d> rvecs, tvecs;
429 cv::aruco::estimatePoseSingleMarkers(diamond_corners, square_length_,
430 camera_matrix_, dist_coeffs_,
431 rvecs, tvecs);
432 DrawTargetPoses(rgb_image, rvecs, tvecs);
433
434 PackPoseResults(rvecs, tvecs, &rvecs_eigen, &tvecs_eigen);
435 result_ids = diamond_ids;
436 result_corners = diamond_corners;
437 } else {
438 VLOG(2) << "Found aruco markers, but no charuco diamond targets";
Austin Schuh25837f22021-06-27 15:49:14 -0700439 }
440 } else {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800441 LOG(FATAL) << "Unknown target type: " << FLAGS_target_type;
Austin Schuh25837f22021-06-27 15:49:14 -0700442 }
Austin Schuh25837f22021-06-27 15:49:14 -0700443 }
Austin Schuhea7b0142021-10-08 22:04:53 -0700444
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800445 handle_charuco_(rgb_image, eof, result_ids, result_corners, valid,
446 rvecs_eigen, tvecs_eigen);
Austin Schuh25837f22021-06-27 15:49:14 -0700447}
448
449} // namespace vision
450} // namespace frc971