blob: ac708f6dedce273550ceead34a56a90ca42cf865 [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"
Austin Schuh25837f22021-06-27 15:49:14 -070016
Austin Schuh25837f22021-06-27 15:49:14 -070017DEFINE_string(board_template_path, "",
18 "If specified, write an image to the specified path for the "
19 "charuco board pattern.");
Jim Ostrowskib3cab972022-12-03 15:47:00 -080020DEFINE_bool(coarse_pattern, true, "If true, use coarse arucos; else, use fine");
Jim Ostrowski814d2812022-12-11 23:17:14 -080021DEFINE_uint32(gray_threshold, 0,
22 "If > 0, threshold image based on this grayscale value");
Jim Ostrowskib3cab972022-12-03 15:47:00 -080023DEFINE_bool(large_board, true, "If true, use the large calibration board.");
24DEFINE_uint32(
25 min_charucos, 10,
26 "The mininum number of aruco targets in charuco board required to match.");
Jim Ostrowskib3cab972022-12-03 15:47:00 -080027DEFINE_bool(visualize, false, "Whether to visualize the resulting data.");
Jim Ostrowski814d2812022-12-11 23:17:14 -080028DEFINE_bool(
29 draw_axes, false,
30 "Whether to draw axes on the resulting data-- warning, may cause crashes.");
Austin Schuh25837f22021-06-27 15:49:14 -070031
Austin Schuhc3419862023-01-08 13:54:36 -080032DEFINE_uint32(disable_delay, 100, "Time after an issue to disable tracing at.");
33
34DECLARE_bool(enable_ftrace);
35
Austin Schuh25837f22021-06-27 15:49:14 -070036namespace frc971 {
37namespace vision {
38namespace chrono = std::chrono;
Austin Schuhea7b0142021-10-08 22:04:53 -070039using aos::monotonic_clock;
Austin Schuh25837f22021-06-27 15:49:14 -070040
41CameraCalibration::CameraCalibration(
James Kuszmaul7e958812023-02-11 15:34:31 -080042 const calibration::CameraCalibration *calibration)
43 : intrinsics_([calibration]() {
44 const cv::Mat result(3, 3, CV_32F,
45 const_cast<void *>(static_cast<const void *>(
46 calibration->intrinsics()->data())));
47 CHECK_EQ(result.total(), calibration->intrinsics()->size());
48 return result;
49 }()),
50 intrinsics_eigen_([this]() {
51 cv::Mat camera_intrinsics = intrinsics_;
52 Eigen::Matrix3d result;
53 cv::cv2eigen(camera_intrinsics, result);
54 return result;
55 }()),
56 dist_coeffs_([calibration]() {
57 const cv::Mat result(5, 1, CV_32F,
58 const_cast<void *>(static_cast<const void *>(
59 calibration->dist_coeffs()->data())));
60 CHECK_EQ(result.total(), calibration->dist_coeffs()->size());
61 return result;
62 }()) {}
Austin Schuh25837f22021-06-27 15:49:14 -070063
Austin Schuhea7b0142021-10-08 22:04:53 -070064ImageCallback::ImageCallback(
65 aos::EventLoop *event_loop, std::string_view channel,
milind-u0cb53112023-02-03 20:32:55 -080066 std::function<void(cv::Mat, monotonic_clock::time_point)> &&handle_image_fn,
67 monotonic_clock::duration max_age)
Austin Schuhea7b0142021-10-08 22:04:53 -070068 : event_loop_(event_loop),
69 server_fetcher_(
70 event_loop_->MakeFetcher<aos::message_bridge::ServerStatistics>(
71 "/aos")),
72 source_node_(aos::configuration::GetNode(
73 event_loop_->configuration(),
74 event_loop_->GetChannel<CameraImage>(channel)
75 ->source_node()
76 ->string_view())),
Austin Schuhc3419862023-01-08 13:54:36 -080077 handle_image_(std::move(handle_image_fn)),
milind-u0cb53112023-02-03 20:32:55 -080078 timer_fn_(event_loop->AddTimer([this]() { DisableTracing(); })),
79 max_age_(max_age) {
Austin Schuh25837f22021-06-27 15:49:14 -070080 event_loop_->MakeWatcher(channel, [this](const CameraImage &image) {
Austin Schuhea7b0142021-10-08 22:04:53 -070081 const monotonic_clock::time_point eof_source_node =
82 monotonic_clock::time_point(
83 chrono::nanoseconds(image.monotonic_timestamp_ns()));
Austin Schuhea7b0142021-10-08 22:04:53 -070084 chrono::nanoseconds offset{0};
85 if (source_node_ != event_loop_->node()) {
Austin Schuhee8bc1e2021-11-20 16:23:41 -080086 server_fetcher_.Fetch();
87 if (!server_fetcher_.get()) {
88 return;
89 }
90
Austin Schuhea7b0142021-10-08 22:04:53 -070091 // If we are viewing this image from another node, convert to our
92 // monotonic clock.
93 const aos::message_bridge::ServerConnection *server_connection = nullptr;
94
95 for (const aos::message_bridge::ServerConnection *connection :
96 *server_fetcher_->connections()) {
97 CHECK(connection->has_node());
98 if (connection->node()->name()->string_view() ==
99 source_node_->name()->string_view()) {
100 server_connection = connection;
101 break;
102 }
103 }
104
105 CHECK(server_connection != nullptr) << ": Failed to find client";
106 if (!server_connection->has_monotonic_offset()) {
107 VLOG(1) << "No offset yet.";
108 return;
109 }
110 offset = chrono::nanoseconds(server_connection->monotonic_offset());
111 }
112
113 const monotonic_clock::time_point eof = eof_source_node - offset;
114
Jim Ostrowski977850f2022-01-22 21:04:22 -0800115 const monotonic_clock::duration age = event_loop_->monotonic_now() - eof;
Austin Schuh25837f22021-06-27 15:49:14 -0700116 const double age_double =
117 std::chrono::duration_cast<std::chrono::duration<double>>(age).count();
milind-u0cb53112023-02-03 20:32:55 -0800118 if (age > max_age_) {
Austin Schuhc3419862023-01-08 13:54:36 -0800119 if (FLAGS_enable_ftrace) {
120 ftrace_.FormatMessage("Too late receiving image, age: %f\n",
121 age_double);
122 if (FLAGS_disable_delay > 0) {
123 if (!disabling_) {
124 timer_fn_->Setup(event_loop_->monotonic_now() +
125 chrono::milliseconds(FLAGS_disable_delay));
126 disabling_ = true;
127 }
128 } else {
129 DisableTracing();
130 }
131 }
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800132 VLOG(2) << "Age: " << age_double << ", getting behind, skipping";
Austin Schuh25837f22021-06-27 15:49:14 -0700133 return;
134 }
135 // Create color image:
136 cv::Mat image_color_mat(cv::Size(image.cols(), image.rows()), CV_8UC2,
137 (void *)image.data()->data());
138 const cv::Size image_size(image.cols(), image.rows());
Austin Schuhac402e92023-01-08 13:56:20 -0800139 switch (format_) {
140 case Format::GRAYSCALE: {
141 ftrace_.FormatMessage("Starting yuyv->greyscale\n");
142 cv::Mat gray_image(image_size, CV_8UC3);
143 cv::cvtColor(image_color_mat, gray_image, cv::COLOR_YUV2GRAY_YUYV);
144 handle_image_(gray_image, eof);
145 } break;
146 case Format::BGR: {
147 cv::Mat rgb_image(image_size, CV_8UC3);
148 cv::cvtColor(image_color_mat, rgb_image, cv::COLOR_YUV2BGR_YUYV);
149 handle_image_(rgb_image, eof);
150 } break;
151 case Format::YUYV2: {
152 handle_image_(image_color_mat, eof);
153 };
154 }
Austin Schuh25837f22021-06-27 15:49:14 -0700155 });
156}
157
Austin Schuhc3419862023-01-08 13:54:36 -0800158void ImageCallback::DisableTracing() {
159 disabling_ = false;
160 ftrace_.TurnOffOrDie();
161}
162
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800163void CharucoExtractor::SetupTargetData() {
Jim Ostrowski814d2812022-12-11 23:17:14 -0800164 marker_length_ = 0.146;
165 square_length_ = 0.2;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800166
167 // Only charuco board has a board associated with it
168 board_ = static_cast<cv::Ptr<cv::aruco::CharucoBoard>>(NULL);
169
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800170 if (target_type_ == TargetType::kCharuco ||
171 target_type_ == TargetType::kAruco) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800172 dictionary_ = cv::aruco::getPredefinedDictionary(
173 FLAGS_large_board ? cv::aruco::DICT_5X5_250 : cv::aruco::DICT_6X6_250);
174
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800175 if (target_type_ == TargetType::kCharuco) {
Jim Ostrowski814d2812022-12-11 23:17:14 -0800176 LOG(INFO) << "Using " << (FLAGS_large_board ? "large" : "small")
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800177 << " charuco board with "
178 << (FLAGS_coarse_pattern ? "coarse" : "fine") << " pattern";
179 board_ =
180 (FLAGS_large_board
181 ? (FLAGS_coarse_pattern ? cv::aruco::CharucoBoard::create(
182 12, 9, 0.06, 0.04666, dictionary_)
183 : cv::aruco::CharucoBoard::create(
184 25, 18, 0.03, 0.0233, dictionary_))
185 : (FLAGS_coarse_pattern ? cv::aruco::CharucoBoard::create(
186 7, 5, 0.04, 0.025, dictionary_)
187 // TODO(jim): Need to figure out what
188 // size is for small board, fine pattern
189 : cv::aruco::CharucoBoard::create(
190 7, 5, 0.03, 0.0233, dictionary_)));
191 if (!FLAGS_board_template_path.empty()) {
192 cv::Mat board_image;
193 board_->draw(cv::Size(600, 500), board_image, 10, 1);
194 cv::imwrite(FLAGS_board_template_path, board_image);
195 }
196 }
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800197 } else if (target_type_ == TargetType::kCharucoDiamond) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800198 marker_length_ = 0.15;
Jim Ostrowski814d2812022-12-11 23:17:14 -0800199 square_length_ = 0.2;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800200 dictionary_ = cv::aruco::getPredefinedDictionary(cv::aruco::DICT_4X4_250);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800201 } else {
202 // Bail out if it's not a supported target
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800203 LOG(FATAL) << "Target type undefined: "
204 << static_cast<uint8_t>(target_type_);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800205 }
206}
207
208void CharucoExtractor::DrawTargetPoses(cv::Mat rgb_image,
209 std::vector<cv::Vec3d> rvecs,
210 std::vector<cv::Vec3d> tvecs) {
211 const Eigen::Matrix<double, 3, 4> camera_projection =
212 Eigen::Matrix<double, 3, 4>::Identity();
213
214 int x_coord = 10;
215 int y_coord = 0;
216 // draw axis for each marker
217 for (uint i = 0; i < rvecs.size(); i++) {
218 Eigen::Vector3d rvec_eigen, tvec_eigen;
219 cv::cv2eigen(rvecs[i], rvec_eigen);
220 cv::cv2eigen(tvecs[i], tvec_eigen);
221
222 Eigen::Quaternion<double> rotation(
223 frc971::controls::ToQuaternionFromRotationVector(rvec_eigen));
224 Eigen::Translation3d translation(tvec_eigen);
225
226 const Eigen::Affine3d board_to_camera = translation * rotation;
227
James Kuszmaul7e958812023-02-11 15:34:31 -0800228 Eigen::Vector3d result = calibration_.CameraIntrinsicsEigen() *
229 camera_projection * board_to_camera *
230 Eigen::Vector3d::Zero();
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800231
232 // Found that drawAxis hangs if you try to draw with z values too
233 // small (trying to draw axes at inifinity)
Jim Ostrowski814d2812022-12-11 23:17:14 -0800234 // TODO<Jim>: Either track this down or reimplement drawAxes
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800235 if (result.z() < 0.01) {
236 LOG(INFO) << "Skipping, due to z value too small: " << result.z();
Jim Ostrowski814d2812022-12-11 23:17:14 -0800237 } else if (FLAGS_draw_axes == true) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800238 result /= result.z();
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800239 if (target_type_ == TargetType::kCharuco) {
James Kuszmaul7e958812023-02-11 15:34:31 -0800240 cv::aruco::drawAxis(rgb_image, calibration_.CameraIntrinsics(),
Jim Ostrowski814d2812022-12-11 23:17:14 -0800241 calibration_.CameraDistCoeffs(), rvecs[i], tvecs[i],
242 0.1);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800243 } else {
James Kuszmaul7e958812023-02-11 15:34:31 -0800244 cv::drawFrameAxes(rgb_image, calibration_.CameraIntrinsics(),
245 calibration_.CameraDistCoeffs(), rvecs[i], tvecs[i],
246 0.1);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800247 }
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(
James Kuszmaul7e958812023-02-11 15:34:31 -0800280 aos::EventLoop *event_loop,
281 const calibration::CameraCalibration *calibration, TargetType target_type,
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800282 std::string_view image_channel,
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800283 std::function<void(cv::Mat, monotonic_clock::time_point,
284 std::vector<cv::Vec4i>,
285 std::vector<std::vector<cv::Point2f>>, bool,
286 std::vector<Eigen::Vector3d>,
287 std::vector<Eigen::Vector3d>)> &&handle_charuco_fn)
Austin Schuhea7b0142021-10-08 22:04:53 -0700288 : event_loop_(event_loop),
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800289 target_type_(target_type),
290 image_channel_(image_channel),
James Kuszmaul7e958812023-02-11 15:34:31 -0800291 calibration_(CHECK_NOTNULL(calibration)),
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
James Kuszmaul7e958812023-02-11 15:34:31 -0800295 LOG(INFO) << "Camera matrix " << calibration_.CameraIntrinsics();
296 LOG(INFO) << "Distortion Coefficients " << calibration_.CameraDistCoeffs();
Austin Schuh25837f22021-06-27 15:49:14 -0700297
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800298 LOG(INFO) << "Connecting to channel " << image_channel_;
Austin Schuh25837f22021-06-27 15:49:14 -0700299}
300
Austin Schuhea7b0142021-10-08 22:04:53 -0700301void CharucoExtractor::HandleImage(cv::Mat rgb_image,
302 const monotonic_clock::time_point eof) {
303 const double age_double =
304 std::chrono::duration_cast<std::chrono::duration<double>>(
305 event_loop_->monotonic_now() - eof)
306 .count();
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800307
Jim Ostrowski814d2812022-12-11 23:17:14 -0800308 // Have found this useful if there is blurry / noisy images
309 if (FLAGS_gray_threshold > 0) {
310 cv::Mat gray;
311 cv::cvtColor(rgb_image, gray, cv::COLOR_BGR2GRAY);
312
313 cv::Mat thresh;
314 cv::threshold(gray, thresh, FLAGS_gray_threshold, 255, cv::THRESH_BINARY);
315 cv::cvtColor(thresh, rgb_image, cv::COLOR_GRAY2RGB);
316 }
317
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800318 // Set up the variables we'll use in the callback function
319 bool valid = false;
320 // Return a list of poses; for Charuco Board there will be just one
321 std::vector<Eigen::Vector3d> rvecs_eigen;
322 std::vector<Eigen::Vector3d> tvecs_eigen;
323
324 // ids and corners for initial aruco marker detections
Austin Schuh25837f22021-06-27 15:49:14 -0700325 std::vector<int> marker_ids;
326 std::vector<std::vector<cv::Point2f>> marker_corners;
327
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800328 // ids and corners for final, refined board / marker detections
329 // Using Vec4i type since it supports Charuco Diamonds
330 // And overloading it using 1st int in Vec4i for others target types
331 std::vector<cv::Vec4i> result_ids;
332 std::vector<std::vector<cv::Point2f>> result_corners;
Austin Schuh25837f22021-06-27 15:49:14 -0700333
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800334 // Do initial marker detection; this is the same for all target types
335 cv::aruco::detectMarkers(rgb_image, dictionary_, marker_corners, marker_ids);
336 cv::aruco::drawDetectedMarkers(rgb_image, marker_corners, marker_ids);
Austin Schuhea7b0142021-10-08 22:04:53 -0700337
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800338 VLOG(2) << "Handle Image, with target type = "
339 << static_cast<uint8_t>(target_type_) << " and " << marker_ids.size()
340 << " markers detected initially";
Austin Schuh25837f22021-06-27 15:49:14 -0700341
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800342 if (marker_ids.size() == 0) {
343 VLOG(2) << "Didn't find any markers";
344 } else {
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800345 if (target_type_ == TargetType::kCharuco) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800346 std::vector<int> charuco_ids;
347 std::vector<cv::Point2f> charuco_corners;
Austin Schuh25837f22021-06-27 15:49:14 -0700348
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800349 // If enough aruco markers detected for the Charuco board
350 if (marker_ids.size() >= FLAGS_min_charucos) {
351 // Run everything twice, once with the calibration, and once
352 // without. This lets us both collect data to calibrate the
353 // intrinsics of the camera (to determine the intrinsics from
354 // multiple samples), and also to use data from a previous/stored
355 // calibration to determine a more accurate pose in real time (used
356 // for extrinsics calibration)
357 cv::aruco::interpolateCornersCharuco(marker_corners, marker_ids,
358 rgb_image, board_, charuco_corners,
359 charuco_ids);
Austin Schuh25837f22021-06-27 15:49:14 -0700360
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800361 std::vector<cv::Point2f> charuco_corners_with_calibration;
362 std::vector<int> charuco_ids_with_calibration;
Austin Schuh25837f22021-06-27 15:49:14 -0700363
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800364 // This call uses a previous intrinsic calibration to get more
365 // accurate marker locations, for a better pose estimate
366 cv::aruco::interpolateCornersCharuco(
367 marker_corners, marker_ids, rgb_image, board_,
368 charuco_corners_with_calibration, charuco_ids_with_calibration,
James Kuszmaul7e958812023-02-11 15:34:31 -0800369 calibration_.CameraIntrinsics(), calibration_.CameraDistCoeffs());
Austin Schuh25837f22021-06-27 15:49:14 -0700370
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800371 if (charuco_ids.size() >= FLAGS_min_charucos) {
372 cv::aruco::drawDetectedCornersCharuco(
373 rgb_image, charuco_corners, charuco_ids, cv::Scalar(255, 0, 0));
Austin Schuh25837f22021-06-27 15:49:14 -0700374
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800375 cv::Vec3d rvec, tvec;
376 valid = cv::aruco::estimatePoseCharucoBoard(
377 charuco_corners_with_calibration, charuco_ids_with_calibration,
James Kuszmaul7e958812023-02-11 15:34:31 -0800378 board_, calibration_.CameraIntrinsics(),
379 calibration_.CameraDistCoeffs(), rvec, tvec);
Austin Schuh25837f22021-06-27 15:49:14 -0700380
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800381 // if charuco pose is valid, return pose, with ids and corners
382 if (valid) {
383 std::vector<cv::Vec3d> rvecs, tvecs;
384 rvecs.emplace_back(rvec);
385 tvecs.emplace_back(tvec);
386 DrawTargetPoses(rgb_image, rvecs, tvecs);
Austin Schuh25837f22021-06-27 15:49:14 -0700387
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800388 PackPoseResults(rvecs, tvecs, &rvecs_eigen, &tvecs_eigen);
389 // Store the corners without calibration, since we use them to
390 // do calibration
391 result_corners.emplace_back(charuco_corners);
392 for (auto id : charuco_ids) {
393 result_ids.emplace_back(cv::Vec4i{id, 0, 0, 0});
394 }
395 } else {
396 VLOG(2) << "Age: " << age_double << ", invalid charuco board pose";
397 }
Jim Ostrowski634b2652022-03-04 02:10:53 -0800398 } else {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800399 VLOG(2) << "Age: " << age_double << ", not enough charuco IDs, got "
400 << charuco_ids.size() << ", needed " << FLAGS_min_charucos;
Jim Ostrowski634b2652022-03-04 02:10:53 -0800401 }
Austin Schuh25837f22021-06-27 15:49:14 -0700402 } else {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800403 VLOG(2) << "Age: " << age_double
404 << ", not enough marker IDs for charuco board, got "
405 << marker_ids.size() << ", needed " << FLAGS_min_charucos;
406 }
milind-u09fb1252023-01-28 19:21:41 -0800407 } else if (target_type_ == TargetType::kAruco) {
408 // estimate pose for arucos doesn't return valid, so marking true
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800409 valid = true;
410 std::vector<cv::Vec3d> rvecs, tvecs;
James Kuszmaul7e958812023-02-11 15:34:31 -0800411 cv::aruco::estimatePoseSingleMarkers(
412 marker_corners, square_length_, calibration_.CameraIntrinsics(),
413 calibration_.CameraDistCoeffs(), rvecs, tvecs);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800414 DrawTargetPoses(rgb_image, rvecs, tvecs);
415
416 PackPoseResults(rvecs, tvecs, &rvecs_eigen, &tvecs_eigen);
417 for (uint i = 0; i < marker_ids.size(); i++) {
418 result_ids.emplace_back(cv::Vec4i{marker_ids[i], 0, 0, 0});
419 }
420 result_corners = marker_corners;
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800421 } else if (target_type_ == TargetType::kCharucoDiamond) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800422 // Extract the diamonds associated with the markers
423 std::vector<cv::Vec4i> diamond_ids;
424 std::vector<std::vector<cv::Point2f>> diamond_corners;
425 cv::aruco::detectCharucoDiamond(rgb_image, marker_corners, marker_ids,
426 square_length_ / marker_length_,
427 diamond_corners, diamond_ids);
428
429 // Check to see if we found any diamond targets
430 if (diamond_ids.size() > 0) {
431 cv::aruco::drawDetectedDiamonds(rgb_image, diamond_corners,
432 diamond_ids);
433
434 // estimate pose for diamonds doesn't return valid, so marking true
435 valid = true;
436 std::vector<cv::Vec3d> rvecs, tvecs;
James Kuszmaul7e958812023-02-11 15:34:31 -0800437 cv::aruco::estimatePoseSingleMarkers(
438 diamond_corners, square_length_, calibration_.CameraIntrinsics(),
439 calibration_.CameraDistCoeffs(), rvecs, tvecs);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800440 DrawTargetPoses(rgb_image, rvecs, tvecs);
441
442 PackPoseResults(rvecs, tvecs, &rvecs_eigen, &tvecs_eigen);
443 result_ids = diamond_ids;
444 result_corners = diamond_corners;
445 } else {
446 VLOG(2) << "Found aruco markers, but no charuco diamond targets";
Austin Schuh25837f22021-06-27 15:49:14 -0700447 }
448 } else {
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800449 LOG(FATAL) << "Unknown target type: "
450 << static_cast<uint8_t>(target_type_);
Austin Schuh25837f22021-06-27 15:49:14 -0700451 }
Austin Schuh25837f22021-06-27 15:49:14 -0700452 }
Austin Schuhea7b0142021-10-08 22:04:53 -0700453
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800454 handle_charuco_(rgb_image, eof, result_ids, result_corners, valid,
455 rvecs_eigen, tvecs_eigen);
Austin Schuh25837f22021-06-27 15:49:14 -0700456}
457
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800458flatbuffers::Offset<foxglove::ImageAnnotations> BuildAnnotations(
Jim Ostrowski5e2c5e62023-02-26 12:52:56 -0800459 flatbuffers::FlatBufferBuilder *fbb,
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800460 const aos::monotonic_clock::time_point monotonic_now,
Jim Ostrowski5e2c5e62023-02-26 12:52:56 -0800461 const std::vector<std::vector<cv::Point2f>> &corners,
462 const std::vector<double> rgba_color, const double thickness,
463 const foxglove::PointsAnnotationType line_type) {
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800464 std::vector<flatbuffers::Offset<foxglove::PointsAnnotation>> rectangles;
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800465 for (const std::vector<cv::Point2f> &rectangle : corners) {
Jim Ostrowski5e2c5e62023-02-26 12:52:56 -0800466 rectangles.push_back(BuildPointsAnnotation(
467 fbb, monotonic_now, rectangle, rgba_color, thickness, line_type));
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800468 }
469
470 const auto rectangles_offset = fbb->CreateVector(rectangles);
471 foxglove::ImageAnnotations::Builder annotation_builder(*fbb);
472 annotation_builder.add_points(rectangles_offset);
473 return annotation_builder.Finish();
474}
475
Jim Ostrowski5e2c5e62023-02-26 12:52:56 -0800476flatbuffers::Offset<foxglove::PointsAnnotation> BuildPointsAnnotation(
477 flatbuffers::FlatBufferBuilder *fbb,
478 const aos::monotonic_clock::time_point monotonic_now,
479 const std::vector<cv::Point2f> &corners,
480 const std::vector<double> rgba_color, const double thickness,
481 const foxglove::PointsAnnotationType line_type) {
482 const struct timespec now_t = aos::time::to_timespec(monotonic_now);
483 foxglove::Time time{static_cast<uint32_t>(now_t.tv_sec),
484 static_cast<uint32_t>(now_t.tv_nsec)};
485 const flatbuffers::Offset<foxglove::Color> color_offset =
486 foxglove::CreateColor(*fbb, rgba_color[0], rgba_color[1], rgba_color[2],
487 rgba_color[3]);
488 std::vector<flatbuffers::Offset<foxglove::Point2>> points_offsets;
489 for (const cv::Point2f &point : corners) {
490 points_offsets.push_back(foxglove::CreatePoint2(*fbb, point.x, point.y));
491 }
492 const flatbuffers::Offset<
493 flatbuffers::Vector<flatbuffers::Offset<foxglove::Point2>>>
494 points_offset = fbb->CreateVector(points_offsets);
495 std::vector<flatbuffers::Offset<foxglove::Color>> color_offsets(
496 points_offsets.size(), color_offset);
497 auto colors_offset = fbb->CreateVector(color_offsets);
498 foxglove::PointsAnnotation::Builder points_builder(*fbb);
499 points_builder.add_timestamp(&time);
500 points_builder.add_type(line_type);
501 points_builder.add_points(points_offset);
502 points_builder.add_outline_color(color_offset);
503 points_builder.add_outline_colors(colors_offset);
504 points_builder.add_thickness(thickness);
505
506 return points_builder.Finish();
507}
508
James Kuszmauld6199be2023-02-11 19:56:28 -0800509TargetType TargetTypeFromString(std::string_view str) {
510 if (str == "aruco") {
511 return TargetType::kAruco;
512 } else if (str == "charuco") {
513 return TargetType::kCharuco;
514 } else if (str == "charuco_diamond") {
515 return TargetType::kCharucoDiamond;
516 } else {
517 LOG(FATAL) << "Unknown target type: " << str
518 << ", expected: aruco|charuco|charuco_diamond";
519 }
520}
521
522std::ostream &operator<<(std::ostream &os, TargetType target_type) {
523 switch (target_type) {
524 case TargetType::kAruco:
525 os << "aruco";
526 break;
527 case TargetType::kCharuco:
528 os << "charuco";
529 break;
530 case TargetType::kCharucoDiamond:
531 os << "charuco_diamond";
532 break;
533 }
534 return os;
535}
536
Austin Schuh25837f22021-06-27 15:49:14 -0700537} // namespace vision
538} // namespace frc971