blob: 77e1ba9f47cfcb0d7011f9c0f731afcf4a3a3569 [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;
Austin Schuhea7b0142021-10-08 22:04:53 -070031using aos::monotonic_clock;
Austin Schuh25837f22021-06-27 15:49:14 -070032
33CameraCalibration::CameraCalibration(
34 const absl::Span<const uint8_t> training_data_bfbs, std::string_view pi) {
35 const aos::FlatbufferSpan<sift::TrainingData> training_data(
36 training_data_bfbs);
37 CHECK(training_data.Verify());
38 camera_calibration_ = FindCameraCalibration(&training_data.message(), pi);
39}
40
41cv::Mat CameraCalibration::CameraIntrinsics() const {
42 const cv::Mat result(3, 3, CV_32F,
43 const_cast<void *>(static_cast<const void *>(
44 camera_calibration_->intrinsics()->data())));
45 CHECK_EQ(result.total(), camera_calibration_->intrinsics()->size());
46 return result;
47}
48
49Eigen::Matrix3d CameraCalibration::CameraIntrinsicsEigen() const {
50 cv::Mat camera_intrinsics = CameraIntrinsics();
51 Eigen::Matrix3d result;
52 cv::cv2eigen(camera_intrinsics, result);
53 return result;
54}
55
56cv::Mat CameraCalibration::CameraDistCoeffs() const {
57 const cv::Mat result(5, 1, CV_32F,
58 const_cast<void *>(static_cast<const void *>(
59 camera_calibration_->dist_coeffs()->data())));
60 CHECK_EQ(result.total(), camera_calibration_->dist_coeffs()->size());
61 return result;
62}
63
64const sift::CameraCalibration *CameraCalibration::FindCameraCalibration(
65 const sift::TrainingData *const training_data, std::string_view pi) const {
66 std::optional<uint16_t> pi_number = aos::network::ParsePiNumber(pi);
67 std::optional<uint16_t> team_number =
68 aos::network::team_number_internal::ParsePiTeamNumber(pi);
69 CHECK(pi_number);
70 CHECK(team_number);
71 const std::string node_name = absl::StrFormat("pi%d", pi_number.value());
72 LOG(INFO) << "Looking for node name " << node_name << " team number "
73 << team_number.value();
74 for (const sift::CameraCalibration *candidate :
75 *training_data->camera_calibrations()) {
76 if (candidate->node_name()->string_view() != node_name) {
77 continue;
78 }
79 if (candidate->team_number() != team_number.value()) {
80 continue;
81 }
82 return candidate;
83 }
84 LOG(FATAL) << ": Failed to find camera calibration for " << node_name
85 << " on " << team_number.value();
86}
87
Austin Schuhea7b0142021-10-08 22:04:53 -070088ImageCallback::ImageCallback(
89 aos::EventLoop *event_loop, std::string_view channel,
90 std::function<void(cv::Mat, monotonic_clock::time_point)> &&fn)
91 : event_loop_(event_loop),
92 server_fetcher_(
93 event_loop_->MakeFetcher<aos::message_bridge::ServerStatistics>(
94 "/aos")),
95 source_node_(aos::configuration::GetNode(
96 event_loop_->configuration(),
97 event_loop_->GetChannel<CameraImage>(channel)
98 ->source_node()
99 ->string_view())),
100 handle_image_(std::move(fn)) {
Austin Schuh25837f22021-06-27 15:49:14 -0700101 event_loop_->MakeWatcher(channel, [this](const CameraImage &image) {
Austin Schuhea7b0142021-10-08 22:04:53 -0700102 const monotonic_clock::time_point eof_source_node =
103 monotonic_clock::time_point(
104 chrono::nanoseconds(image.monotonic_timestamp_ns()));
105 server_fetcher_.Fetch();
106 if (!server_fetcher_.get()) {
107 return;
108 }
109
110 chrono::nanoseconds offset{0};
111 if (source_node_ != event_loop_->node()) {
112 // If we are viewing this image from another node, convert to our
113 // monotonic clock.
114 const aos::message_bridge::ServerConnection *server_connection = nullptr;
115
116 for (const aos::message_bridge::ServerConnection *connection :
117 *server_fetcher_->connections()) {
118 CHECK(connection->has_node());
119 if (connection->node()->name()->string_view() ==
120 source_node_->name()->string_view()) {
121 server_connection = connection;
122 break;
123 }
124 }
125
126 CHECK(server_connection != nullptr) << ": Failed to find client";
127 if (!server_connection->has_monotonic_offset()) {
128 VLOG(1) << "No offset yet.";
129 return;
130 }
131 offset = chrono::nanoseconds(server_connection->monotonic_offset());
132 }
133
134 const monotonic_clock::time_point eof = eof_source_node - offset;
135
136 const monotonic_clock::duration age =
137 event_loop_->monotonic_now() - eof;
Austin Schuh25837f22021-06-27 15:49:14 -0700138 const double age_double =
139 std::chrono::duration_cast<std::chrono::duration<double>>(age).count();
140 if (age > std::chrono::milliseconds(100)) {
141 LOG(INFO) << "Age: " << age_double << ", getting behind, skipping";
142 return;
143 }
144 // Create color image:
145 cv::Mat image_color_mat(cv::Size(image.cols(), image.rows()), CV_8UC2,
146 (void *)image.data()->data());
147 const cv::Size image_size(image.cols(), image.rows());
148 cv::Mat rgb_image(image_size, CV_8UC3);
149 cv::cvtColor(image_color_mat, rgb_image, CV_YUV2BGR_YUYV);
Austin Schuhea7b0142021-10-08 22:04:53 -0700150 handle_image_(rgb_image, eof);
Austin Schuh25837f22021-06-27 15:49:14 -0700151 });
152}
153
154CharucoExtractor::CharucoExtractor(
155 aos::EventLoop *event_loop, std::string_view pi,
Austin Schuhea7b0142021-10-08 22:04:53 -0700156 std::function<void(cv::Mat, monotonic_clock::time_point, std::vector<int>,
Austin Schuh25837f22021-06-27 15:49:14 -0700157 std::vector<cv::Point2f>, bool, Eigen::Vector3d,
158 Eigen::Vector3d)> &&fn)
Austin Schuhea7b0142021-10-08 22:04:53 -0700159 : event_loop_(event_loop),
160 calibration_(SiftTrainingData(), pi),
Austin Schuh25837f22021-06-27 15:49:14 -0700161 dictionary_(cv::aruco::getPredefinedDictionary(
162 FLAGS_large_board ? cv::aruco::DICT_5X5_250
163 : cv::aruco::DICT_6X6_250)),
164 board_(
165 FLAGS_large_board
166 ? (FLAGS_coarse_pattern ? cv::aruco::CharucoBoard::create(
167 12, 9, 0.06, 0.04666, dictionary_)
168 : cv::aruco::CharucoBoard::create(
169 25, 18, 0.03, 0.0233, dictionary_))
170 : (FLAGS_coarse_pattern ? cv::aruco::CharucoBoard::create(
171 7, 5, 0.04, 0.025, dictionary_)
172 // TODO(jim): Need to figure out what size
173 // is for small board, fine pattern
174 : cv::aruco::CharucoBoard::create(
175 7, 5, 0.03, 0.0233, dictionary_))),
176 camera_matrix_(calibration_.CameraIntrinsics()),
177 eigen_camera_matrix_(calibration_.CameraIntrinsicsEigen()),
178 dist_coeffs_(calibration_.CameraDistCoeffs()),
179 pi_number_(aos::network::ParsePiNumber(pi)),
180 image_callback_(
181 event_loop,
182 absl::StrCat("/pi", std::to_string(pi_number_.value()), "/camera"),
Austin Schuhea7b0142021-10-08 22:04:53 -0700183 [this](cv::Mat rgb_image, const monotonic_clock::time_point eof) {
184 HandleImage(rgb_image, eof);
Austin Schuh25837f22021-06-27 15:49:14 -0700185 }),
186 handle_charuco_(std::move(fn)) {
187 LOG(INFO) << "Using " << (FLAGS_large_board ? "large" : "small")
188 << " board with " << (FLAGS_coarse_pattern ? "coarse" : "fine")
189 << " pattern";
190 if (!FLAGS_board_template_path.empty()) {
191 cv::Mat board_image;
192 board_->draw(cv::Size(600, 500), board_image, 10, 1);
193 cv::imwrite(FLAGS_board_template_path, board_image);
194 }
195
196 LOG(INFO) << "Camera matrix " << camera_matrix_;
197 LOG(INFO) << "Distortion Coefficients " << dist_coeffs_;
198
199 CHECK(pi_number_) << ": Invalid pi number " << pi
200 << ", failed to parse pi number";
201
202 LOG(INFO) << "Connecting to channel /pi" << pi_number_.value() << "/camera";
203}
204
Austin Schuhea7b0142021-10-08 22:04:53 -0700205void CharucoExtractor::HandleImage(cv::Mat rgb_image,
206 const monotonic_clock::time_point eof) {
207 const double age_double =
208 std::chrono::duration_cast<std::chrono::duration<double>>(
209 event_loop_->monotonic_now() - eof)
210 .count();
Austin Schuh25837f22021-06-27 15:49:14 -0700211 std::vector<int> marker_ids;
212 std::vector<std::vector<cv::Point2f>> marker_corners;
213
214 cv::aruco::detectMarkers(rgb_image, board_->dictionary, marker_corners,
215 marker_ids);
216
217 std::vector<cv::Point2f> charuco_corners;
218 std::vector<int> charuco_ids;
Austin Schuhea7b0142021-10-08 22:04:53 -0700219 bool valid = false;
220 Eigen::Vector3d rvec_eigen = Eigen::Vector3d::Zero();
221 Eigen::Vector3d tvec_eigen = Eigen::Vector3d::Zero();
222
Austin Schuh25837f22021-06-27 15:49:14 -0700223 // If at least one marker detected
224 if (marker_ids.size() >= FLAGS_min_targets) {
225 // Run everything twice, once with the calibration, and once
226 // without. This lets us both calibrate, and also print out the pose
227 // real time with the previous calibration.
228 cv::aruco::interpolateCornersCharuco(marker_corners, marker_ids, rgb_image,
229 board_, charuco_corners, charuco_ids);
230
231 std::vector<cv::Point2f> charuco_corners_with_calibration;
232 std::vector<int> charuco_ids_with_calibration;
233
234 cv::aruco::interpolateCornersCharuco(
235 marker_corners, marker_ids, rgb_image, board_,
236 charuco_corners_with_calibration, charuco_ids_with_calibration,
237 camera_matrix_, dist_coeffs_);
238
239 cv::aruco::drawDetectedMarkers(rgb_image, marker_corners, marker_ids);
240
241 if (charuco_ids.size() >= FLAGS_min_targets) {
242 cv::aruco::drawDetectedCornersCharuco(rgb_image, charuco_corners,
243 charuco_ids, cv::Scalar(255, 0, 0));
244
245 cv::Vec3d rvec, tvec;
Austin Schuhea7b0142021-10-08 22:04:53 -0700246 valid = cv::aruco::estimatePoseCharucoBoard(
Austin Schuh25837f22021-06-27 15:49:14 -0700247 charuco_corners_with_calibration, charuco_ids_with_calibration,
248 board_, camera_matrix_, dist_coeffs_, rvec, tvec);
249
250 // if charuco pose is valid
251 if (valid) {
Austin Schuh25837f22021-06-27 15:49:14 -0700252 cv::cv2eigen(rvec, rvec_eigen);
253 cv::cv2eigen(tvec, tvec_eigen);
254
255 Eigen::Quaternion<double> rotation(
256 frc971::controls::ToQuaternionFromRotationVector(rvec_eigen));
257 Eigen::Translation3d translation(tvec_eigen);
258
259 const Eigen::Affine3d board_to_camera = translation * rotation;
260
261 Eigen::Matrix<double, 3, 4> camera_projection =
262 Eigen::Matrix<double, 3, 4>::Identity();
263 Eigen::Vector3d result = eigen_camera_matrix_ * camera_projection *
264 board_to_camera * Eigen::Vector3d::Zero();
265
266 result /= result.z();
267 cv::circle(rgb_image, cv::Point(result.x(), result.y()), 4,
268 cv::Scalar(255, 255, 255), 0, cv::LINE_8);
269
270 cv::aruco::drawAxis(rgb_image, camera_matrix_, dist_coeffs_, rvec, tvec,
271 0.1);
Austin Schuh25837f22021-06-27 15:49:14 -0700272 } else {
273 LOG(INFO) << "Age: " << age_double << ", invalid pose";
Austin Schuh25837f22021-06-27 15:49:14 -0700274 }
275 } else {
Austin Schuhea7b0142021-10-08 22:04:53 -0700276 LOG(INFO) << "Age: " << age_double << ", not enough charuco IDs, got "
277 << charuco_ids.size() << ", needed " << FLAGS_min_targets;
Austin Schuh25837f22021-06-27 15:49:14 -0700278 }
279 } else {
Austin Schuhea7b0142021-10-08 22:04:53 -0700280 LOG(INFO) << "Age: " << age_double << ", not enough marker IDs, got "
281 << marker_ids.size() << ", needed " << FLAGS_min_targets;
Austin Schuh25837f22021-06-27 15:49:14 -0700282 cv::aruco::drawDetectedMarkers(rgb_image, marker_corners, marker_ids);
Austin Schuh25837f22021-06-27 15:49:14 -0700283 }
Austin Schuhea7b0142021-10-08 22:04:53 -0700284
285 handle_charuco_(rgb_image, eof, charuco_ids, charuco_corners, valid,
286 rvec_eigen, tvec_eigen);
Austin Schuh25837f22021-06-27 15:49:14 -0700287}
288
289} // namespace vision
290} // namespace frc971