blob: c24d02ce0c262ed6756f7d8690afb618423a1050 [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>
Philipp Schrader790cb542023-07-05 21:06:52 -07005#include <string_view>
6
7#include "glog/logging.h"
Austin Schuh25837f22021-06-27 15:49:14 -07008#include <opencv2/core/eigen.hpp>
9#include <opencv2/highgui/highgui.hpp>
10#include <opencv2/imgproc.hpp>
Austin Schuhdcb6b362022-02-25 18:06:21 -080011
Austin Schuh25837f22021-06-27 15:49:14 -070012#include "aos/events/event_loop.h"
13#include "aos/flatbuffers.h"
14#include "aos/network/team_number.h"
15#include "frc971/control_loops/quaternion_utils.h"
Jim Ostrowski977850f2022-01-22 21:04:22 -080016#include "frc971/vision/vision_generated.h"
Austin Schuh25837f22021-06-27 15:49:14 -070017
Austin Schuh25837f22021-06-27 15:49:14 -070018DEFINE_string(board_template_path, "",
19 "If specified, write an image to the specified path for the "
20 "charuco board pattern.");
Jim Ostrowskib3cab972022-12-03 15:47:00 -080021DEFINE_bool(coarse_pattern, true, "If true, use coarse arucos; else, use fine");
Jim Ostrowski814d2812022-12-11 23:17:14 -080022DEFINE_uint32(gray_threshold, 0,
23 "If > 0, threshold image based on this grayscale value");
Jim Ostrowskib3cab972022-12-03 15:47:00 -080024DEFINE_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 Ostrowski2f2685f2023-03-25 11:57:54 -070028DEFINE_uint32(min_id, 0, "Minimum valid charuco id");
29DEFINE_uint32(max_diamonds, 0,
30 "Maximum number of diamonds to see. Set to 0 for no limit");
31DEFINE_uint32(max_id, 15, "Maximum valid charuco id");
Jim Ostrowskib3cab972022-12-03 15:47:00 -080032DEFINE_bool(visualize, false, "Whether to visualize the resulting data.");
Jim Ostrowski814d2812022-12-11 23:17:14 -080033DEFINE_bool(
34 draw_axes, false,
35 "Whether to draw axes on the resulting data-- warning, may cause crashes.");
Austin Schuh25837f22021-06-27 15:49:14 -070036
Austin Schuhc3419862023-01-08 13:54:36 -080037DEFINE_uint32(disable_delay, 100, "Time after an issue to disable tracing at.");
38
39DECLARE_bool(enable_ftrace);
40
Stephan Pleinesf63bde82024-01-13 15:59:33 -080041namespace frc971::vision {
Austin Schuh25837f22021-06-27 15:49:14 -070042namespace chrono = std::chrono;
Austin Schuhea7b0142021-10-08 22:04:53 -070043using aos::monotonic_clock;
Austin Schuh25837f22021-06-27 15:49:14 -070044
45CameraCalibration::CameraCalibration(
James Kuszmaul7e958812023-02-11 15:34:31 -080046 const calibration::CameraCalibration *calibration)
47 : intrinsics_([calibration]() {
48 const cv::Mat result(3, 3, CV_32F,
49 const_cast<void *>(static_cast<const void *>(
50 calibration->intrinsics()->data())));
51 CHECK_EQ(result.total(), calibration->intrinsics()->size());
52 return result;
53 }()),
54 intrinsics_eigen_([this]() {
55 cv::Mat camera_intrinsics = intrinsics_;
56 Eigen::Matrix3d result;
57 cv::cv2eigen(camera_intrinsics, result);
58 return result;
59 }()),
60 dist_coeffs_([calibration]() {
61 const cv::Mat result(5, 1, CV_32F,
62 const_cast<void *>(static_cast<const void *>(
63 calibration->dist_coeffs()->data())));
64 CHECK_EQ(result.total(), calibration->dist_coeffs()->size());
65 return result;
66 }()) {}
Austin Schuh25837f22021-06-27 15:49:14 -070067
Austin Schuhea7b0142021-10-08 22:04:53 -070068ImageCallback::ImageCallback(
69 aos::EventLoop *event_loop, std::string_view channel,
milind-u0cb53112023-02-03 20:32:55 -080070 std::function<void(cv::Mat, monotonic_clock::time_point)> &&handle_image_fn,
71 monotonic_clock::duration max_age)
Austin Schuhea7b0142021-10-08 22:04:53 -070072 : event_loop_(event_loop),
73 server_fetcher_(
74 event_loop_->MakeFetcher<aos::message_bridge::ServerStatistics>(
75 "/aos")),
76 source_node_(aos::configuration::GetNode(
77 event_loop_->configuration(),
78 event_loop_->GetChannel<CameraImage>(channel)
79 ->source_node()
80 ->string_view())),
Austin Schuhc3419862023-01-08 13:54:36 -080081 handle_image_(std::move(handle_image_fn)),
milind-u0cb53112023-02-03 20:32:55 -080082 timer_fn_(event_loop->AddTimer([this]() { DisableTracing(); })),
83 max_age_(max_age) {
Austin Schuh25837f22021-06-27 15:49:14 -070084 event_loop_->MakeWatcher(channel, [this](const CameraImage &image) {
Austin Schuhea7b0142021-10-08 22:04:53 -070085 const monotonic_clock::time_point eof_source_node =
86 monotonic_clock::time_point(
87 chrono::nanoseconds(image.monotonic_timestamp_ns()));
Austin Schuhea7b0142021-10-08 22:04:53 -070088 chrono::nanoseconds offset{0};
89 if (source_node_ != event_loop_->node()) {
Austin Schuhee8bc1e2021-11-20 16:23:41 -080090 server_fetcher_.Fetch();
91 if (!server_fetcher_.get()) {
92 return;
93 }
94
Austin Schuhea7b0142021-10-08 22:04:53 -070095 // If we are viewing this image from another node, convert to our
96 // monotonic clock.
97 const aos::message_bridge::ServerConnection *server_connection = nullptr;
98
99 for (const aos::message_bridge::ServerConnection *connection :
100 *server_fetcher_->connections()) {
101 CHECK(connection->has_node());
102 if (connection->node()->name()->string_view() ==
103 source_node_->name()->string_view()) {
104 server_connection = connection;
105 break;
106 }
107 }
108
109 CHECK(server_connection != nullptr) << ": Failed to find client";
110 if (!server_connection->has_monotonic_offset()) {
111 VLOG(1) << "No offset yet.";
112 return;
113 }
114 offset = chrono::nanoseconds(server_connection->monotonic_offset());
115 }
116
117 const monotonic_clock::time_point eof = eof_source_node - offset;
118
Jim Ostrowski977850f2022-01-22 21:04:22 -0800119 const monotonic_clock::duration age = event_loop_->monotonic_now() - eof;
Austin Schuh25837f22021-06-27 15:49:14 -0700120 const double age_double =
121 std::chrono::duration_cast<std::chrono::duration<double>>(age).count();
milind-u0cb53112023-02-03 20:32:55 -0800122 if (age > max_age_) {
Austin Schuhc3419862023-01-08 13:54:36 -0800123 if (FLAGS_enable_ftrace) {
124 ftrace_.FormatMessage("Too late receiving image, age: %f\n",
125 age_double);
126 if (FLAGS_disable_delay > 0) {
127 if (!disabling_) {
Philipp Schradera6712522023-07-05 20:25:11 -0700128 timer_fn_->Schedule(event_loop_->monotonic_now() +
129 chrono::milliseconds(FLAGS_disable_delay));
Austin Schuhc3419862023-01-08 13:54:36 -0800130 disabling_ = true;
131 }
132 } else {
133 DisableTracing();
134 }
135 }
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800136 VLOG(2) << "Age: " << age_double << ", getting behind, skipping";
Austin Schuh25837f22021-06-27 15:49:14 -0700137 return;
138 }
139 // Create color image:
140 cv::Mat image_color_mat(cv::Size(image.cols(), image.rows()), CV_8UC2,
141 (void *)image.data()->data());
142 const cv::Size image_size(image.cols(), image.rows());
Austin Schuhac402e92023-01-08 13:56:20 -0800143 switch (format_) {
144 case Format::GRAYSCALE: {
145 ftrace_.FormatMessage("Starting yuyv->greyscale\n");
146 cv::Mat gray_image(image_size, CV_8UC3);
147 cv::cvtColor(image_color_mat, gray_image, cv::COLOR_YUV2GRAY_YUYV);
148 handle_image_(gray_image, eof);
149 } break;
150 case Format::BGR: {
151 cv::Mat rgb_image(image_size, CV_8UC3);
152 cv::cvtColor(image_color_mat, rgb_image, cv::COLOR_YUV2BGR_YUYV);
153 handle_image_(rgb_image, eof);
154 } break;
155 case Format::YUYV2: {
156 handle_image_(image_color_mat, eof);
157 };
158 }
Austin Schuh25837f22021-06-27 15:49:14 -0700159 });
160}
161
Austin Schuhc3419862023-01-08 13:54:36 -0800162void ImageCallback::DisableTracing() {
163 disabling_ = false;
164 ftrace_.TurnOffOrDie();
165}
166
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800167void CharucoExtractor::SetupTargetData() {
Jim Ostrowski814d2812022-12-11 23:17:14 -0800168 marker_length_ = 0.146;
169 square_length_ = 0.2;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800170
171 // Only charuco board has a board associated with it
172 board_ = static_cast<cv::Ptr<cv::aruco::CharucoBoard>>(NULL);
173
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800174 if (target_type_ == TargetType::kCharuco ||
175 target_type_ == TargetType::kAruco) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800176 dictionary_ = cv::aruco::getPredefinedDictionary(
177 FLAGS_large_board ? cv::aruco::DICT_5X5_250 : cv::aruco::DICT_6X6_250);
178
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800179 if (target_type_ == TargetType::kCharuco) {
Jim Ostrowski814d2812022-12-11 23:17:14 -0800180 LOG(INFO) << "Using " << (FLAGS_large_board ? "large" : "small")
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800181 << " charuco board with "
182 << (FLAGS_coarse_pattern ? "coarse" : "fine") << " pattern";
183 board_ =
184 (FLAGS_large_board
185 ? (FLAGS_coarse_pattern ? cv::aruco::CharucoBoard::create(
186 12, 9, 0.06, 0.04666, dictionary_)
187 : cv::aruco::CharucoBoard::create(
188 25, 18, 0.03, 0.0233, dictionary_))
189 : (FLAGS_coarse_pattern ? cv::aruco::CharucoBoard::create(
190 7, 5, 0.04, 0.025, dictionary_)
191 // TODO(jim): Need to figure out what
192 // size is for small board, fine pattern
193 : cv::aruco::CharucoBoard::create(
194 7, 5, 0.03, 0.0233, dictionary_)));
195 if (!FLAGS_board_template_path.empty()) {
196 cv::Mat board_image;
197 board_->draw(cv::Size(600, 500), board_image, 10, 1);
198 cv::imwrite(FLAGS_board_template_path, board_image);
199 }
200 }
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800201 } else if (target_type_ == TargetType::kCharucoDiamond) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800202 marker_length_ = 0.15;
Jim Ostrowski814d2812022-12-11 23:17:14 -0800203 square_length_ = 0.2;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800204 dictionary_ = cv::aruco::getPredefinedDictionary(cv::aruco::DICT_4X4_250);
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700205 } else if (target_type_ == TargetType::kAprilTag) {
206 marker_length_ = 0.1016;
207 square_length_ = 0.1524;
208 dictionary_ =
209 cv::aruco::getPredefinedDictionary(cv::aruco::DICT_APRILTAG_16h5);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800210 } else {
211 // Bail out if it's not a supported target
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800212 LOG(FATAL) << "Target type undefined: "
213 << static_cast<uint8_t>(target_type_);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800214 }
215}
216
217void CharucoExtractor::DrawTargetPoses(cv::Mat rgb_image,
218 std::vector<cv::Vec3d> rvecs,
219 std::vector<cv::Vec3d> tvecs) {
220 const Eigen::Matrix<double, 3, 4> camera_projection =
221 Eigen::Matrix<double, 3, 4>::Identity();
222
223 int x_coord = 10;
224 int y_coord = 0;
225 // draw axis for each marker
226 for (uint i = 0; i < rvecs.size(); i++) {
227 Eigen::Vector3d rvec_eigen, tvec_eigen;
228 cv::cv2eigen(rvecs[i], rvec_eigen);
229 cv::cv2eigen(tvecs[i], tvec_eigen);
230
231 Eigen::Quaternion<double> rotation(
232 frc971::controls::ToQuaternionFromRotationVector(rvec_eigen));
233 Eigen::Translation3d translation(tvec_eigen);
234
235 const Eigen::Affine3d board_to_camera = translation * rotation;
236
James Kuszmaul7e958812023-02-11 15:34:31 -0800237 Eigen::Vector3d result = calibration_.CameraIntrinsicsEigen() *
238 camera_projection * board_to_camera *
239 Eigen::Vector3d::Zero();
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800240
241 // Found that drawAxis hangs if you try to draw with z values too
242 // small (trying to draw axes at inifinity)
Jim Ostrowski814d2812022-12-11 23:17:14 -0800243 // TODO<Jim>: Either track this down or reimplement drawAxes
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800244 if (result.z() < 0.01) {
245 LOG(INFO) << "Skipping, due to z value too small: " << result.z();
Jim Ostrowski814d2812022-12-11 23:17:14 -0800246 } else if (FLAGS_draw_axes == true) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800247 result /= result.z();
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700248 if (target_type_ == TargetType::kCharuco ||
249 target_type_ == TargetType::kAprilTag) {
Austin Schuhbffbe8b2023-11-22 21:32:05 -0800250 cv::drawFrameAxes(rgb_image, calibration_.CameraIntrinsics(),
251 calibration_.CameraDistCoeffs(), rvecs[i], tvecs[i],
252 square_length_);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800253 } else {
James Kuszmaul7e958812023-02-11 15:34:31 -0800254 cv::drawFrameAxes(rgb_image, calibration_.CameraIntrinsics(),
255 calibration_.CameraDistCoeffs(), rvecs[i], tvecs[i],
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700256 square_length_);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800257 }
258 }
259 std::stringstream ss;
260 ss << "tvec[" << i << "] = " << tvecs[i];
261 y_coord += 25;
262 cv::putText(rgb_image, ss.str(), cv::Point(x_coord, y_coord),
263 cv::FONT_HERSHEY_PLAIN, 1.0, cv::Scalar(255, 255, 255));
264 ss.str("");
265 ss << "rvec[" << i << "] = " << rvecs[i];
266 y_coord += 25;
267 cv::putText(rgb_image, ss.str(), cv::Point(x_coord, y_coord),
268 cv::FONT_HERSHEY_PLAIN, 1.0, cv::Scalar(255, 255, 255));
269 }
270}
271
272void CharucoExtractor::PackPoseResults(
273 std::vector<cv::Vec3d> &rvecs, std::vector<cv::Vec3d> &tvecs,
274 std::vector<Eigen::Vector3d> *rvecs_eigen,
275 std::vector<Eigen::Vector3d> *tvecs_eigen) {
276 for (cv::Vec3d rvec : rvecs) {
277 Eigen::Vector3d rvec_eigen = Eigen::Vector3d::Zero();
278 cv::cv2eigen(rvec, rvec_eigen);
279 rvecs_eigen->emplace_back(rvec_eigen);
280 }
281
282 for (cv::Vec3d tvec : tvecs) {
283 Eigen::Vector3d tvec_eigen = Eigen::Vector3d::Zero();
284 cv::cv2eigen(tvec, tvec_eigen);
285 tvecs_eigen->emplace_back(tvec_eigen);
286 }
287}
288
Austin Schuh25837f22021-06-27 15:49:14 -0700289CharucoExtractor::CharucoExtractor(
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700290 const calibration::CameraCalibration *calibration,
291 const TargetType target_type)
292 : event_loop_(nullptr),
293 target_type_(target_type),
294 calibration_(CHECK_NOTNULL(calibration)) {
295 VLOG(2) << "Configuring CharucoExtractor without event_loop";
296 SetupTargetData();
297 VLOG(2) << "Camera matrix:\n" << calibration_.CameraIntrinsics();
298 VLOG(2) << "Distortion Coefficients:\n" << calibration_.CameraDistCoeffs();
299}
300
301CharucoExtractor::CharucoExtractor(
James Kuszmaul7e958812023-02-11 15:34:31 -0800302 aos::EventLoop *event_loop,
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700303 const calibration::CameraCalibration *calibration,
304 const TargetType target_type, std::string_view image_channel,
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800305 std::function<void(cv::Mat, monotonic_clock::time_point,
306 std::vector<cv::Vec4i>,
307 std::vector<std::vector<cv::Point2f>>, bool,
308 std::vector<Eigen::Vector3d>,
309 std::vector<Eigen::Vector3d>)> &&handle_charuco_fn)
Austin Schuhea7b0142021-10-08 22:04:53 -0700310 : event_loop_(event_loop),
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800311 target_type_(target_type),
312 image_channel_(image_channel),
James Kuszmaul7e958812023-02-11 15:34:31 -0800313 calibration_(CHECK_NOTNULL(calibration)),
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800314 handle_charuco_(std::move(handle_charuco_fn)) {
315 SetupTargetData();
Austin Schuh25837f22021-06-27 15:49:14 -0700316
James Kuszmaul7e958812023-02-11 15:34:31 -0800317 LOG(INFO) << "Camera matrix " << calibration_.CameraIntrinsics();
318 LOG(INFO) << "Distortion Coefficients " << calibration_.CameraDistCoeffs();
Austin Schuh25837f22021-06-27 15:49:14 -0700319
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800320 LOG(INFO) << "Connecting to channel " << image_channel_;
Austin Schuh25837f22021-06-27 15:49:14 -0700321}
322
Austin Schuhea7b0142021-10-08 22:04:53 -0700323void CharucoExtractor::HandleImage(cv::Mat rgb_image,
324 const monotonic_clock::time_point eof) {
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700325 // Set up the variables we'll use in the callback function
326 bool valid = false;
327 // ids and corners for final, refined board / marker detections
328 // Using Vec4i type since it supports Charuco Diamonds
329 // And overloading it using 1st int in Vec4i for others target types
330 std::vector<cv::Vec4i> result_ids;
331 std::vector<std::vector<cv::Point2f>> result_corners;
332
333 // Return a list of poses; for Charuco Board there will be just one
334 std::vector<Eigen::Vector3d> rvecs_eigen;
335 std::vector<Eigen::Vector3d> tvecs_eigen;
336 ProcessImage(rgb_image, eof, event_loop_->monotonic_now(), result_ids,
337 result_corners, valid, rvecs_eigen, tvecs_eigen);
338
339 handle_charuco_(rgb_image, eof, result_ids, result_corners, valid,
340 rvecs_eigen, tvecs_eigen);
341}
342
343void CharucoExtractor::ProcessImage(
344 cv::Mat rgb_image, const monotonic_clock::time_point eof,
345 const monotonic_clock::time_point current_time,
346 std::vector<cv::Vec4i> &result_ids,
347 std::vector<std::vector<cv::Point2f>> &result_corners, bool &valid,
348 std::vector<Eigen::Vector3d> &rvecs_eigen,
349 std::vector<Eigen::Vector3d> &tvecs_eigen) {
Austin Schuhea7b0142021-10-08 22:04:53 -0700350 const double age_double =
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700351 std::chrono::duration_cast<std::chrono::duration<double>>(current_time -
352 eof)
Austin Schuhea7b0142021-10-08 22:04:53 -0700353 .count();
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800354
Jim Ostrowski814d2812022-12-11 23:17:14 -0800355 // Have found this useful if there is blurry / noisy images
356 if (FLAGS_gray_threshold > 0) {
357 cv::Mat gray;
358 cv::cvtColor(rgb_image, gray, cv::COLOR_BGR2GRAY);
359
360 cv::Mat thresh;
361 cv::threshold(gray, thresh, FLAGS_gray_threshold, 255, cv::THRESH_BINARY);
362 cv::cvtColor(thresh, rgb_image, cv::COLOR_GRAY2RGB);
363 }
364
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800365 // ids and corners for initial aruco marker detections
Austin Schuh25837f22021-06-27 15:49:14 -0700366 std::vector<int> marker_ids;
367 std::vector<std::vector<cv::Point2f>> marker_corners;
368
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800369 // Do initial marker detection; this is the same for all target types
370 cv::aruco::detectMarkers(rgb_image, dictionary_, marker_corners, marker_ids);
371 cv::aruco::drawDetectedMarkers(rgb_image, marker_corners, marker_ids);
Austin Schuhea7b0142021-10-08 22:04:53 -0700372
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800373 VLOG(2) << "Handle Image, with target type = "
374 << static_cast<uint8_t>(target_type_) << " and " << marker_ids.size()
375 << " markers detected initially";
Austin Schuh25837f22021-06-27 15:49:14 -0700376
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800377 if (marker_ids.size() == 0) {
378 VLOG(2) << "Didn't find any markers";
379 } else {
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800380 if (target_type_ == TargetType::kCharuco) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800381 std::vector<int> charuco_ids;
382 std::vector<cv::Point2f> charuco_corners;
Austin Schuh25837f22021-06-27 15:49:14 -0700383
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800384 // If enough aruco markers detected for the Charuco board
385 if (marker_ids.size() >= FLAGS_min_charucos) {
386 // Run everything twice, once with the calibration, and once
387 // without. This lets us both collect data to calibrate the
388 // intrinsics of the camera (to determine the intrinsics from
389 // multiple samples), and also to use data from a previous/stored
390 // calibration to determine a more accurate pose in real time (used
391 // for extrinsics calibration)
392 cv::aruco::interpolateCornersCharuco(marker_corners, marker_ids,
393 rgb_image, board_, charuco_corners,
394 charuco_ids);
Austin Schuh25837f22021-06-27 15:49:14 -0700395
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800396 std::vector<cv::Point2f> charuco_corners_with_calibration;
397 std::vector<int> charuco_ids_with_calibration;
Austin Schuh25837f22021-06-27 15:49:14 -0700398
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800399 // This call uses a previous intrinsic calibration to get more
400 // accurate marker locations, for a better pose estimate
401 cv::aruco::interpolateCornersCharuco(
402 marker_corners, marker_ids, rgb_image, board_,
403 charuco_corners_with_calibration, charuco_ids_with_calibration,
James Kuszmaul7e958812023-02-11 15:34:31 -0800404 calibration_.CameraIntrinsics(), calibration_.CameraDistCoeffs());
Austin Schuh25837f22021-06-27 15:49:14 -0700405
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800406 if (charuco_ids.size() >= FLAGS_min_charucos) {
407 cv::aruco::drawDetectedCornersCharuco(
408 rgb_image, charuco_corners, charuco_ids, cv::Scalar(255, 0, 0));
Austin Schuh25837f22021-06-27 15:49:14 -0700409
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800410 cv::Vec3d rvec, tvec;
411 valid = cv::aruco::estimatePoseCharucoBoard(
412 charuco_corners_with_calibration, charuco_ids_with_calibration,
James Kuszmaul7e958812023-02-11 15:34:31 -0800413 board_, calibration_.CameraIntrinsics(),
414 calibration_.CameraDistCoeffs(), rvec, tvec);
Austin Schuh25837f22021-06-27 15:49:14 -0700415
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800416 // if charuco pose is valid, return pose, with ids and corners
417 if (valid) {
418 std::vector<cv::Vec3d> rvecs, tvecs;
419 rvecs.emplace_back(rvec);
420 tvecs.emplace_back(tvec);
421 DrawTargetPoses(rgb_image, rvecs, tvecs);
Austin Schuh25837f22021-06-27 15:49:14 -0700422
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800423 PackPoseResults(rvecs, tvecs, &rvecs_eigen, &tvecs_eigen);
424 // Store the corners without calibration, since we use them to
425 // do calibration
426 result_corners.emplace_back(charuco_corners);
427 for (auto id : charuco_ids) {
428 result_ids.emplace_back(cv::Vec4i{id, 0, 0, 0});
429 }
430 } else {
431 VLOG(2) << "Age: " << age_double << ", invalid charuco board pose";
432 }
Jim Ostrowski634b2652022-03-04 02:10:53 -0800433 } else {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800434 VLOG(2) << "Age: " << age_double << ", not enough charuco IDs, got "
435 << charuco_ids.size() << ", needed " << FLAGS_min_charucos;
Jim Ostrowski634b2652022-03-04 02:10:53 -0800436 }
Austin Schuh25837f22021-06-27 15:49:14 -0700437 } else {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800438 VLOG(2) << "Age: " << age_double
439 << ", not enough marker IDs for charuco board, got "
440 << marker_ids.size() << ", needed " << FLAGS_min_charucos;
441 }
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700442 } else if (target_type_ == TargetType::kAruco ||
443 target_type_ == TargetType::kAprilTag) {
milind-u09fb1252023-01-28 19:21:41 -0800444 // estimate pose for arucos doesn't return valid, so marking true
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800445 valid = true;
446 std::vector<cv::Vec3d> rvecs, tvecs;
James Kuszmaul7e958812023-02-11 15:34:31 -0800447 cv::aruco::estimatePoseSingleMarkers(
448 marker_corners, square_length_, calibration_.CameraIntrinsics(),
449 calibration_.CameraDistCoeffs(), rvecs, tvecs);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800450 DrawTargetPoses(rgb_image, rvecs, tvecs);
451
452 PackPoseResults(rvecs, tvecs, &rvecs_eigen, &tvecs_eigen);
453 for (uint i = 0; i < marker_ids.size(); i++) {
454 result_ids.emplace_back(cv::Vec4i{marker_ids[i], 0, 0, 0});
455 }
456 result_corners = marker_corners;
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800457 } else if (target_type_ == TargetType::kCharucoDiamond) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800458 // Extract the diamonds associated with the markers
459 std::vector<cv::Vec4i> diamond_ids;
460 std::vector<std::vector<cv::Point2f>> diamond_corners;
461 cv::aruco::detectCharucoDiamond(rgb_image, marker_corners, marker_ids,
462 square_length_ / marker_length_,
463 diamond_corners, diamond_ids);
464
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700465 // Check that we have an acceptable number of diamonds detected.
466 // Should be at least one, and no more than FLAGS_max_diamonds.
467 // Different calibration routines will require different values for this
468 if (diamond_ids.size() > 0 &&
469 (FLAGS_max_diamonds == 0 ||
470 diamond_ids.size() <= FLAGS_max_diamonds)) {
471 // TODO<Jim>: Could probably make this check more general than
472 // requiring range of ids
Jim Ostrowskic7d90102023-03-09 14:47:25 -0800473 bool all_valid_ids = true;
474 for (uint i = 0; i < 4; i++) {
475 uint id = diamond_ids[0][i];
476 if ((id < FLAGS_min_id) || (id > FLAGS_max_id)) {
477 all_valid_ids = false;
478 LOG(INFO) << "Got invalid charuco id: " << id;
479 }
480 }
481 if (all_valid_ids) {
482 cv::aruco::drawDetectedDiamonds(rgb_image, diamond_corners,
483 diamond_ids);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800484
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700485 // estimate pose for diamonds doesn't return valid, so marking
486 // true
Jim Ostrowskic7d90102023-03-09 14:47:25 -0800487 valid = true;
488 std::vector<cv::Vec3d> rvecs, tvecs;
489 cv::aruco::estimatePoseSingleMarkers(
490 diamond_corners, square_length_, calibration_.CameraIntrinsics(),
491 calibration_.CameraDistCoeffs(), rvecs, tvecs);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800492
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700493 DrawTargetPoses(rgb_image, rvecs, tvecs);
Jim Ostrowskic7d90102023-03-09 14:47:25 -0800494 PackPoseResults(rvecs, tvecs, &rvecs_eigen, &tvecs_eigen);
495 result_ids = diamond_ids;
496 result_corners = diamond_corners;
497 } else {
498 LOG(INFO) << "Not all charuco ids were valid, so skipping";
499 }
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800500 } else {
Jim Ostrowskic7d90102023-03-09 14:47:25 -0800501 if (diamond_ids.size() == 0) {
502 // OK to not see any markers sometimes
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700503 VLOG(2) << "Found aruco markers, but no valid charuco diamond "
504 "targets";
Jim Ostrowskic7d90102023-03-09 14:47:25 -0800505 } else {
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700506 VLOG(2) << "Found too many number of diamond markers, which likely "
507 "means false positives were detected: "
508 << diamond_ids.size() << " > " << FLAGS_max_diamonds;
Jim Ostrowskic7d90102023-03-09 14:47:25 -0800509 }
Austin Schuh25837f22021-06-27 15:49:14 -0700510 }
511 } else {
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800512 LOG(FATAL) << "Unknown target type: "
513 << static_cast<uint8_t>(target_type_);
Austin Schuh25837f22021-06-27 15:49:14 -0700514 }
Austin Schuh25837f22021-06-27 15:49:14 -0700515 }
Austin Schuh25837f22021-06-27 15:49:14 -0700516}
517
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800518flatbuffers::Offset<foxglove::ImageAnnotations> BuildAnnotations(
Jim Ostrowski5e2c5e62023-02-26 12:52:56 -0800519 flatbuffers::FlatBufferBuilder *fbb,
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800520 const aos::monotonic_clock::time_point monotonic_now,
Jim Ostrowski5e2c5e62023-02-26 12:52:56 -0800521 const std::vector<std::vector<cv::Point2f>> &corners,
522 const std::vector<double> rgba_color, const double thickness,
523 const foxglove::PointsAnnotationType line_type) {
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800524 std::vector<flatbuffers::Offset<foxglove::PointsAnnotation>> rectangles;
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800525 for (const std::vector<cv::Point2f> &rectangle : corners) {
Jim Ostrowski5e2c5e62023-02-26 12:52:56 -0800526 rectangles.push_back(BuildPointsAnnotation(
527 fbb, monotonic_now, rectangle, rgba_color, thickness, line_type));
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800528 }
529
530 const auto rectangles_offset = fbb->CreateVector(rectangles);
531 foxglove::ImageAnnotations::Builder annotation_builder(*fbb);
532 annotation_builder.add_points(rectangles_offset);
533 return annotation_builder.Finish();
534}
535
Jim Ostrowski5e2c5e62023-02-26 12:52:56 -0800536flatbuffers::Offset<foxglove::PointsAnnotation> BuildPointsAnnotation(
537 flatbuffers::FlatBufferBuilder *fbb,
538 const aos::monotonic_clock::time_point monotonic_now,
539 const std::vector<cv::Point2f> &corners,
540 const std::vector<double> rgba_color, const double thickness,
541 const foxglove::PointsAnnotationType line_type) {
542 const struct timespec now_t = aos::time::to_timespec(monotonic_now);
543 foxglove::Time time{static_cast<uint32_t>(now_t.tv_sec),
544 static_cast<uint32_t>(now_t.tv_nsec)};
545 const flatbuffers::Offset<foxglove::Color> color_offset =
546 foxglove::CreateColor(*fbb, rgba_color[0], rgba_color[1], rgba_color[2],
547 rgba_color[3]);
548 std::vector<flatbuffers::Offset<foxglove::Point2>> points_offsets;
549 for (const cv::Point2f &point : corners) {
550 points_offsets.push_back(foxglove::CreatePoint2(*fbb, point.x, point.y));
551 }
552 const flatbuffers::Offset<
553 flatbuffers::Vector<flatbuffers::Offset<foxglove::Point2>>>
554 points_offset = fbb->CreateVector(points_offsets);
555 std::vector<flatbuffers::Offset<foxglove::Color>> color_offsets(
556 points_offsets.size(), color_offset);
557 auto colors_offset = fbb->CreateVector(color_offsets);
558 foxglove::PointsAnnotation::Builder points_builder(*fbb);
559 points_builder.add_timestamp(&time);
560 points_builder.add_type(line_type);
561 points_builder.add_points(points_offset);
562 points_builder.add_outline_color(color_offset);
563 points_builder.add_outline_colors(colors_offset);
564 points_builder.add_thickness(thickness);
565
566 return points_builder.Finish();
567}
568
James Kuszmauld6199be2023-02-11 19:56:28 -0800569TargetType TargetTypeFromString(std::string_view str) {
570 if (str == "aruco") {
571 return TargetType::kAruco;
572 } else if (str == "charuco") {
573 return TargetType::kCharuco;
574 } else if (str == "charuco_diamond") {
575 return TargetType::kCharucoDiamond;
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700576 } else if (str == "apriltag") {
577 return TargetType::kAprilTag;
James Kuszmauld6199be2023-02-11 19:56:28 -0800578 } else {
579 LOG(FATAL) << "Unknown target type: " << str
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700580 << ", expected: apriltag|aruco|charuco|charuco_diamond";
James Kuszmauld6199be2023-02-11 19:56:28 -0800581 }
582}
583
584std::ostream &operator<<(std::ostream &os, TargetType target_type) {
585 switch (target_type) {
586 case TargetType::kAruco:
587 os << "aruco";
588 break;
589 case TargetType::kCharuco:
590 os << "charuco";
591 break;
592 case TargetType::kCharucoDiamond:
593 os << "charuco_diamond";
594 break;
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700595 case TargetType::kAprilTag:
596 os << "apriltag";
597 break;
James Kuszmauld6199be2023-02-11 19:56:28 -0800598 }
599 return os;
600}
601
Stephan Pleinesf63bde82024-01-13 15:59:33 -0800602} // namespace frc971::vision