blob: c86663a8d1fedc866874b473c5c6174a1f377ece [file] [log] [blame]
Austin Schuh25837f22021-06-27 15:49:14 -07001#include "y2020/vision/charuco_lib.h"
2
3#include <chrono>
4#include <functional>
5#include <string_view>
6
7#include <opencv2/core/eigen.hpp>
8#include <opencv2/highgui/highgui.hpp>
9#include <opencv2/imgproc.hpp>
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"
14#include "glog/logging.h"
15#include "y2020/vision/sift/sift_generated.h"
16#include "y2020/vision/sift/sift_training_generated.h"
17#include "y2020/vision/tools/python_code/sift_training_data.h"
18#include "y2020/vision/vision_generated.h"
19
20DEFINE_uint32(min_targets, 10,
21 "The mininum number of targets required to match.");
22DEFINE_bool(large_board, true, "If true, use the large calibration board.");
23DEFINE_bool(coarse_pattern, true, "If true, use coarse arucos; else, use fine");
24DEFINE_string(board_template_path, "",
25 "If specified, write an image to the specified path for the "
26 "charuco board pattern.");
27
28namespace frc971 {
29namespace vision {
30namespace chrono = std::chrono;
31
32CameraCalibration::CameraCalibration(
33 const absl::Span<const uint8_t> training_data_bfbs, std::string_view pi) {
34 const aos::FlatbufferSpan<sift::TrainingData> training_data(
35 training_data_bfbs);
36 CHECK(training_data.Verify());
37 camera_calibration_ = FindCameraCalibration(&training_data.message(), pi);
38}
39
40cv::Mat CameraCalibration::CameraIntrinsics() const {
41 const cv::Mat result(3, 3, CV_32F,
42 const_cast<void *>(static_cast<const void *>(
43 camera_calibration_->intrinsics()->data())));
44 CHECK_EQ(result.total(), camera_calibration_->intrinsics()->size());
45 return result;
46}
47
48Eigen::Matrix3d CameraCalibration::CameraIntrinsicsEigen() const {
49 cv::Mat camera_intrinsics = CameraIntrinsics();
50 Eigen::Matrix3d result;
51 cv::cv2eigen(camera_intrinsics, result);
52 return result;
53}
54
55cv::Mat CameraCalibration::CameraDistCoeffs() const {
56 const cv::Mat result(5, 1, CV_32F,
57 const_cast<void *>(static_cast<const void *>(
58 camera_calibration_->dist_coeffs()->data())));
59 CHECK_EQ(result.total(), camera_calibration_->dist_coeffs()->size());
60 return result;
61}
62
63const sift::CameraCalibration *CameraCalibration::FindCameraCalibration(
64 const sift::TrainingData *const training_data, std::string_view pi) const {
65 std::optional<uint16_t> pi_number = aos::network::ParsePiNumber(pi);
66 std::optional<uint16_t> team_number =
67 aos::network::team_number_internal::ParsePiTeamNumber(pi);
68 CHECK(pi_number);
69 CHECK(team_number);
70 const std::string node_name = absl::StrFormat("pi%d", pi_number.value());
71 LOG(INFO) << "Looking for node name " << node_name << " team number "
72 << team_number.value();
73 for (const sift::CameraCalibration *candidate :
74 *training_data->camera_calibrations()) {
75 if (candidate->node_name()->string_view() != node_name) {
76 continue;
77 }
78 if (candidate->team_number() != team_number.value()) {
79 continue;
80 }
81 return candidate;
82 }
83 LOG(FATAL) << ": Failed to find camera calibration for " << node_name
84 << " on " << team_number.value();
85}
86
87ImageCallback::ImageCallback(aos::EventLoop *event_loop,
88 std::string_view channel,
89 std::function<void(cv::Mat, double)> &&fn)
90 : event_loop_(event_loop), handle_image_(std::move(fn)) {
91 event_loop_->MakeWatcher(channel, [this](const CameraImage &image) {
92 const aos::monotonic_clock::duration age =
93 event_loop_->monotonic_now() -
94 event_loop_->context().monotonic_event_time;
95 const double age_double =
96 std::chrono::duration_cast<std::chrono::duration<double>>(age).count();
97 if (age > std::chrono::milliseconds(100)) {
98 LOG(INFO) << "Age: " << age_double << ", getting behind, skipping";
99 return;
100 }
101 // Create color image:
102 cv::Mat image_color_mat(cv::Size(image.cols(), image.rows()), CV_8UC2,
103 (void *)image.data()->data());
104 const cv::Size image_size(image.cols(), image.rows());
105 cv::Mat rgb_image(image_size, CV_8UC3);
106 cv::cvtColor(image_color_mat, rgb_image, CV_YUV2BGR_YUYV);
107 handle_image_(rgb_image, age_double);
108 });
109}
110
111CharucoExtractor::CharucoExtractor(
112 aos::EventLoop *event_loop, std::string_view pi,
113 std::function<void(cv::Mat, const double, std::vector<int>,
114 std::vector<cv::Point2f>, bool, Eigen::Vector3d,
115 Eigen::Vector3d)> &&fn)
116 : calibration_(SiftTrainingData(), pi),
117 dictionary_(cv::aruco::getPredefinedDictionary(
118 FLAGS_large_board ? cv::aruco::DICT_5X5_250
119 : cv::aruco::DICT_6X6_250)),
120 board_(
121 FLAGS_large_board
122 ? (FLAGS_coarse_pattern ? cv::aruco::CharucoBoard::create(
123 12, 9, 0.06, 0.04666, dictionary_)
124 : cv::aruco::CharucoBoard::create(
125 25, 18, 0.03, 0.0233, dictionary_))
126 : (FLAGS_coarse_pattern ? cv::aruco::CharucoBoard::create(
127 7, 5, 0.04, 0.025, dictionary_)
128 // TODO(jim): Need to figure out what size
129 // is for small board, fine pattern
130 : cv::aruco::CharucoBoard::create(
131 7, 5, 0.03, 0.0233, dictionary_))),
132 camera_matrix_(calibration_.CameraIntrinsics()),
133 eigen_camera_matrix_(calibration_.CameraIntrinsicsEigen()),
134 dist_coeffs_(calibration_.CameraDistCoeffs()),
135 pi_number_(aos::network::ParsePiNumber(pi)),
136 image_callback_(
137 event_loop,
138 absl::StrCat("/pi", std::to_string(pi_number_.value()), "/camera"),
139 [this](cv::Mat rgb_image, const double age_double) {
140 HandleImage(rgb_image, age_double);
141 }),
142 handle_charuco_(std::move(fn)) {
143 LOG(INFO) << "Using " << (FLAGS_large_board ? "large" : "small")
144 << " board with " << (FLAGS_coarse_pattern ? "coarse" : "fine")
145 << " pattern";
146 if (!FLAGS_board_template_path.empty()) {
147 cv::Mat board_image;
148 board_->draw(cv::Size(600, 500), board_image, 10, 1);
149 cv::imwrite(FLAGS_board_template_path, board_image);
150 }
151
152 LOG(INFO) << "Camera matrix " << camera_matrix_;
153 LOG(INFO) << "Distortion Coefficients " << dist_coeffs_;
154
155 CHECK(pi_number_) << ": Invalid pi number " << pi
156 << ", failed to parse pi number";
157
158 LOG(INFO) << "Connecting to channel /pi" << pi_number_.value() << "/camera";
159}
160
161void CharucoExtractor::HandleImage(cv::Mat rgb_image, const double age_double) {
162 std::vector<int> marker_ids;
163 std::vector<std::vector<cv::Point2f>> marker_corners;
164
165 cv::aruco::detectMarkers(rgb_image, board_->dictionary, marker_corners,
166 marker_ids);
167
168 std::vector<cv::Point2f> charuco_corners;
169 std::vector<int> charuco_ids;
170 // If at least one marker detected
171 if (marker_ids.size() >= FLAGS_min_targets) {
172 // Run everything twice, once with the calibration, and once
173 // without. This lets us both calibrate, and also print out the pose
174 // real time with the previous calibration.
175 cv::aruco::interpolateCornersCharuco(marker_corners, marker_ids, rgb_image,
176 board_, charuco_corners, charuco_ids);
177
178 std::vector<cv::Point2f> charuco_corners_with_calibration;
179 std::vector<int> charuco_ids_with_calibration;
180
181 cv::aruco::interpolateCornersCharuco(
182 marker_corners, marker_ids, rgb_image, board_,
183 charuco_corners_with_calibration, charuco_ids_with_calibration,
184 camera_matrix_, dist_coeffs_);
185
186 cv::aruco::drawDetectedMarkers(rgb_image, marker_corners, marker_ids);
187
188 if (charuco_ids.size() >= FLAGS_min_targets) {
189 cv::aruco::drawDetectedCornersCharuco(rgb_image, charuco_corners,
190 charuco_ids, cv::Scalar(255, 0, 0));
191
192 cv::Vec3d rvec, tvec;
193 const bool valid = cv::aruco::estimatePoseCharucoBoard(
194 charuco_corners_with_calibration, charuco_ids_with_calibration,
195 board_, camera_matrix_, dist_coeffs_, rvec, tvec);
196
197 // if charuco pose is valid
198 if (valid) {
199 Eigen::Vector3d rvec_eigen;
200 Eigen::Vector3d tvec_eigen;
201 cv::cv2eigen(rvec, rvec_eigen);
202 cv::cv2eigen(tvec, tvec_eigen);
203
204 Eigen::Quaternion<double> rotation(
205 frc971::controls::ToQuaternionFromRotationVector(rvec_eigen));
206 Eigen::Translation3d translation(tvec_eigen);
207
208 const Eigen::Affine3d board_to_camera = translation * rotation;
209
210 Eigen::Matrix<double, 3, 4> camera_projection =
211 Eigen::Matrix<double, 3, 4>::Identity();
212 Eigen::Vector3d result = eigen_camera_matrix_ * camera_projection *
213 board_to_camera * Eigen::Vector3d::Zero();
214
215 result /= result.z();
216 cv::circle(rgb_image, cv::Point(result.x(), result.y()), 4,
217 cv::Scalar(255, 255, 255), 0, cv::LINE_8);
218
219 cv::aruco::drawAxis(rgb_image, camera_matrix_, dist_coeffs_, rvec, tvec,
220 0.1);
221
222 handle_charuco_(rgb_image, age_double, charuco_ids, charuco_corners,
223
224 true, rvec_eigen, tvec_eigen);
225 } else {
226 LOG(INFO) << "Age: " << age_double << ", invalid pose";
227 handle_charuco_(rgb_image, age_double, charuco_ids, charuco_corners,
228
229 false, Eigen::Vector3d::Zero(),
230 Eigen::Vector3d::Zero());
231 }
232 } else {
233 LOG(INFO) << "Age: " << age_double << ", no charuco IDs.";
234 handle_charuco_(rgb_image, age_double, charuco_ids, charuco_corners,
235
236 false, Eigen::Vector3d::Zero(), Eigen::Vector3d::Zero());
237 }
238 } else {
239 LOG(INFO) << "Age: " << age_double << ", no marker IDs";
240 cv::aruco::drawDetectedMarkers(rgb_image, marker_corners, marker_ids);
241
242 handle_charuco_(rgb_image, age_double, charuco_ids, charuco_corners, false,
243 Eigen::Vector3d::Zero(), Eigen::Vector3d::Zero());
244 }
245}
246
247} // namespace vision
248} // namespace frc971