blob: 82cc6b3ba541512885d405fc038826f2d5903df3 [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 Ostrowskic7d90102023-03-09 14:47:25 -080028DEFINE_uint32(min_id, 12, "Minimum valid charuco id");
29DEFINE_uint32(max_id, 15, "Minimum valid charuco id");
Jim Ostrowskib3cab972022-12-03 15:47:00 -080030DEFINE_bool(visualize, false, "Whether to visualize the resulting data.");
Jim Ostrowski814d2812022-12-11 23:17:14 -080031DEFINE_bool(
32 draw_axes, false,
33 "Whether to draw axes on the resulting data-- warning, may cause crashes.");
Austin Schuh25837f22021-06-27 15:49:14 -070034
Austin Schuhc3419862023-01-08 13:54:36 -080035DEFINE_uint32(disable_delay, 100, "Time after an issue to disable tracing at.");
36
37DECLARE_bool(enable_ftrace);
38
Austin Schuh25837f22021-06-27 15:49:14 -070039namespace frc971 {
40namespace vision {
41namespace chrono = std::chrono;
Austin Schuhea7b0142021-10-08 22:04:53 -070042using aos::monotonic_clock;
Austin Schuh25837f22021-06-27 15:49:14 -070043
44CameraCalibration::CameraCalibration(
James Kuszmaul7e958812023-02-11 15:34:31 -080045 const calibration::CameraCalibration *calibration)
46 : intrinsics_([calibration]() {
47 const cv::Mat result(3, 3, CV_32F,
48 const_cast<void *>(static_cast<const void *>(
49 calibration->intrinsics()->data())));
50 CHECK_EQ(result.total(), calibration->intrinsics()->size());
51 return result;
52 }()),
53 intrinsics_eigen_([this]() {
54 cv::Mat camera_intrinsics = intrinsics_;
55 Eigen::Matrix3d result;
56 cv::cv2eigen(camera_intrinsics, result);
57 return result;
58 }()),
59 dist_coeffs_([calibration]() {
60 const cv::Mat result(5, 1, CV_32F,
61 const_cast<void *>(static_cast<const void *>(
62 calibration->dist_coeffs()->data())));
63 CHECK_EQ(result.total(), calibration->dist_coeffs()->size());
64 return result;
65 }()) {}
Austin Schuh25837f22021-06-27 15:49:14 -070066
Austin Schuhea7b0142021-10-08 22:04:53 -070067ImageCallback::ImageCallback(
68 aos::EventLoop *event_loop, std::string_view channel,
milind-u0cb53112023-02-03 20:32:55 -080069 std::function<void(cv::Mat, monotonic_clock::time_point)> &&handle_image_fn,
70 monotonic_clock::duration max_age)
Austin Schuhea7b0142021-10-08 22:04:53 -070071 : event_loop_(event_loop),
72 server_fetcher_(
73 event_loop_->MakeFetcher<aos::message_bridge::ServerStatistics>(
74 "/aos")),
75 source_node_(aos::configuration::GetNode(
76 event_loop_->configuration(),
77 event_loop_->GetChannel<CameraImage>(channel)
78 ->source_node()
79 ->string_view())),
Austin Schuhc3419862023-01-08 13:54:36 -080080 handle_image_(std::move(handle_image_fn)),
milind-u0cb53112023-02-03 20:32:55 -080081 timer_fn_(event_loop->AddTimer([this]() { DisableTracing(); })),
82 max_age_(max_age) {
Austin Schuh25837f22021-06-27 15:49:14 -070083 event_loop_->MakeWatcher(channel, [this](const CameraImage &image) {
Austin Schuhea7b0142021-10-08 22:04:53 -070084 const monotonic_clock::time_point eof_source_node =
85 monotonic_clock::time_point(
86 chrono::nanoseconds(image.monotonic_timestamp_ns()));
Austin Schuhea7b0142021-10-08 22:04:53 -070087 chrono::nanoseconds offset{0};
88 if (source_node_ != event_loop_->node()) {
Austin Schuhee8bc1e2021-11-20 16:23:41 -080089 server_fetcher_.Fetch();
90 if (!server_fetcher_.get()) {
91 return;
92 }
93
Austin Schuhea7b0142021-10-08 22:04:53 -070094 // If we are viewing this image from another node, convert to our
95 // monotonic clock.
96 const aos::message_bridge::ServerConnection *server_connection = nullptr;
97
98 for (const aos::message_bridge::ServerConnection *connection :
99 *server_fetcher_->connections()) {
100 CHECK(connection->has_node());
101 if (connection->node()->name()->string_view() ==
102 source_node_->name()->string_view()) {
103 server_connection = connection;
104 break;
105 }
106 }
107
108 CHECK(server_connection != nullptr) << ": Failed to find client";
109 if (!server_connection->has_monotonic_offset()) {
110 VLOG(1) << "No offset yet.";
111 return;
112 }
113 offset = chrono::nanoseconds(server_connection->monotonic_offset());
114 }
115
116 const monotonic_clock::time_point eof = eof_source_node - offset;
117
Jim Ostrowski977850f2022-01-22 21:04:22 -0800118 const monotonic_clock::duration age = event_loop_->monotonic_now() - eof;
Austin Schuh25837f22021-06-27 15:49:14 -0700119 const double age_double =
120 std::chrono::duration_cast<std::chrono::duration<double>>(age).count();
milind-u0cb53112023-02-03 20:32:55 -0800121 if (age > max_age_) {
Austin Schuhc3419862023-01-08 13:54:36 -0800122 if (FLAGS_enable_ftrace) {
123 ftrace_.FormatMessage("Too late receiving image, age: %f\n",
124 age_double);
125 if (FLAGS_disable_delay > 0) {
126 if (!disabling_) {
Philipp Schradera6712522023-07-05 20:25:11 -0700127 timer_fn_->Schedule(event_loop_->monotonic_now() +
128 chrono::milliseconds(FLAGS_disable_delay));
Austin Schuhc3419862023-01-08 13:54:36 -0800129 disabling_ = true;
130 }
131 } else {
132 DisableTracing();
133 }
134 }
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800135 VLOG(2) << "Age: " << age_double << ", getting behind, skipping";
Austin Schuh25837f22021-06-27 15:49:14 -0700136 return;
137 }
138 // Create color image:
139 cv::Mat image_color_mat(cv::Size(image.cols(), image.rows()), CV_8UC2,
140 (void *)image.data()->data());
141 const cv::Size image_size(image.cols(), image.rows());
Austin Schuhac402e92023-01-08 13:56:20 -0800142 switch (format_) {
143 case Format::GRAYSCALE: {
144 ftrace_.FormatMessage("Starting yuyv->greyscale\n");
145 cv::Mat gray_image(image_size, CV_8UC3);
146 cv::cvtColor(image_color_mat, gray_image, cv::COLOR_YUV2GRAY_YUYV);
147 handle_image_(gray_image, eof);
148 } break;
149 case Format::BGR: {
150 cv::Mat rgb_image(image_size, CV_8UC3);
151 cv::cvtColor(image_color_mat, rgb_image, cv::COLOR_YUV2BGR_YUYV);
152 handle_image_(rgb_image, eof);
153 } break;
154 case Format::YUYV2: {
155 handle_image_(image_color_mat, eof);
156 };
157 }
Austin Schuh25837f22021-06-27 15:49:14 -0700158 });
159}
160
Austin Schuhc3419862023-01-08 13:54:36 -0800161void ImageCallback::DisableTracing() {
162 disabling_ = false;
163 ftrace_.TurnOffOrDie();
164}
165
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800166void CharucoExtractor::SetupTargetData() {
Jim Ostrowski814d2812022-12-11 23:17:14 -0800167 marker_length_ = 0.146;
168 square_length_ = 0.2;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800169
170 // Only charuco board has a board associated with it
171 board_ = static_cast<cv::Ptr<cv::aruco::CharucoBoard>>(NULL);
172
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800173 if (target_type_ == TargetType::kCharuco ||
174 target_type_ == TargetType::kAruco) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800175 dictionary_ = cv::aruco::getPredefinedDictionary(
176 FLAGS_large_board ? cv::aruco::DICT_5X5_250 : cv::aruco::DICT_6X6_250);
177
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800178 if (target_type_ == TargetType::kCharuco) {
Jim Ostrowski814d2812022-12-11 23:17:14 -0800179 LOG(INFO) << "Using " << (FLAGS_large_board ? "large" : "small")
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800180 << " charuco board with "
181 << (FLAGS_coarse_pattern ? "coarse" : "fine") << " pattern";
182 board_ =
183 (FLAGS_large_board
184 ? (FLAGS_coarse_pattern ? cv::aruco::CharucoBoard::create(
185 12, 9, 0.06, 0.04666, dictionary_)
186 : cv::aruco::CharucoBoard::create(
187 25, 18, 0.03, 0.0233, dictionary_))
188 : (FLAGS_coarse_pattern ? cv::aruco::CharucoBoard::create(
189 7, 5, 0.04, 0.025, dictionary_)
190 // TODO(jim): Need to figure out what
191 // size is for small board, fine pattern
192 : cv::aruco::CharucoBoard::create(
193 7, 5, 0.03, 0.0233, dictionary_)));
194 if (!FLAGS_board_template_path.empty()) {
195 cv::Mat board_image;
196 board_->draw(cv::Size(600, 500), board_image, 10, 1);
197 cv::imwrite(FLAGS_board_template_path, board_image);
198 }
199 }
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800200 } else if (target_type_ == TargetType::kCharucoDiamond) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800201 marker_length_ = 0.15;
Jim Ostrowski814d2812022-12-11 23:17:14 -0800202 square_length_ = 0.2;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800203 dictionary_ = cv::aruco::getPredefinedDictionary(cv::aruco::DICT_4X4_250);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800204 } else {
205 // Bail out if it's not a supported target
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800206 LOG(FATAL) << "Target type undefined: "
207 << static_cast<uint8_t>(target_type_);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800208 }
209}
210
211void CharucoExtractor::DrawTargetPoses(cv::Mat rgb_image,
212 std::vector<cv::Vec3d> rvecs,
213 std::vector<cv::Vec3d> tvecs) {
214 const Eigen::Matrix<double, 3, 4> camera_projection =
215 Eigen::Matrix<double, 3, 4>::Identity();
216
217 int x_coord = 10;
218 int y_coord = 0;
219 // draw axis for each marker
220 for (uint i = 0; i < rvecs.size(); i++) {
221 Eigen::Vector3d rvec_eigen, tvec_eigen;
222 cv::cv2eigen(rvecs[i], rvec_eigen);
223 cv::cv2eigen(tvecs[i], tvec_eigen);
224
225 Eigen::Quaternion<double> rotation(
226 frc971::controls::ToQuaternionFromRotationVector(rvec_eigen));
227 Eigen::Translation3d translation(tvec_eigen);
228
229 const Eigen::Affine3d board_to_camera = translation * rotation;
230
James Kuszmaul7e958812023-02-11 15:34:31 -0800231 Eigen::Vector3d result = calibration_.CameraIntrinsicsEigen() *
232 camera_projection * board_to_camera *
233 Eigen::Vector3d::Zero();
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800234
235 // Found that drawAxis hangs if you try to draw with z values too
236 // small (trying to draw axes at inifinity)
Jim Ostrowski814d2812022-12-11 23:17:14 -0800237 // TODO<Jim>: Either track this down or reimplement drawAxes
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800238 if (result.z() < 0.01) {
239 LOG(INFO) << "Skipping, due to z value too small: " << result.z();
Jim Ostrowski814d2812022-12-11 23:17:14 -0800240 } else if (FLAGS_draw_axes == true) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800241 result /= result.z();
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800242 if (target_type_ == TargetType::kCharuco) {
James Kuszmaul7e958812023-02-11 15:34:31 -0800243 cv::aruco::drawAxis(rgb_image, calibration_.CameraIntrinsics(),
Jim Ostrowski814d2812022-12-11 23:17:14 -0800244 calibration_.CameraDistCoeffs(), rvecs[i], tvecs[i],
245 0.1);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800246 } else {
James Kuszmaul7e958812023-02-11 15:34:31 -0800247 cv::drawFrameAxes(rgb_image, calibration_.CameraIntrinsics(),
248 calibration_.CameraDistCoeffs(), rvecs[i], tvecs[i],
249 0.1);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800250 }
251 }
252 std::stringstream ss;
253 ss << "tvec[" << i << "] = " << tvecs[i];
254 y_coord += 25;
255 cv::putText(rgb_image, ss.str(), cv::Point(x_coord, y_coord),
256 cv::FONT_HERSHEY_PLAIN, 1.0, cv::Scalar(255, 255, 255));
257 ss.str("");
258 ss << "rvec[" << i << "] = " << rvecs[i];
259 y_coord += 25;
260 cv::putText(rgb_image, ss.str(), cv::Point(x_coord, y_coord),
261 cv::FONT_HERSHEY_PLAIN, 1.0, cv::Scalar(255, 255, 255));
262 }
263}
264
265void CharucoExtractor::PackPoseResults(
266 std::vector<cv::Vec3d> &rvecs, std::vector<cv::Vec3d> &tvecs,
267 std::vector<Eigen::Vector3d> *rvecs_eigen,
268 std::vector<Eigen::Vector3d> *tvecs_eigen) {
269 for (cv::Vec3d rvec : rvecs) {
270 Eigen::Vector3d rvec_eigen = Eigen::Vector3d::Zero();
271 cv::cv2eigen(rvec, rvec_eigen);
272 rvecs_eigen->emplace_back(rvec_eigen);
273 }
274
275 for (cv::Vec3d tvec : tvecs) {
276 Eigen::Vector3d tvec_eigen = Eigen::Vector3d::Zero();
277 cv::cv2eigen(tvec, tvec_eigen);
278 tvecs_eigen->emplace_back(tvec_eigen);
279 }
280}
281
Austin Schuh25837f22021-06-27 15:49:14 -0700282CharucoExtractor::CharucoExtractor(
James Kuszmaul7e958812023-02-11 15:34:31 -0800283 aos::EventLoop *event_loop,
284 const calibration::CameraCalibration *calibration, TargetType target_type,
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800285 std::string_view image_channel,
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800286 std::function<void(cv::Mat, monotonic_clock::time_point,
287 std::vector<cv::Vec4i>,
288 std::vector<std::vector<cv::Point2f>>, bool,
289 std::vector<Eigen::Vector3d>,
290 std::vector<Eigen::Vector3d>)> &&handle_charuco_fn)
Austin Schuhea7b0142021-10-08 22:04:53 -0700291 : event_loop_(event_loop),
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800292 target_type_(target_type),
293 image_channel_(image_channel),
James Kuszmaul7e958812023-02-11 15:34:31 -0800294 calibration_(CHECK_NOTNULL(calibration)),
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800295 handle_charuco_(std::move(handle_charuco_fn)) {
296 SetupTargetData();
Austin Schuh25837f22021-06-27 15:49:14 -0700297
James Kuszmaul7e958812023-02-11 15:34:31 -0800298 LOG(INFO) << "Camera matrix " << calibration_.CameraIntrinsics();
299 LOG(INFO) << "Distortion Coefficients " << calibration_.CameraDistCoeffs();
Austin Schuh25837f22021-06-27 15:49:14 -0700300
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800301 LOG(INFO) << "Connecting to channel " << image_channel_;
Austin Schuh25837f22021-06-27 15:49:14 -0700302}
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
Jim Ostrowski814d2812022-12-11 23:17:14 -0800311 // Have found this useful if there is blurry / noisy images
312 if (FLAGS_gray_threshold > 0) {
313 cv::Mat gray;
314 cv::cvtColor(rgb_image, gray, cv::COLOR_BGR2GRAY);
315
316 cv::Mat thresh;
317 cv::threshold(gray, thresh, FLAGS_gray_threshold, 255, cv::THRESH_BINARY);
318 cv::cvtColor(thresh, rgb_image, cv::COLOR_GRAY2RGB);
319 }
320
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800321 // Set up the variables we'll use in the callback function
322 bool valid = false;
323 // Return a list of poses; for Charuco Board there will be just one
324 std::vector<Eigen::Vector3d> rvecs_eigen;
325 std::vector<Eigen::Vector3d> tvecs_eigen;
326
327 // ids and corners for initial aruco marker detections
Austin Schuh25837f22021-06-27 15:49:14 -0700328 std::vector<int> marker_ids;
329 std::vector<std::vector<cv::Point2f>> marker_corners;
330
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800331 // ids and corners for final, refined board / marker detections
332 // Using Vec4i type since it supports Charuco Diamonds
333 // And overloading it using 1st int in Vec4i for others target types
334 std::vector<cv::Vec4i> result_ids;
335 std::vector<std::vector<cv::Point2f>> result_corners;
Austin Schuh25837f22021-06-27 15:49:14 -0700336
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800337 // Do initial marker detection; this is the same for all target types
338 cv::aruco::detectMarkers(rgb_image, dictionary_, marker_corners, marker_ids);
339 cv::aruco::drawDetectedMarkers(rgb_image, marker_corners, marker_ids);
Austin Schuhea7b0142021-10-08 22:04:53 -0700340
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800341 VLOG(2) << "Handle Image, with target type = "
342 << static_cast<uint8_t>(target_type_) << " and " << marker_ids.size()
343 << " markers detected initially";
Austin Schuh25837f22021-06-27 15:49:14 -0700344
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800345 if (marker_ids.size() == 0) {
346 VLOG(2) << "Didn't find any markers";
347 } else {
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800348 if (target_type_ == TargetType::kCharuco) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800349 std::vector<int> charuco_ids;
350 std::vector<cv::Point2f> charuco_corners;
Austin Schuh25837f22021-06-27 15:49:14 -0700351
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800352 // If enough aruco markers detected for the Charuco board
353 if (marker_ids.size() >= FLAGS_min_charucos) {
354 // Run everything twice, once with the calibration, and once
355 // without. This lets us both collect data to calibrate the
356 // intrinsics of the camera (to determine the intrinsics from
357 // multiple samples), and also to use data from a previous/stored
358 // calibration to determine a more accurate pose in real time (used
359 // for extrinsics calibration)
360 cv::aruco::interpolateCornersCharuco(marker_corners, marker_ids,
361 rgb_image, board_, charuco_corners,
362 charuco_ids);
Austin Schuh25837f22021-06-27 15:49:14 -0700363
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800364 std::vector<cv::Point2f> charuco_corners_with_calibration;
365 std::vector<int> charuco_ids_with_calibration;
Austin Schuh25837f22021-06-27 15:49:14 -0700366
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800367 // This call uses a previous intrinsic calibration to get more
368 // accurate marker locations, for a better pose estimate
369 cv::aruco::interpolateCornersCharuco(
370 marker_corners, marker_ids, rgb_image, board_,
371 charuco_corners_with_calibration, charuco_ids_with_calibration,
James Kuszmaul7e958812023-02-11 15:34:31 -0800372 calibration_.CameraIntrinsics(), calibration_.CameraDistCoeffs());
Austin Schuh25837f22021-06-27 15:49:14 -0700373
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800374 if (charuco_ids.size() >= FLAGS_min_charucos) {
375 cv::aruco::drawDetectedCornersCharuco(
376 rgb_image, charuco_corners, charuco_ids, cv::Scalar(255, 0, 0));
Austin Schuh25837f22021-06-27 15:49:14 -0700377
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800378 cv::Vec3d rvec, tvec;
379 valid = cv::aruco::estimatePoseCharucoBoard(
380 charuco_corners_with_calibration, charuco_ids_with_calibration,
James Kuszmaul7e958812023-02-11 15:34:31 -0800381 board_, calibration_.CameraIntrinsics(),
382 calibration_.CameraDistCoeffs(), rvec, tvec);
Austin Schuh25837f22021-06-27 15:49:14 -0700383
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800384 // if charuco pose is valid, return pose, with ids and corners
385 if (valid) {
386 std::vector<cv::Vec3d> rvecs, tvecs;
387 rvecs.emplace_back(rvec);
388 tvecs.emplace_back(tvec);
389 DrawTargetPoses(rgb_image, rvecs, tvecs);
Austin Schuh25837f22021-06-27 15:49:14 -0700390
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800391 PackPoseResults(rvecs, tvecs, &rvecs_eigen, &tvecs_eigen);
392 // Store the corners without calibration, since we use them to
393 // do calibration
394 result_corners.emplace_back(charuco_corners);
395 for (auto id : charuco_ids) {
396 result_ids.emplace_back(cv::Vec4i{id, 0, 0, 0});
397 }
398 } else {
399 VLOG(2) << "Age: " << age_double << ", invalid charuco board pose";
400 }
Jim Ostrowski634b2652022-03-04 02:10:53 -0800401 } else {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800402 VLOG(2) << "Age: " << age_double << ", not enough charuco IDs, got "
403 << charuco_ids.size() << ", needed " << FLAGS_min_charucos;
Jim Ostrowski634b2652022-03-04 02:10:53 -0800404 }
Austin Schuh25837f22021-06-27 15:49:14 -0700405 } else {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800406 VLOG(2) << "Age: " << age_double
407 << ", not enough marker IDs for charuco board, got "
408 << marker_ids.size() << ", needed " << FLAGS_min_charucos;
409 }
milind-u09fb1252023-01-28 19:21:41 -0800410 } else if (target_type_ == TargetType::kAruco) {
411 // estimate pose for arucos doesn't return valid, so marking true
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800412 valid = true;
413 std::vector<cv::Vec3d> rvecs, tvecs;
James Kuszmaul7e958812023-02-11 15:34:31 -0800414 cv::aruco::estimatePoseSingleMarkers(
415 marker_corners, square_length_, calibration_.CameraIntrinsics(),
416 calibration_.CameraDistCoeffs(), rvecs, tvecs);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800417 DrawTargetPoses(rgb_image, rvecs, tvecs);
418
419 PackPoseResults(rvecs, tvecs, &rvecs_eigen, &tvecs_eigen);
420 for (uint i = 0; i < marker_ids.size(); i++) {
421 result_ids.emplace_back(cv::Vec4i{marker_ids[i], 0, 0, 0});
422 }
423 result_corners = marker_corners;
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800424 } else if (target_type_ == TargetType::kCharucoDiamond) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800425 // Extract the diamonds associated with the markers
426 std::vector<cv::Vec4i> diamond_ids;
427 std::vector<std::vector<cv::Point2f>> diamond_corners;
428 cv::aruco::detectCharucoDiamond(rgb_image, marker_corners, marker_ids,
429 square_length_ / marker_length_,
430 diamond_corners, diamond_ids);
431
Jim Ostrowskic7d90102023-03-09 14:47:25 -0800432 // Check that we have exactly one charuco diamond. For calibration, we
433 // can constrain things so that this is the case
434 if (diamond_ids.size() == 1) {
435 // TODO<Jim>: Could probably make this check more general than requiring
436 // range of ids
437 bool all_valid_ids = true;
438 for (uint i = 0; i < 4; i++) {
439 uint id = diamond_ids[0][i];
440 if ((id < FLAGS_min_id) || (id > FLAGS_max_id)) {
441 all_valid_ids = false;
442 LOG(INFO) << "Got invalid charuco id: " << id;
443 }
444 }
445 if (all_valid_ids) {
446 cv::aruco::drawDetectedDiamonds(rgb_image, diamond_corners,
447 diamond_ids);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800448
Jim Ostrowskic7d90102023-03-09 14:47:25 -0800449 // estimate pose for diamonds doesn't return valid, so marking true
450 valid = true;
451 std::vector<cv::Vec3d> rvecs, tvecs;
452 cv::aruco::estimatePoseSingleMarkers(
453 diamond_corners, square_length_, calibration_.CameraIntrinsics(),
454 calibration_.CameraDistCoeffs(), rvecs, tvecs);
455 DrawTargetPoses(rgb_image, rvecs, tvecs);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800456
Jim Ostrowskic7d90102023-03-09 14:47:25 -0800457 PackPoseResults(rvecs, tvecs, &rvecs_eigen, &tvecs_eigen);
458 result_ids = diamond_ids;
459 result_corners = diamond_corners;
460 } else {
461 LOG(INFO) << "Not all charuco ids were valid, so skipping";
462 }
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800463 } else {
Jim Ostrowskic7d90102023-03-09 14:47:25 -0800464 if (diamond_ids.size() == 0) {
465 // OK to not see any markers sometimes
466 VLOG(2)
467 << "Found aruco markers, but no valid charuco diamond targets";
468 } else {
469 // But should never detect multiple
470 LOG(FATAL) << "Found multiple charuco diamond markers. Should only "
471 "be one";
472 }
Austin Schuh25837f22021-06-27 15:49:14 -0700473 }
474 } else {
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800475 LOG(FATAL) << "Unknown target type: "
476 << static_cast<uint8_t>(target_type_);
Austin Schuh25837f22021-06-27 15:49:14 -0700477 }
Austin Schuh25837f22021-06-27 15:49:14 -0700478 }
Austin Schuhea7b0142021-10-08 22:04:53 -0700479
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800480 handle_charuco_(rgb_image, eof, result_ids, result_corners, valid,
481 rvecs_eigen, tvecs_eigen);
Austin Schuh25837f22021-06-27 15:49:14 -0700482}
483
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800484flatbuffers::Offset<foxglove::ImageAnnotations> BuildAnnotations(
Jim Ostrowski5e2c5e62023-02-26 12:52:56 -0800485 flatbuffers::FlatBufferBuilder *fbb,
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800486 const aos::monotonic_clock::time_point monotonic_now,
Jim Ostrowski5e2c5e62023-02-26 12:52:56 -0800487 const std::vector<std::vector<cv::Point2f>> &corners,
488 const std::vector<double> rgba_color, const double thickness,
489 const foxglove::PointsAnnotationType line_type) {
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800490 std::vector<flatbuffers::Offset<foxglove::PointsAnnotation>> rectangles;
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800491 for (const std::vector<cv::Point2f> &rectangle : corners) {
Jim Ostrowski5e2c5e62023-02-26 12:52:56 -0800492 rectangles.push_back(BuildPointsAnnotation(
493 fbb, monotonic_now, rectangle, rgba_color, thickness, line_type));
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800494 }
495
496 const auto rectangles_offset = fbb->CreateVector(rectangles);
497 foxglove::ImageAnnotations::Builder annotation_builder(*fbb);
498 annotation_builder.add_points(rectangles_offset);
499 return annotation_builder.Finish();
500}
501
Jim Ostrowski5e2c5e62023-02-26 12:52:56 -0800502flatbuffers::Offset<foxglove::PointsAnnotation> BuildPointsAnnotation(
503 flatbuffers::FlatBufferBuilder *fbb,
504 const aos::monotonic_clock::time_point monotonic_now,
505 const std::vector<cv::Point2f> &corners,
506 const std::vector<double> rgba_color, const double thickness,
507 const foxglove::PointsAnnotationType line_type) {
508 const struct timespec now_t = aos::time::to_timespec(monotonic_now);
509 foxglove::Time time{static_cast<uint32_t>(now_t.tv_sec),
510 static_cast<uint32_t>(now_t.tv_nsec)};
511 const flatbuffers::Offset<foxglove::Color> color_offset =
512 foxglove::CreateColor(*fbb, rgba_color[0], rgba_color[1], rgba_color[2],
513 rgba_color[3]);
514 std::vector<flatbuffers::Offset<foxglove::Point2>> points_offsets;
515 for (const cv::Point2f &point : corners) {
516 points_offsets.push_back(foxglove::CreatePoint2(*fbb, point.x, point.y));
517 }
518 const flatbuffers::Offset<
519 flatbuffers::Vector<flatbuffers::Offset<foxglove::Point2>>>
520 points_offset = fbb->CreateVector(points_offsets);
521 std::vector<flatbuffers::Offset<foxglove::Color>> color_offsets(
522 points_offsets.size(), color_offset);
523 auto colors_offset = fbb->CreateVector(color_offsets);
524 foxglove::PointsAnnotation::Builder points_builder(*fbb);
525 points_builder.add_timestamp(&time);
526 points_builder.add_type(line_type);
527 points_builder.add_points(points_offset);
528 points_builder.add_outline_color(color_offset);
529 points_builder.add_outline_colors(colors_offset);
530 points_builder.add_thickness(thickness);
531
532 return points_builder.Finish();
533}
534
James Kuszmauld6199be2023-02-11 19:56:28 -0800535TargetType TargetTypeFromString(std::string_view str) {
536 if (str == "aruco") {
537 return TargetType::kAruco;
538 } else if (str == "charuco") {
539 return TargetType::kCharuco;
540 } else if (str == "charuco_diamond") {
541 return TargetType::kCharucoDiamond;
542 } else {
543 LOG(FATAL) << "Unknown target type: " << str
544 << ", expected: aruco|charuco|charuco_diamond";
545 }
546}
547
548std::ostream &operator<<(std::ostream &os, TargetType target_type) {
549 switch (target_type) {
550 case TargetType::kAruco:
551 os << "aruco";
552 break;
553 case TargetType::kCharuco:
554 os << "charuco";
555 break;
556 case TargetType::kCharucoDiamond:
557 os << "charuco_diamond";
558 break;
559 }
560 return os;
561}
562
Austin Schuh25837f22021-06-27 15:49:14 -0700563} // namespace vision
564} // namespace frc971