Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 1 | #include "frc971/vision/charuco_lib.h" |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 2 | |
| 3 | #include <chrono> |
| 4 | #include <functional> |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 5 | #include <opencv2/core/eigen.hpp> |
| 6 | #include <opencv2/highgui/highgui.hpp> |
| 7 | #include <opencv2/imgproc.hpp> |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 8 | #include <string_view> |
| 9 | |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 10 | #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 Ostrowski | 977850f | 2022-01-22 21:04:22 -0800 | [diff] [blame] | 14 | #include "frc971/vision/vision_generated.h" |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 15 | #include "glog/logging.h" |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 16 | |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 17 | DEFINE_string(board_template_path, "", |
| 18 | "If specified, write an image to the specified path for the " |
| 19 | "charuco board pattern."); |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 20 | DEFINE_bool(coarse_pattern, true, "If true, use coarse arucos; else, use fine"); |
| 21 | DEFINE_bool(large_board, true, "If true, use the large calibration board."); |
| 22 | DEFINE_uint32( |
| 23 | min_charucos, 10, |
| 24 | "The mininum number of aruco targets in charuco board required to match."); |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 25 | DEFINE_bool(visualize, false, "Whether to visualize the resulting data."); |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 26 | |
Austin Schuh | c341986 | 2023-01-08 13:54:36 -0800 | [diff] [blame] | 27 | DEFINE_uint32(disable_delay, 100, "Time after an issue to disable tracing at."); |
| 28 | |
| 29 | DECLARE_bool(enable_ftrace); |
| 30 | |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 31 | namespace frc971 { |
| 32 | namespace vision { |
| 33 | namespace chrono = std::chrono; |
Austin Schuh | ea7b014 | 2021-10-08 22:04:53 -0700 | [diff] [blame] | 34 | using aos::monotonic_clock; |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 35 | |
| 36 | CameraCalibration::CameraCalibration( |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame^] | 37 | const calibration::CameraCalibration *calibration) |
| 38 | : intrinsics_([calibration]() { |
| 39 | const cv::Mat result(3, 3, CV_32F, |
| 40 | const_cast<void *>(static_cast<const void *>( |
| 41 | calibration->intrinsics()->data()))); |
| 42 | CHECK_EQ(result.total(), calibration->intrinsics()->size()); |
| 43 | return result; |
| 44 | }()), |
| 45 | intrinsics_eigen_([this]() { |
| 46 | cv::Mat camera_intrinsics = intrinsics_; |
| 47 | Eigen::Matrix3d result; |
| 48 | cv::cv2eigen(camera_intrinsics, result); |
| 49 | return result; |
| 50 | }()), |
| 51 | dist_coeffs_([calibration]() { |
| 52 | const cv::Mat result(5, 1, CV_32F, |
| 53 | const_cast<void *>(static_cast<const void *>( |
| 54 | calibration->dist_coeffs()->data()))); |
| 55 | CHECK_EQ(result.total(), calibration->dist_coeffs()->size()); |
| 56 | return result; |
| 57 | }()) {} |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 58 | |
Austin Schuh | ea7b014 | 2021-10-08 22:04:53 -0700 | [diff] [blame] | 59 | ImageCallback::ImageCallback( |
| 60 | aos::EventLoop *event_loop, std::string_view channel, |
milind-u | 0cb5311 | 2023-02-03 20:32:55 -0800 | [diff] [blame] | 61 | std::function<void(cv::Mat, monotonic_clock::time_point)> &&handle_image_fn, |
| 62 | monotonic_clock::duration max_age) |
Austin Schuh | ea7b014 | 2021-10-08 22:04:53 -0700 | [diff] [blame] | 63 | : event_loop_(event_loop), |
| 64 | server_fetcher_( |
| 65 | event_loop_->MakeFetcher<aos::message_bridge::ServerStatistics>( |
| 66 | "/aos")), |
| 67 | source_node_(aos::configuration::GetNode( |
| 68 | event_loop_->configuration(), |
| 69 | event_loop_->GetChannel<CameraImage>(channel) |
| 70 | ->source_node() |
| 71 | ->string_view())), |
Austin Schuh | c341986 | 2023-01-08 13:54:36 -0800 | [diff] [blame] | 72 | handle_image_(std::move(handle_image_fn)), |
milind-u | 0cb5311 | 2023-02-03 20:32:55 -0800 | [diff] [blame] | 73 | timer_fn_(event_loop->AddTimer([this]() { DisableTracing(); })), |
| 74 | max_age_(max_age) { |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 75 | event_loop_->MakeWatcher(channel, [this](const CameraImage &image) { |
Austin Schuh | ea7b014 | 2021-10-08 22:04:53 -0700 | [diff] [blame] | 76 | const monotonic_clock::time_point eof_source_node = |
| 77 | monotonic_clock::time_point( |
| 78 | chrono::nanoseconds(image.monotonic_timestamp_ns())); |
Austin Schuh | ea7b014 | 2021-10-08 22:04:53 -0700 | [diff] [blame] | 79 | chrono::nanoseconds offset{0}; |
| 80 | if (source_node_ != event_loop_->node()) { |
Austin Schuh | ee8bc1e | 2021-11-20 16:23:41 -0800 | [diff] [blame] | 81 | server_fetcher_.Fetch(); |
| 82 | if (!server_fetcher_.get()) { |
| 83 | return; |
| 84 | } |
| 85 | |
Austin Schuh | ea7b014 | 2021-10-08 22:04:53 -0700 | [diff] [blame] | 86 | // If we are viewing this image from another node, convert to our |
| 87 | // monotonic clock. |
| 88 | const aos::message_bridge::ServerConnection *server_connection = nullptr; |
| 89 | |
| 90 | for (const aos::message_bridge::ServerConnection *connection : |
| 91 | *server_fetcher_->connections()) { |
| 92 | CHECK(connection->has_node()); |
| 93 | if (connection->node()->name()->string_view() == |
| 94 | source_node_->name()->string_view()) { |
| 95 | server_connection = connection; |
| 96 | break; |
| 97 | } |
| 98 | } |
| 99 | |
| 100 | CHECK(server_connection != nullptr) << ": Failed to find client"; |
| 101 | if (!server_connection->has_monotonic_offset()) { |
| 102 | VLOG(1) << "No offset yet."; |
| 103 | return; |
| 104 | } |
| 105 | offset = chrono::nanoseconds(server_connection->monotonic_offset()); |
| 106 | } |
| 107 | |
| 108 | const monotonic_clock::time_point eof = eof_source_node - offset; |
| 109 | |
Jim Ostrowski | 977850f | 2022-01-22 21:04:22 -0800 | [diff] [blame] | 110 | const monotonic_clock::duration age = event_loop_->monotonic_now() - eof; |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 111 | const double age_double = |
| 112 | std::chrono::duration_cast<std::chrono::duration<double>>(age).count(); |
milind-u | 0cb5311 | 2023-02-03 20:32:55 -0800 | [diff] [blame] | 113 | if (age > max_age_) { |
Austin Schuh | c341986 | 2023-01-08 13:54:36 -0800 | [diff] [blame] | 114 | if (FLAGS_enable_ftrace) { |
| 115 | ftrace_.FormatMessage("Too late receiving image, age: %f\n", |
| 116 | age_double); |
| 117 | if (FLAGS_disable_delay > 0) { |
| 118 | if (!disabling_) { |
| 119 | timer_fn_->Setup(event_loop_->monotonic_now() + |
| 120 | chrono::milliseconds(FLAGS_disable_delay)); |
| 121 | disabling_ = true; |
| 122 | } |
| 123 | } else { |
| 124 | DisableTracing(); |
| 125 | } |
| 126 | } |
Jim Ostrowski | fec0c33 | 2022-02-06 23:28:26 -0800 | [diff] [blame] | 127 | VLOG(2) << "Age: " << age_double << ", getting behind, skipping"; |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 128 | return; |
| 129 | } |
| 130 | // Create color image: |
| 131 | cv::Mat image_color_mat(cv::Size(image.cols(), image.rows()), CV_8UC2, |
| 132 | (void *)image.data()->data()); |
| 133 | const cv::Size image_size(image.cols(), image.rows()); |
Austin Schuh | ac402e9 | 2023-01-08 13:56:20 -0800 | [diff] [blame] | 134 | switch (format_) { |
| 135 | case Format::GRAYSCALE: { |
| 136 | ftrace_.FormatMessage("Starting yuyv->greyscale\n"); |
| 137 | cv::Mat gray_image(image_size, CV_8UC3); |
| 138 | cv::cvtColor(image_color_mat, gray_image, cv::COLOR_YUV2GRAY_YUYV); |
| 139 | handle_image_(gray_image, eof); |
| 140 | } break; |
| 141 | case Format::BGR: { |
| 142 | cv::Mat rgb_image(image_size, CV_8UC3); |
| 143 | cv::cvtColor(image_color_mat, rgb_image, cv::COLOR_YUV2BGR_YUYV); |
| 144 | handle_image_(rgb_image, eof); |
| 145 | } break; |
| 146 | case Format::YUYV2: { |
| 147 | handle_image_(image_color_mat, eof); |
| 148 | }; |
| 149 | } |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 150 | }); |
| 151 | } |
| 152 | |
Austin Schuh | c341986 | 2023-01-08 13:54:36 -0800 | [diff] [blame] | 153 | void ImageCallback::DisableTracing() { |
| 154 | disabling_ = false; |
| 155 | ftrace_.TurnOffOrDie(); |
| 156 | } |
| 157 | |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 158 | void CharucoExtractor::SetupTargetData() { |
| 159 | // TODO(Jim): Put correct values here |
| 160 | marker_length_ = 0.15; |
| 161 | square_length_ = 0.1651; |
| 162 | |
| 163 | // Only charuco board has a board associated with it |
| 164 | board_ = static_cast<cv::Ptr<cv::aruco::CharucoBoard>>(NULL); |
| 165 | |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 166 | if (target_type_ == TargetType::kCharuco || |
| 167 | target_type_ == TargetType::kAruco) { |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 168 | dictionary_ = cv::aruco::getPredefinedDictionary( |
| 169 | FLAGS_large_board ? cv::aruco::DICT_5X5_250 : cv::aruco::DICT_6X6_250); |
| 170 | |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 171 | if (target_type_ == TargetType::kCharuco) { |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 172 | LOG(INFO) << "Using " << (FLAGS_large_board ? " large " : " small ") |
| 173 | << " charuco board with " |
| 174 | << (FLAGS_coarse_pattern ? "coarse" : "fine") << " pattern"; |
| 175 | board_ = |
| 176 | (FLAGS_large_board |
| 177 | ? (FLAGS_coarse_pattern ? cv::aruco::CharucoBoard::create( |
| 178 | 12, 9, 0.06, 0.04666, dictionary_) |
| 179 | : cv::aruco::CharucoBoard::create( |
| 180 | 25, 18, 0.03, 0.0233, dictionary_)) |
| 181 | : (FLAGS_coarse_pattern ? cv::aruco::CharucoBoard::create( |
| 182 | 7, 5, 0.04, 0.025, dictionary_) |
| 183 | // TODO(jim): Need to figure out what |
| 184 | // size is for small board, fine pattern |
| 185 | : cv::aruco::CharucoBoard::create( |
| 186 | 7, 5, 0.03, 0.0233, dictionary_))); |
| 187 | if (!FLAGS_board_template_path.empty()) { |
| 188 | cv::Mat board_image; |
| 189 | board_->draw(cv::Size(600, 500), board_image, 10, 1); |
| 190 | cv::imwrite(FLAGS_board_template_path, board_image); |
| 191 | } |
| 192 | } |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 193 | } else if (target_type_ == TargetType::kCharucoDiamond) { |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 194 | // TODO<Jim>: Measure this |
| 195 | marker_length_ = 0.15; |
| 196 | square_length_ = 0.1651; |
| 197 | dictionary_ = cv::aruco::getPredefinedDictionary(cv::aruco::DICT_4X4_250); |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 198 | } else { |
| 199 | // Bail out if it's not a supported target |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 200 | LOG(FATAL) << "Target type undefined: " |
| 201 | << static_cast<uint8_t>(target_type_); |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 202 | } |
| 203 | } |
| 204 | |
| 205 | void CharucoExtractor::DrawTargetPoses(cv::Mat rgb_image, |
| 206 | std::vector<cv::Vec3d> rvecs, |
| 207 | std::vector<cv::Vec3d> tvecs) { |
| 208 | const Eigen::Matrix<double, 3, 4> camera_projection = |
| 209 | Eigen::Matrix<double, 3, 4>::Identity(); |
| 210 | |
| 211 | int x_coord = 10; |
| 212 | int y_coord = 0; |
| 213 | // draw axis for each marker |
| 214 | for (uint i = 0; i < rvecs.size(); i++) { |
| 215 | Eigen::Vector3d rvec_eigen, tvec_eigen; |
| 216 | cv::cv2eigen(rvecs[i], rvec_eigen); |
| 217 | cv::cv2eigen(tvecs[i], tvec_eigen); |
| 218 | |
| 219 | Eigen::Quaternion<double> rotation( |
| 220 | frc971::controls::ToQuaternionFromRotationVector(rvec_eigen)); |
| 221 | Eigen::Translation3d translation(tvec_eigen); |
| 222 | |
| 223 | const Eigen::Affine3d board_to_camera = translation * rotation; |
| 224 | |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame^] | 225 | Eigen::Vector3d result = calibration_.CameraIntrinsicsEigen() * |
| 226 | camera_projection * board_to_camera * |
| 227 | Eigen::Vector3d::Zero(); |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 228 | |
| 229 | // Found that drawAxis hangs if you try to draw with z values too |
| 230 | // small (trying to draw axes at inifinity) |
| 231 | // TODO<Jim>: Explore what real thresholds for this should be; |
| 232 | // likely Don't need to get rid of negative values |
| 233 | if (result.z() < 0.01) { |
| 234 | LOG(INFO) << "Skipping, due to z value too small: " << result.z(); |
| 235 | } else { |
| 236 | result /= result.z(); |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 237 | if (target_type_ == TargetType::kCharuco) { |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame^] | 238 | cv::aruco::drawAxis(rgb_image, calibration_.CameraIntrinsics(), |
| 239 | calibration_.CameraDistCoeffs(), rvecs[i], |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 240 | tvecs[i], 0.1); |
| 241 | } else { |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame^] | 242 | cv::drawFrameAxes(rgb_image, calibration_.CameraIntrinsics(), |
| 243 | calibration_.CameraDistCoeffs(), rvecs[i], tvecs[i], |
| 244 | 0.1); |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 245 | } |
| 246 | } |
| 247 | std::stringstream ss; |
| 248 | ss << "tvec[" << i << "] = " << tvecs[i]; |
| 249 | y_coord += 25; |
| 250 | cv::putText(rgb_image, ss.str(), cv::Point(x_coord, y_coord), |
| 251 | cv::FONT_HERSHEY_PLAIN, 1.0, cv::Scalar(255, 255, 255)); |
| 252 | ss.str(""); |
| 253 | ss << "rvec[" << i << "] = " << rvecs[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 | } |
| 258 | } |
| 259 | |
| 260 | void CharucoExtractor::PackPoseResults( |
| 261 | std::vector<cv::Vec3d> &rvecs, std::vector<cv::Vec3d> &tvecs, |
| 262 | std::vector<Eigen::Vector3d> *rvecs_eigen, |
| 263 | std::vector<Eigen::Vector3d> *tvecs_eigen) { |
| 264 | for (cv::Vec3d rvec : rvecs) { |
| 265 | Eigen::Vector3d rvec_eigen = Eigen::Vector3d::Zero(); |
| 266 | cv::cv2eigen(rvec, rvec_eigen); |
| 267 | rvecs_eigen->emplace_back(rvec_eigen); |
| 268 | } |
| 269 | |
| 270 | for (cv::Vec3d tvec : tvecs) { |
| 271 | Eigen::Vector3d tvec_eigen = Eigen::Vector3d::Zero(); |
| 272 | cv::cv2eigen(tvec, tvec_eigen); |
| 273 | tvecs_eigen->emplace_back(tvec_eigen); |
| 274 | } |
| 275 | } |
| 276 | |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 277 | CharucoExtractor::CharucoExtractor( |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame^] | 278 | aos::EventLoop *event_loop, |
| 279 | const calibration::CameraCalibration *calibration, TargetType target_type, |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 280 | std::string_view image_channel, |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 281 | std::function<void(cv::Mat, monotonic_clock::time_point, |
| 282 | std::vector<cv::Vec4i>, |
| 283 | std::vector<std::vector<cv::Point2f>>, bool, |
| 284 | std::vector<Eigen::Vector3d>, |
| 285 | std::vector<Eigen::Vector3d>)> &&handle_charuco_fn) |
Austin Schuh | ea7b014 | 2021-10-08 22:04:53 -0700 | [diff] [blame] | 286 | : event_loop_(event_loop), |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 287 | target_type_(target_type), |
| 288 | image_channel_(image_channel), |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame^] | 289 | calibration_(CHECK_NOTNULL(calibration)), |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 290 | handle_charuco_(std::move(handle_charuco_fn)) { |
| 291 | SetupTargetData(); |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 292 | |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame^] | 293 | LOG(INFO) << "Camera matrix " << calibration_.CameraIntrinsics(); |
| 294 | LOG(INFO) << "Distortion Coefficients " << calibration_.CameraDistCoeffs(); |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 295 | |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 296 | LOG(INFO) << "Connecting to channel " << image_channel_; |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 297 | } |
| 298 | |
Austin Schuh | ea7b014 | 2021-10-08 22:04:53 -0700 | [diff] [blame] | 299 | void CharucoExtractor::HandleImage(cv::Mat rgb_image, |
| 300 | const monotonic_clock::time_point eof) { |
| 301 | const double age_double = |
| 302 | std::chrono::duration_cast<std::chrono::duration<double>>( |
| 303 | event_loop_->monotonic_now() - eof) |
| 304 | .count(); |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 305 | |
| 306 | // Set up the variables we'll use in the callback function |
| 307 | bool valid = false; |
| 308 | // Return a list of poses; for Charuco Board there will be just one |
| 309 | std::vector<Eigen::Vector3d> rvecs_eigen; |
| 310 | std::vector<Eigen::Vector3d> tvecs_eigen; |
| 311 | |
| 312 | // ids and corners for initial aruco marker detections |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 313 | std::vector<int> marker_ids; |
| 314 | std::vector<std::vector<cv::Point2f>> marker_corners; |
| 315 | |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 316 | // ids and corners for final, refined board / marker detections |
| 317 | // Using Vec4i type since it supports Charuco Diamonds |
| 318 | // And overloading it using 1st int in Vec4i for others target types |
| 319 | std::vector<cv::Vec4i> result_ids; |
| 320 | std::vector<std::vector<cv::Point2f>> result_corners; |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 321 | |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 322 | // Do initial marker detection; this is the same for all target types |
| 323 | cv::aruco::detectMarkers(rgb_image, dictionary_, marker_corners, marker_ids); |
| 324 | cv::aruco::drawDetectedMarkers(rgb_image, marker_corners, marker_ids); |
Austin Schuh | ea7b014 | 2021-10-08 22:04:53 -0700 | [diff] [blame] | 325 | |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 326 | VLOG(2) << "Handle Image, with target type = " |
| 327 | << static_cast<uint8_t>(target_type_) << " and " << marker_ids.size() |
| 328 | << " markers detected initially"; |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 329 | |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 330 | if (marker_ids.size() == 0) { |
| 331 | VLOG(2) << "Didn't find any markers"; |
| 332 | } else { |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 333 | if (target_type_ == TargetType::kCharuco) { |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 334 | std::vector<int> charuco_ids; |
| 335 | std::vector<cv::Point2f> charuco_corners; |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 336 | |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 337 | // If enough aruco markers detected for the Charuco board |
| 338 | if (marker_ids.size() >= FLAGS_min_charucos) { |
| 339 | // Run everything twice, once with the calibration, and once |
| 340 | // without. This lets us both collect data to calibrate the |
| 341 | // intrinsics of the camera (to determine the intrinsics from |
| 342 | // multiple samples), and also to use data from a previous/stored |
| 343 | // calibration to determine a more accurate pose in real time (used |
| 344 | // for extrinsics calibration) |
| 345 | cv::aruco::interpolateCornersCharuco(marker_corners, marker_ids, |
| 346 | rgb_image, board_, charuco_corners, |
| 347 | charuco_ids); |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 348 | |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 349 | std::vector<cv::Point2f> charuco_corners_with_calibration; |
| 350 | std::vector<int> charuco_ids_with_calibration; |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 351 | |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 352 | // This call uses a previous intrinsic calibration to get more |
| 353 | // accurate marker locations, for a better pose estimate |
| 354 | cv::aruco::interpolateCornersCharuco( |
| 355 | marker_corners, marker_ids, rgb_image, board_, |
| 356 | charuco_corners_with_calibration, charuco_ids_with_calibration, |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame^] | 357 | calibration_.CameraIntrinsics(), calibration_.CameraDistCoeffs()); |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 358 | |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 359 | if (charuco_ids.size() >= FLAGS_min_charucos) { |
| 360 | cv::aruco::drawDetectedCornersCharuco( |
| 361 | rgb_image, charuco_corners, charuco_ids, cv::Scalar(255, 0, 0)); |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 362 | |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 363 | cv::Vec3d rvec, tvec; |
| 364 | valid = cv::aruco::estimatePoseCharucoBoard( |
| 365 | charuco_corners_with_calibration, charuco_ids_with_calibration, |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame^] | 366 | board_, calibration_.CameraIntrinsics(), |
| 367 | calibration_.CameraDistCoeffs(), rvec, tvec); |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 368 | |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 369 | // if charuco pose is valid, return pose, with ids and corners |
| 370 | if (valid) { |
| 371 | std::vector<cv::Vec3d> rvecs, tvecs; |
| 372 | rvecs.emplace_back(rvec); |
| 373 | tvecs.emplace_back(tvec); |
| 374 | DrawTargetPoses(rgb_image, rvecs, tvecs); |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 375 | |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 376 | PackPoseResults(rvecs, tvecs, &rvecs_eigen, &tvecs_eigen); |
| 377 | // Store the corners without calibration, since we use them to |
| 378 | // do calibration |
| 379 | result_corners.emplace_back(charuco_corners); |
| 380 | for (auto id : charuco_ids) { |
| 381 | result_ids.emplace_back(cv::Vec4i{id, 0, 0, 0}); |
| 382 | } |
| 383 | } else { |
| 384 | VLOG(2) << "Age: " << age_double << ", invalid charuco board pose"; |
| 385 | } |
Jim Ostrowski | 634b265 | 2022-03-04 02:10:53 -0800 | [diff] [blame] | 386 | } else { |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 387 | VLOG(2) << "Age: " << age_double << ", not enough charuco IDs, got " |
| 388 | << charuco_ids.size() << ", needed " << FLAGS_min_charucos; |
Jim Ostrowski | 634b265 | 2022-03-04 02:10:53 -0800 | [diff] [blame] | 389 | } |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 390 | } else { |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 391 | VLOG(2) << "Age: " << age_double |
| 392 | << ", not enough marker IDs for charuco board, got " |
| 393 | << marker_ids.size() << ", needed " << FLAGS_min_charucos; |
| 394 | } |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 395 | } else if (target_type_ == TargetType::kAruco) { |
| 396 | // estimate pose for arucos doesn't return valid, so marking true |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 397 | valid = true; |
| 398 | std::vector<cv::Vec3d> rvecs, tvecs; |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame^] | 399 | cv::aruco::estimatePoseSingleMarkers( |
| 400 | marker_corners, square_length_, calibration_.CameraIntrinsics(), |
| 401 | calibration_.CameraDistCoeffs(), rvecs, tvecs); |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 402 | DrawTargetPoses(rgb_image, rvecs, tvecs); |
| 403 | |
| 404 | PackPoseResults(rvecs, tvecs, &rvecs_eigen, &tvecs_eigen); |
| 405 | for (uint i = 0; i < marker_ids.size(); i++) { |
| 406 | result_ids.emplace_back(cv::Vec4i{marker_ids[i], 0, 0, 0}); |
| 407 | } |
| 408 | result_corners = marker_corners; |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 409 | } else if (target_type_ == TargetType::kCharucoDiamond) { |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 410 | // Extract the diamonds associated with the markers |
| 411 | std::vector<cv::Vec4i> diamond_ids; |
| 412 | std::vector<std::vector<cv::Point2f>> diamond_corners; |
| 413 | cv::aruco::detectCharucoDiamond(rgb_image, marker_corners, marker_ids, |
| 414 | square_length_ / marker_length_, |
| 415 | diamond_corners, diamond_ids); |
| 416 | |
| 417 | // Check to see if we found any diamond targets |
| 418 | if (diamond_ids.size() > 0) { |
| 419 | cv::aruco::drawDetectedDiamonds(rgb_image, diamond_corners, |
| 420 | diamond_ids); |
| 421 | |
| 422 | // estimate pose for diamonds doesn't return valid, so marking true |
| 423 | valid = true; |
| 424 | std::vector<cv::Vec3d> rvecs, tvecs; |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame^] | 425 | cv::aruco::estimatePoseSingleMarkers( |
| 426 | diamond_corners, square_length_, calibration_.CameraIntrinsics(), |
| 427 | calibration_.CameraDistCoeffs(), rvecs, tvecs); |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 428 | DrawTargetPoses(rgb_image, rvecs, tvecs); |
| 429 | |
| 430 | PackPoseResults(rvecs, tvecs, &rvecs_eigen, &tvecs_eigen); |
| 431 | result_ids = diamond_ids; |
| 432 | result_corners = diamond_corners; |
| 433 | } else { |
| 434 | VLOG(2) << "Found aruco markers, but no charuco diamond targets"; |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 435 | } |
| 436 | } else { |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 437 | LOG(FATAL) << "Unknown target type: " |
| 438 | << static_cast<uint8_t>(target_type_); |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 439 | } |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 440 | } |
Austin Schuh | ea7b014 | 2021-10-08 22:04:53 -0700 | [diff] [blame] | 441 | |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 442 | handle_charuco_(rgb_image, eof, result_ids, result_corners, valid, |
| 443 | rvecs_eigen, tvecs_eigen); |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 444 | } |
| 445 | |
James Kuszmaul | 969e4ab | 2023-01-28 16:09:19 -0800 | [diff] [blame] | 446 | flatbuffers::Offset<foxglove::ImageAnnotations> BuildAnnotations( |
| 447 | const aos::monotonic_clock::time_point monotonic_now, |
| 448 | const std::vector<std::vector<cv::Point2f>> &corners, |
| 449 | flatbuffers::FlatBufferBuilder *fbb) { |
| 450 | std::vector<flatbuffers::Offset<foxglove::PointsAnnotation>> rectangles; |
| 451 | const struct timespec now_t = aos::time::to_timespec(monotonic_now); |
| 452 | foxglove::Time time{static_cast<uint32_t>(now_t.tv_sec), |
| 453 | static_cast<uint32_t>(now_t.tv_nsec)}; |
| 454 | const flatbuffers::Offset<foxglove::Color> color_offset = |
| 455 | foxglove::CreateColor(*fbb, 0.0, 1.0, 0.0, 1.0); |
| 456 | for (const std::vector<cv::Point2f> &rectangle : corners) { |
| 457 | std::vector<flatbuffers::Offset<foxglove::Point2>> points_offsets; |
| 458 | for (const cv::Point2f &point : rectangle) { |
| 459 | points_offsets.push_back(foxglove::CreatePoint2(*fbb, point.x, point.y)); |
| 460 | } |
| 461 | const flatbuffers::Offset< |
| 462 | flatbuffers::Vector<flatbuffers::Offset<foxglove::Point2>>> |
| 463 | points_offset = fbb->CreateVector(points_offsets); |
| 464 | std::vector<flatbuffers::Offset<foxglove::Color>> color_offsets( |
| 465 | points_offsets.size(), color_offset); |
| 466 | auto colors_offset = fbb->CreateVector(color_offsets); |
| 467 | foxglove::PointsAnnotation::Builder points_builder(*fbb); |
| 468 | points_builder.add_timestamp(&time); |
| 469 | points_builder.add_type(foxglove::PointsAnnotationType::POINTS); |
| 470 | points_builder.add_points(points_offset); |
| 471 | points_builder.add_outline_color(color_offset); |
| 472 | points_builder.add_outline_colors(colors_offset); |
| 473 | points_builder.add_thickness(2.0); |
| 474 | rectangles.push_back(points_builder.Finish()); |
| 475 | } |
| 476 | |
| 477 | const auto rectangles_offset = fbb->CreateVector(rectangles); |
| 478 | foxglove::ImageAnnotations::Builder annotation_builder(*fbb); |
| 479 | annotation_builder.add_points(rectangles_offset); |
| 480 | return annotation_builder.Finish(); |
| 481 | } |
| 482 | |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 483 | } // namespace vision |
| 484 | } // namespace frc971 |