blob: b8edcae0016a65b13fcee6ba76629c1928fa651d [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
Austin Schuh25837f22021-06-27 15:49:14 -070041namespace frc971 {
42namespace vision {
43namespace chrono = std::chrono;
Austin Schuhea7b0142021-10-08 22:04:53 -070044using aos::monotonic_clock;
Austin Schuh25837f22021-06-27 15:49:14 -070045
46CameraCalibration::CameraCalibration(
James Kuszmaul7e958812023-02-11 15:34:31 -080047 const calibration::CameraCalibration *calibration)
48 : intrinsics_([calibration]() {
49 const cv::Mat result(3, 3, CV_32F,
50 const_cast<void *>(static_cast<const void *>(
51 calibration->intrinsics()->data())));
52 CHECK_EQ(result.total(), calibration->intrinsics()->size());
53 return result;
54 }()),
55 intrinsics_eigen_([this]() {
56 cv::Mat camera_intrinsics = intrinsics_;
57 Eigen::Matrix3d result;
58 cv::cv2eigen(camera_intrinsics, result);
59 return result;
60 }()),
61 dist_coeffs_([calibration]() {
62 const cv::Mat result(5, 1, CV_32F,
63 const_cast<void *>(static_cast<const void *>(
64 calibration->dist_coeffs()->data())));
65 CHECK_EQ(result.total(), calibration->dist_coeffs()->size());
66 return result;
67 }()) {}
Austin Schuh25837f22021-06-27 15:49:14 -070068
Austin Schuhea7b0142021-10-08 22:04:53 -070069ImageCallback::ImageCallback(
70 aos::EventLoop *event_loop, std::string_view channel,
milind-u0cb53112023-02-03 20:32:55 -080071 std::function<void(cv::Mat, monotonic_clock::time_point)> &&handle_image_fn,
72 monotonic_clock::duration max_age)
Austin Schuhea7b0142021-10-08 22:04:53 -070073 : event_loop_(event_loop),
74 server_fetcher_(
75 event_loop_->MakeFetcher<aos::message_bridge::ServerStatistics>(
76 "/aos")),
77 source_node_(aos::configuration::GetNode(
78 event_loop_->configuration(),
79 event_loop_->GetChannel<CameraImage>(channel)
80 ->source_node()
81 ->string_view())),
Austin Schuhc3419862023-01-08 13:54:36 -080082 handle_image_(std::move(handle_image_fn)),
milind-u0cb53112023-02-03 20:32:55 -080083 timer_fn_(event_loop->AddTimer([this]() { DisableTracing(); })),
84 max_age_(max_age) {
Austin Schuh25837f22021-06-27 15:49:14 -070085 event_loop_->MakeWatcher(channel, [this](const CameraImage &image) {
Austin Schuhea7b0142021-10-08 22:04:53 -070086 const monotonic_clock::time_point eof_source_node =
87 monotonic_clock::time_point(
88 chrono::nanoseconds(image.monotonic_timestamp_ns()));
Austin Schuhea7b0142021-10-08 22:04:53 -070089 chrono::nanoseconds offset{0};
90 if (source_node_ != event_loop_->node()) {
Austin Schuhee8bc1e2021-11-20 16:23:41 -080091 server_fetcher_.Fetch();
92 if (!server_fetcher_.get()) {
93 return;
94 }
95
Austin Schuhea7b0142021-10-08 22:04:53 -070096 // If we are viewing this image from another node, convert to our
97 // monotonic clock.
98 const aos::message_bridge::ServerConnection *server_connection = nullptr;
99
100 for (const aos::message_bridge::ServerConnection *connection :
101 *server_fetcher_->connections()) {
102 CHECK(connection->has_node());
103 if (connection->node()->name()->string_view() ==
104 source_node_->name()->string_view()) {
105 server_connection = connection;
106 break;
107 }
108 }
109
110 CHECK(server_connection != nullptr) << ": Failed to find client";
111 if (!server_connection->has_monotonic_offset()) {
112 VLOG(1) << "No offset yet.";
113 return;
114 }
115 offset = chrono::nanoseconds(server_connection->monotonic_offset());
116 }
117
118 const monotonic_clock::time_point eof = eof_source_node - offset;
119
Jim Ostrowski977850f2022-01-22 21:04:22 -0800120 const monotonic_clock::duration age = event_loop_->monotonic_now() - eof;
Austin Schuh25837f22021-06-27 15:49:14 -0700121 const double age_double =
122 std::chrono::duration_cast<std::chrono::duration<double>>(age).count();
milind-u0cb53112023-02-03 20:32:55 -0800123 if (age > max_age_) {
Austin Schuhc3419862023-01-08 13:54:36 -0800124 if (FLAGS_enable_ftrace) {
125 ftrace_.FormatMessage("Too late receiving image, age: %f\n",
126 age_double);
127 if (FLAGS_disable_delay > 0) {
128 if (!disabling_) {
Philipp Schradera6712522023-07-05 20:25:11 -0700129 timer_fn_->Schedule(event_loop_->monotonic_now() +
130 chrono::milliseconds(FLAGS_disable_delay));
Austin Schuhc3419862023-01-08 13:54:36 -0800131 disabling_ = true;
132 }
133 } else {
134 DisableTracing();
135 }
136 }
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800137 VLOG(2) << "Age: " << age_double << ", getting behind, skipping";
Austin Schuh25837f22021-06-27 15:49:14 -0700138 return;
139 }
140 // Create color image:
141 cv::Mat image_color_mat(cv::Size(image.cols(), image.rows()), CV_8UC2,
142 (void *)image.data()->data());
143 const cv::Size image_size(image.cols(), image.rows());
Austin Schuhac402e92023-01-08 13:56:20 -0800144 switch (format_) {
145 case Format::GRAYSCALE: {
146 ftrace_.FormatMessage("Starting yuyv->greyscale\n");
147 cv::Mat gray_image(image_size, CV_8UC3);
148 cv::cvtColor(image_color_mat, gray_image, cv::COLOR_YUV2GRAY_YUYV);
149 handle_image_(gray_image, eof);
150 } break;
151 case Format::BGR: {
152 cv::Mat rgb_image(image_size, CV_8UC3);
153 cv::cvtColor(image_color_mat, rgb_image, cv::COLOR_YUV2BGR_YUYV);
154 handle_image_(rgb_image, eof);
155 } break;
156 case Format::YUYV2: {
157 handle_image_(image_color_mat, eof);
158 };
159 }
Austin Schuh25837f22021-06-27 15:49:14 -0700160 });
161}
162
Austin Schuhc3419862023-01-08 13:54:36 -0800163void ImageCallback::DisableTracing() {
164 disabling_ = false;
165 ftrace_.TurnOffOrDie();
166}
167
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800168void CharucoExtractor::SetupTargetData() {
Jim Ostrowski814d2812022-12-11 23:17:14 -0800169 marker_length_ = 0.146;
170 square_length_ = 0.2;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800171
172 // Only charuco board has a board associated with it
173 board_ = static_cast<cv::Ptr<cv::aruco::CharucoBoard>>(NULL);
174
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800175 if (target_type_ == TargetType::kCharuco ||
176 target_type_ == TargetType::kAruco) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800177 dictionary_ = cv::aruco::getPredefinedDictionary(
178 FLAGS_large_board ? cv::aruco::DICT_5X5_250 : cv::aruco::DICT_6X6_250);
179
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800180 if (target_type_ == TargetType::kCharuco) {
Jim Ostrowski814d2812022-12-11 23:17:14 -0800181 LOG(INFO) << "Using " << (FLAGS_large_board ? "large" : "small")
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800182 << " charuco board with "
183 << (FLAGS_coarse_pattern ? "coarse" : "fine") << " pattern";
184 board_ =
185 (FLAGS_large_board
186 ? (FLAGS_coarse_pattern ? cv::aruco::CharucoBoard::create(
187 12, 9, 0.06, 0.04666, dictionary_)
188 : cv::aruco::CharucoBoard::create(
189 25, 18, 0.03, 0.0233, dictionary_))
190 : (FLAGS_coarse_pattern ? cv::aruco::CharucoBoard::create(
191 7, 5, 0.04, 0.025, dictionary_)
192 // TODO(jim): Need to figure out what
193 // size is for small board, fine pattern
194 : cv::aruco::CharucoBoard::create(
195 7, 5, 0.03, 0.0233, dictionary_)));
196 if (!FLAGS_board_template_path.empty()) {
197 cv::Mat board_image;
198 board_->draw(cv::Size(600, 500), board_image, 10, 1);
199 cv::imwrite(FLAGS_board_template_path, board_image);
200 }
201 }
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800202 } else if (target_type_ == TargetType::kCharucoDiamond) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800203 marker_length_ = 0.15;
Jim Ostrowski814d2812022-12-11 23:17:14 -0800204 square_length_ = 0.2;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800205 dictionary_ = cv::aruco::getPredefinedDictionary(cv::aruco::DICT_4X4_250);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800206 } else {
207 // Bail out if it's not a supported target
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800208 LOG(FATAL) << "Target type undefined: "
209 << static_cast<uint8_t>(target_type_);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800210 }
211}
212
213void CharucoExtractor::DrawTargetPoses(cv::Mat rgb_image,
214 std::vector<cv::Vec3d> rvecs,
215 std::vector<cv::Vec3d> tvecs) {
216 const Eigen::Matrix<double, 3, 4> camera_projection =
217 Eigen::Matrix<double, 3, 4>::Identity();
218
219 int x_coord = 10;
220 int y_coord = 0;
221 // draw axis for each marker
222 for (uint i = 0; i < rvecs.size(); i++) {
223 Eigen::Vector3d rvec_eigen, tvec_eigen;
224 cv::cv2eigen(rvecs[i], rvec_eigen);
225 cv::cv2eigen(tvecs[i], tvec_eigen);
226
227 Eigen::Quaternion<double> rotation(
228 frc971::controls::ToQuaternionFromRotationVector(rvec_eigen));
229 Eigen::Translation3d translation(tvec_eigen);
230
231 const Eigen::Affine3d board_to_camera = translation * rotation;
232
James Kuszmaul7e958812023-02-11 15:34:31 -0800233 Eigen::Vector3d result = calibration_.CameraIntrinsicsEigen() *
234 camera_projection * board_to_camera *
235 Eigen::Vector3d::Zero();
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800236
237 // Found that drawAxis hangs if you try to draw with z values too
238 // small (trying to draw axes at inifinity)
Jim Ostrowski814d2812022-12-11 23:17:14 -0800239 // TODO<Jim>: Either track this down or reimplement drawAxes
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800240 if (result.z() < 0.01) {
241 LOG(INFO) << "Skipping, due to z value too small: " << result.z();
Jim Ostrowski814d2812022-12-11 23:17:14 -0800242 } else if (FLAGS_draw_axes == true) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800243 result /= result.z();
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800244 if (target_type_ == TargetType::kCharuco) {
James Kuszmaul7e958812023-02-11 15:34:31 -0800245 cv::aruco::drawAxis(rgb_image, calibration_.CameraIntrinsics(),
Jim Ostrowski814d2812022-12-11 23:17:14 -0800246 calibration_.CameraDistCoeffs(), rvecs[i], tvecs[i],
247 0.1);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800248 } else {
James Kuszmaul7e958812023-02-11 15:34:31 -0800249 cv::drawFrameAxes(rgb_image, calibration_.CameraIntrinsics(),
250 calibration_.CameraDistCoeffs(), rvecs[i], tvecs[i],
251 0.1);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800252 }
253 }
254 std::stringstream ss;
255 ss << "tvec[" << i << "] = " << tvecs[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 ss.str("");
260 ss << "rvec[" << i << "] = " << rvecs[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 }
265}
266
267void CharucoExtractor::PackPoseResults(
268 std::vector<cv::Vec3d> &rvecs, std::vector<cv::Vec3d> &tvecs,
269 std::vector<Eigen::Vector3d> *rvecs_eigen,
270 std::vector<Eigen::Vector3d> *tvecs_eigen) {
271 for (cv::Vec3d rvec : rvecs) {
272 Eigen::Vector3d rvec_eigen = Eigen::Vector3d::Zero();
273 cv::cv2eigen(rvec, rvec_eigen);
274 rvecs_eigen->emplace_back(rvec_eigen);
275 }
276
277 for (cv::Vec3d tvec : tvecs) {
278 Eigen::Vector3d tvec_eigen = Eigen::Vector3d::Zero();
279 cv::cv2eigen(tvec, tvec_eigen);
280 tvecs_eigen->emplace_back(tvec_eigen);
281 }
282}
283
Austin Schuh25837f22021-06-27 15:49:14 -0700284CharucoExtractor::CharucoExtractor(
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700285 const calibration::CameraCalibration *calibration,
286 const TargetType target_type)
287 : event_loop_(nullptr),
288 target_type_(target_type),
289 calibration_(CHECK_NOTNULL(calibration)) {
290 VLOG(2) << "Configuring CharucoExtractor without event_loop";
291 SetupTargetData();
292 VLOG(2) << "Camera matrix:\n" << calibration_.CameraIntrinsics();
293 VLOG(2) << "Distortion Coefficients:\n" << calibration_.CameraDistCoeffs();
294}
295
296CharucoExtractor::CharucoExtractor(
James Kuszmaul7e958812023-02-11 15:34:31 -0800297 aos::EventLoop *event_loop,
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700298 const calibration::CameraCalibration *calibration,
299 const TargetType target_type, std::string_view image_channel,
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800300 std::function<void(cv::Mat, monotonic_clock::time_point,
301 std::vector<cv::Vec4i>,
302 std::vector<std::vector<cv::Point2f>>, bool,
303 std::vector<Eigen::Vector3d>,
304 std::vector<Eigen::Vector3d>)> &&handle_charuco_fn)
Austin Schuhea7b0142021-10-08 22:04:53 -0700305 : event_loop_(event_loop),
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800306 target_type_(target_type),
307 image_channel_(image_channel),
James Kuszmaul7e958812023-02-11 15:34:31 -0800308 calibration_(CHECK_NOTNULL(calibration)),
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800309 handle_charuco_(std::move(handle_charuco_fn)) {
310 SetupTargetData();
Austin Schuh25837f22021-06-27 15:49:14 -0700311
James Kuszmaul7e958812023-02-11 15:34:31 -0800312 LOG(INFO) << "Camera matrix " << calibration_.CameraIntrinsics();
313 LOG(INFO) << "Distortion Coefficients " << calibration_.CameraDistCoeffs();
Austin Schuh25837f22021-06-27 15:49:14 -0700314
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800315 LOG(INFO) << "Connecting to channel " << image_channel_;
Austin Schuh25837f22021-06-27 15:49:14 -0700316}
317
Austin Schuhea7b0142021-10-08 22:04:53 -0700318void CharucoExtractor::HandleImage(cv::Mat rgb_image,
319 const monotonic_clock::time_point eof) {
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700320 // Set up the variables we'll use in the callback function
321 bool valid = false;
322 // ids and corners for final, refined board / marker detections
323 // Using Vec4i type since it supports Charuco Diamonds
324 // And overloading it using 1st int in Vec4i for others target types
325 std::vector<cv::Vec4i> result_ids;
326 std::vector<std::vector<cv::Point2f>> result_corners;
327
328 // Return a list of poses; for Charuco Board there will be just one
329 std::vector<Eigen::Vector3d> rvecs_eigen;
330 std::vector<Eigen::Vector3d> tvecs_eigen;
331 ProcessImage(rgb_image, eof, event_loop_->monotonic_now(), result_ids,
332 result_corners, valid, rvecs_eigen, tvecs_eigen);
333
334 handle_charuco_(rgb_image, eof, result_ids, result_corners, valid,
335 rvecs_eigen, tvecs_eigen);
336}
337
338void CharucoExtractor::ProcessImage(
339 cv::Mat rgb_image, const monotonic_clock::time_point eof,
340 const monotonic_clock::time_point current_time,
341 std::vector<cv::Vec4i> &result_ids,
342 std::vector<std::vector<cv::Point2f>> &result_corners, bool &valid,
343 std::vector<Eigen::Vector3d> &rvecs_eigen,
344 std::vector<Eigen::Vector3d> &tvecs_eigen) {
Austin Schuhea7b0142021-10-08 22:04:53 -0700345 const double age_double =
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700346 std::chrono::duration_cast<std::chrono::duration<double>>(current_time -
347 eof)
Austin Schuhea7b0142021-10-08 22:04:53 -0700348 .count();
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800349
Jim Ostrowski814d2812022-12-11 23:17:14 -0800350 // Have found this useful if there is blurry / noisy images
351 if (FLAGS_gray_threshold > 0) {
352 cv::Mat gray;
353 cv::cvtColor(rgb_image, gray, cv::COLOR_BGR2GRAY);
354
355 cv::Mat thresh;
356 cv::threshold(gray, thresh, FLAGS_gray_threshold, 255, cv::THRESH_BINARY);
357 cv::cvtColor(thresh, rgb_image, cv::COLOR_GRAY2RGB);
358 }
359
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800360 // ids and corners for initial aruco marker detections
Austin Schuh25837f22021-06-27 15:49:14 -0700361 std::vector<int> marker_ids;
362 std::vector<std::vector<cv::Point2f>> marker_corners;
363
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800364 // Do initial marker detection; this is the same for all target types
365 cv::aruco::detectMarkers(rgb_image, dictionary_, marker_corners, marker_ids);
366 cv::aruco::drawDetectedMarkers(rgb_image, marker_corners, marker_ids);
Austin Schuhea7b0142021-10-08 22:04:53 -0700367
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800368 VLOG(2) << "Handle Image, with target type = "
369 << static_cast<uint8_t>(target_type_) << " and " << marker_ids.size()
370 << " markers detected initially";
Austin Schuh25837f22021-06-27 15:49:14 -0700371
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800372 if (marker_ids.size() == 0) {
373 VLOG(2) << "Didn't find any markers";
374 } else {
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800375 if (target_type_ == TargetType::kCharuco) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800376 std::vector<int> charuco_ids;
377 std::vector<cv::Point2f> charuco_corners;
Austin Schuh25837f22021-06-27 15:49:14 -0700378
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800379 // If enough aruco markers detected for the Charuco board
380 if (marker_ids.size() >= FLAGS_min_charucos) {
381 // Run everything twice, once with the calibration, and once
382 // without. This lets us both collect data to calibrate the
383 // intrinsics of the camera (to determine the intrinsics from
384 // multiple samples), and also to use data from a previous/stored
385 // calibration to determine a more accurate pose in real time (used
386 // for extrinsics calibration)
387 cv::aruco::interpolateCornersCharuco(marker_corners, marker_ids,
388 rgb_image, board_, charuco_corners,
389 charuco_ids);
Austin Schuh25837f22021-06-27 15:49:14 -0700390
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800391 std::vector<cv::Point2f> charuco_corners_with_calibration;
392 std::vector<int> charuco_ids_with_calibration;
Austin Schuh25837f22021-06-27 15:49:14 -0700393
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800394 // This call uses a previous intrinsic calibration to get more
395 // accurate marker locations, for a better pose estimate
396 cv::aruco::interpolateCornersCharuco(
397 marker_corners, marker_ids, rgb_image, board_,
398 charuco_corners_with_calibration, charuco_ids_with_calibration,
James Kuszmaul7e958812023-02-11 15:34:31 -0800399 calibration_.CameraIntrinsics(), calibration_.CameraDistCoeffs());
Austin Schuh25837f22021-06-27 15:49:14 -0700400
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800401 if (charuco_ids.size() >= FLAGS_min_charucos) {
402 cv::aruco::drawDetectedCornersCharuco(
403 rgb_image, charuco_corners, charuco_ids, cv::Scalar(255, 0, 0));
Austin Schuh25837f22021-06-27 15:49:14 -0700404
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800405 cv::Vec3d rvec, tvec;
406 valid = cv::aruco::estimatePoseCharucoBoard(
407 charuco_corners_with_calibration, charuco_ids_with_calibration,
James Kuszmaul7e958812023-02-11 15:34:31 -0800408 board_, calibration_.CameraIntrinsics(),
409 calibration_.CameraDistCoeffs(), rvec, tvec);
Austin Schuh25837f22021-06-27 15:49:14 -0700410
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800411 // if charuco pose is valid, return pose, with ids and corners
412 if (valid) {
413 std::vector<cv::Vec3d> rvecs, tvecs;
414 rvecs.emplace_back(rvec);
415 tvecs.emplace_back(tvec);
416 DrawTargetPoses(rgb_image, rvecs, tvecs);
Austin Schuh25837f22021-06-27 15:49:14 -0700417
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800418 PackPoseResults(rvecs, tvecs, &rvecs_eigen, &tvecs_eigen);
419 // Store the corners without calibration, since we use them to
420 // do calibration
421 result_corners.emplace_back(charuco_corners);
422 for (auto id : charuco_ids) {
423 result_ids.emplace_back(cv::Vec4i{id, 0, 0, 0});
424 }
425 } else {
426 VLOG(2) << "Age: " << age_double << ", invalid charuco board pose";
427 }
Jim Ostrowski634b2652022-03-04 02:10:53 -0800428 } else {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800429 VLOG(2) << "Age: " << age_double << ", not enough charuco IDs, got "
430 << charuco_ids.size() << ", needed " << FLAGS_min_charucos;
Jim Ostrowski634b2652022-03-04 02:10:53 -0800431 }
Austin Schuh25837f22021-06-27 15:49:14 -0700432 } else {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800433 VLOG(2) << "Age: " << age_double
434 << ", not enough marker IDs for charuco board, got "
435 << marker_ids.size() << ", needed " << FLAGS_min_charucos;
436 }
milind-u09fb1252023-01-28 19:21:41 -0800437 } else if (target_type_ == TargetType::kAruco) {
438 // estimate pose for arucos doesn't return valid, so marking true
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800439 valid = true;
440 std::vector<cv::Vec3d> rvecs, tvecs;
James Kuszmaul7e958812023-02-11 15:34:31 -0800441 cv::aruco::estimatePoseSingleMarkers(
442 marker_corners, square_length_, calibration_.CameraIntrinsics(),
443 calibration_.CameraDistCoeffs(), rvecs, tvecs);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800444 DrawTargetPoses(rgb_image, rvecs, tvecs);
445
446 PackPoseResults(rvecs, tvecs, &rvecs_eigen, &tvecs_eigen);
447 for (uint i = 0; i < marker_ids.size(); i++) {
448 result_ids.emplace_back(cv::Vec4i{marker_ids[i], 0, 0, 0});
449 }
450 result_corners = marker_corners;
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800451 } else if (target_type_ == TargetType::kCharucoDiamond) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800452 // Extract the diamonds associated with the markers
453 std::vector<cv::Vec4i> diamond_ids;
454 std::vector<std::vector<cv::Point2f>> diamond_corners;
455 cv::aruco::detectCharucoDiamond(rgb_image, marker_corners, marker_ids,
456 square_length_ / marker_length_,
457 diamond_corners, diamond_ids);
458
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700459 // Check that we have an acceptable number of diamonds detected.
460 // Should be at least one, and no more than FLAGS_max_diamonds.
461 // Different calibration routines will require different values for this
462 if (diamond_ids.size() > 0 &&
463 (FLAGS_max_diamonds == 0 ||
464 diamond_ids.size() <= FLAGS_max_diamonds)) {
465 // TODO<Jim>: Could probably make this check more general than
466 // requiring range of ids
Jim Ostrowskic7d90102023-03-09 14:47:25 -0800467 bool all_valid_ids = true;
468 for (uint i = 0; i < 4; i++) {
469 uint id = diamond_ids[0][i];
470 if ((id < FLAGS_min_id) || (id > FLAGS_max_id)) {
471 all_valid_ids = false;
472 LOG(INFO) << "Got invalid charuco id: " << id;
473 }
474 }
475 if (all_valid_ids) {
476 cv::aruco::drawDetectedDiamonds(rgb_image, diamond_corners,
477 diamond_ids);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800478
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700479 // estimate pose for diamonds doesn't return valid, so marking
480 // true
Jim Ostrowskic7d90102023-03-09 14:47:25 -0800481 valid = true;
482 std::vector<cv::Vec3d> rvecs, tvecs;
483 cv::aruco::estimatePoseSingleMarkers(
484 diamond_corners, square_length_, calibration_.CameraIntrinsics(),
485 calibration_.CameraDistCoeffs(), rvecs, tvecs);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800486
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700487 DrawTargetPoses(rgb_image, rvecs, tvecs);
Jim Ostrowskic7d90102023-03-09 14:47:25 -0800488 PackPoseResults(rvecs, tvecs, &rvecs_eigen, &tvecs_eigen);
489 result_ids = diamond_ids;
490 result_corners = diamond_corners;
491 } else {
492 LOG(INFO) << "Not all charuco ids were valid, so skipping";
493 }
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800494 } else {
Jim Ostrowskic7d90102023-03-09 14:47:25 -0800495 if (diamond_ids.size() == 0) {
496 // OK to not see any markers sometimes
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700497 VLOG(2) << "Found aruco markers, but no valid charuco diamond "
498 "targets";
Jim Ostrowskic7d90102023-03-09 14:47:25 -0800499 } else {
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700500 VLOG(2) << "Found too many number of diamond markers, which likely "
501 "means false positives were detected: "
502 << diamond_ids.size() << " > " << FLAGS_max_diamonds;
Jim Ostrowskic7d90102023-03-09 14:47:25 -0800503 }
Austin Schuh25837f22021-06-27 15:49:14 -0700504 }
505 } else {
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800506 LOG(FATAL) << "Unknown target type: "
507 << static_cast<uint8_t>(target_type_);
Austin Schuh25837f22021-06-27 15:49:14 -0700508 }
Austin Schuh25837f22021-06-27 15:49:14 -0700509 }
Austin Schuh25837f22021-06-27 15:49:14 -0700510}
511
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800512flatbuffers::Offset<foxglove::ImageAnnotations> BuildAnnotations(
Jim Ostrowski5e2c5e62023-02-26 12:52:56 -0800513 flatbuffers::FlatBufferBuilder *fbb,
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800514 const aos::monotonic_clock::time_point monotonic_now,
Jim Ostrowski5e2c5e62023-02-26 12:52:56 -0800515 const std::vector<std::vector<cv::Point2f>> &corners,
516 const std::vector<double> rgba_color, const double thickness,
517 const foxglove::PointsAnnotationType line_type) {
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800518 std::vector<flatbuffers::Offset<foxglove::PointsAnnotation>> rectangles;
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800519 for (const std::vector<cv::Point2f> &rectangle : corners) {
Jim Ostrowski5e2c5e62023-02-26 12:52:56 -0800520 rectangles.push_back(BuildPointsAnnotation(
521 fbb, monotonic_now, rectangle, rgba_color, thickness, line_type));
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800522 }
523
524 const auto rectangles_offset = fbb->CreateVector(rectangles);
525 foxglove::ImageAnnotations::Builder annotation_builder(*fbb);
526 annotation_builder.add_points(rectangles_offset);
527 return annotation_builder.Finish();
528}
529
Jim Ostrowski5e2c5e62023-02-26 12:52:56 -0800530flatbuffers::Offset<foxglove::PointsAnnotation> BuildPointsAnnotation(
531 flatbuffers::FlatBufferBuilder *fbb,
532 const aos::monotonic_clock::time_point monotonic_now,
533 const std::vector<cv::Point2f> &corners,
534 const std::vector<double> rgba_color, const double thickness,
535 const foxglove::PointsAnnotationType line_type) {
536 const struct timespec now_t = aos::time::to_timespec(monotonic_now);
537 foxglove::Time time{static_cast<uint32_t>(now_t.tv_sec),
538 static_cast<uint32_t>(now_t.tv_nsec)};
539 const flatbuffers::Offset<foxglove::Color> color_offset =
540 foxglove::CreateColor(*fbb, rgba_color[0], rgba_color[1], rgba_color[2],
541 rgba_color[3]);
542 std::vector<flatbuffers::Offset<foxglove::Point2>> points_offsets;
543 for (const cv::Point2f &point : corners) {
544 points_offsets.push_back(foxglove::CreatePoint2(*fbb, point.x, point.y));
545 }
546 const flatbuffers::Offset<
547 flatbuffers::Vector<flatbuffers::Offset<foxglove::Point2>>>
548 points_offset = fbb->CreateVector(points_offsets);
549 std::vector<flatbuffers::Offset<foxglove::Color>> color_offsets(
550 points_offsets.size(), color_offset);
551 auto colors_offset = fbb->CreateVector(color_offsets);
552 foxglove::PointsAnnotation::Builder points_builder(*fbb);
553 points_builder.add_timestamp(&time);
554 points_builder.add_type(line_type);
555 points_builder.add_points(points_offset);
556 points_builder.add_outline_color(color_offset);
557 points_builder.add_outline_colors(colors_offset);
558 points_builder.add_thickness(thickness);
559
560 return points_builder.Finish();
561}
562
James Kuszmauld6199be2023-02-11 19:56:28 -0800563TargetType TargetTypeFromString(std::string_view str) {
564 if (str == "aruco") {
565 return TargetType::kAruco;
566 } else if (str == "charuco") {
567 return TargetType::kCharuco;
568 } else if (str == "charuco_diamond") {
569 return TargetType::kCharucoDiamond;
570 } else {
571 LOG(FATAL) << "Unknown target type: " << str
572 << ", expected: aruco|charuco|charuco_diamond";
573 }
574}
575
576std::ostream &operator<<(std::ostream &os, TargetType target_type) {
577 switch (target_type) {
578 case TargetType::kAruco:
579 os << "aruco";
580 break;
581 case TargetType::kCharuco:
582 os << "charuco";
583 break;
584 case TargetType::kCharucoDiamond:
585 os << "charuco_diamond";
586 break;
587 }
588 return os;
589}
590
Austin Schuh25837f22021-06-27 15:49:14 -0700591} // namespace vision
592} // namespace frc971