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