blob: d3cfa6f5e3f3346ddd53f4110bc19bc3a3c1264e [file] [log] [blame]
Jim Ostrowski2f2685f2023-03-25 11:57:54 -07001#include <numeric>
2
3#include "aos/configuration.h"
4#include "aos/events/logging/log_reader.h"
5#include "aos/events/simulated_event_loop.h"
6#include "aos/init.h"
7#include "aos/util/mcap_logger.h"
8#include "frc971/control_loops/pose.h"
9#include "frc971/control_loops/quaternion_utils.h"
10#include "frc971/vision/calibration_generated.h"
11#include "frc971/vision/charuco_lib.h"
Jim Ostrowski68c321d2023-11-14 21:36:28 -080012#include "frc971/vision/extrinsics_calibration.h"
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070013#include "frc971/vision/target_mapper.h"
14#include "frc971/vision/visualize_robot.h"
15// clang-format off
16// OpenCV eigen files must be included after Eigen includes
17#include "opencv2/aruco.hpp"
18#include "opencv2/calib3d.hpp"
19#include "opencv2/core/eigen.hpp"
20#include "opencv2/features2d.hpp"
21#include "opencv2/highgui.hpp"
22#include "opencv2/highgui/highgui.hpp"
23#include "opencv2/imgproc.hpp"
24// clang-format on
25#include "y2023/constants/simulated_constants_sender.h"
26#include "y2023/vision/aprilrobotics.h"
27#include "y2023/vision/vision_util.h"
28
Jim Ostrowski2be78e32023-03-25 11:57:54 -070029DEFINE_bool(alt_view, false,
30 "If true, show visualization from field level, rather than above");
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070031DEFINE_string(config, "",
32 "If set, override the log's config file with this one.");
33DEFINE_string(constants_path, "y2023/constants/constants.json",
34 "Path to the constant file");
Jim Ostrowski68c321d2023-11-14 21:36:28 -080035DEFINE_double(max_pose_error, 5e-5,
36 "Throw out target poses with a higher pose error than this");
37DEFINE_double(
38 max_pose_error_ratio, 0.4,
39 "Throw out target poses with a higher pose error ratio than this");
40DEFINE_string(output_folder, "/tmp",
41 "Directory in which to store the updated calibration files");
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070042DEFINE_string(target_type, "charuco_diamond",
43 "Type of target being used [aruco, charuco, charuco_diamond]");
44DEFINE_int32(team_number, 0,
45 "Required: Use the calibration for a node with this team number");
Jim Ostrowski68c321d2023-11-14 21:36:28 -080046DEFINE_bool(use_full_logs, false,
47 "If true, extract data from logs with images");
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070048DEFINE_uint64(
49 wait_key, 1,
50 "Time in ms to wait between images (0 to wait indefinitely until click)");
51
Jim Ostrowski68c321d2023-11-14 21:36:28 -080052DECLARE_int32(min_target_id);
53DECLARE_int32(max_target_id);
54
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070055// Calibrate extrinsic relationship between cameras using two targets
56// seen jointly between cameras. Uses two types of information: 1)
57// when a single camera sees two targets, we estimate the pose between
58// targets, and 2) when two separate cameras each see a target, we can
59// use the pose between targets to estimate the pose between cameras.
60
61// We then create the extrinsics for the robot by starting with the
62// given extrinsic for camera 1 (between imu/robot and camera frames)
63// and then map each subsequent camera based on the data collected and
64// the extrinsic poses computed here.
65
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070066// TODO<Jim>: Not currently using estimate from pi1->pi4-- should do full
67// estimation, and probably also include camera->imu extrinsics from all
68// cameras, not just pi1
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070069
70namespace y2023 {
71namespace vision {
72using frc971::vision::DataAdapter;
73using frc971::vision::ImageCallback;
74using frc971::vision::PoseUtils;
75using frc971::vision::TargetMap;
76using frc971::vision::TargetMapper;
Jim Ostrowski2be78e32023-03-25 11:57:54 -070077using frc971::vision::VisualizeRobot;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070078namespace calibration = frc971::vision::calibration;
79
80static constexpr double kImagePeriodMs =
81 1.0 / 30.0 * 1000.0; // Image capture period in ms
82
83// Change reference frame from camera to robot
84Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target,
85 Eigen::Affine3d extrinsics) {
86 const Eigen::Affine3d H_robot_camera = extrinsics;
87 const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target;
88 return H_robot_target;
89}
90
91struct TimestampedPiDetection {
92 aos::distributed_clock::time_point time;
93 // Pose of target relative to robot
94 Eigen::Affine3d H_camera_target;
95 // name of pi
96 std::string pi_name;
97 int board_id;
98};
99
100TimestampedPiDetection last_observation;
101std::vector<std::pair<TimestampedPiDetection, TimestampedPiDetection>>
102 detection_list;
103std::vector<TimestampedPiDetection> two_board_extrinsics_list;
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700104VisualizeRobot vis_robot_;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700105
106// TODO<jim>: Implement variance calcs
107Eigen::Affine3d ComputeAveragePose(
108 std::vector<Eigen::Vector3d> &translation_list,
109 std::vector<Eigen::Vector4d> &rotation_list,
110 Eigen::Vector3d *translation_variance = nullptr,
111 Eigen::Vector3d *rotation_variance = nullptr) {
112 Eigen::Vector3d avg_translation =
113 std::accumulate(translation_list.begin(), translation_list.end(),
114 Eigen::Vector3d{0, 0, 0}) /
115 translation_list.size();
116
117 // TODO<Jim>: Use QuaternionMean from quaternion_utils.cc (but this
118 // requires a fixed number of quaternions to be averaged
119 Eigen::Vector4d avg_rotation =
120 std::accumulate(rotation_list.begin(), rotation_list.end(),
121 Eigen::Vector4d{0, 0, 0, 0}) /
122 rotation_list.size();
123 // Normalize, so it's a valid quaternion
124 avg_rotation = avg_rotation / avg_rotation.norm();
125 Eigen::Quaterniond avg_rotation_q{avg_rotation[0], avg_rotation[1],
126 avg_rotation[2], avg_rotation[3]};
127 Eigen::Translation3d translation(avg_translation);
128 Eigen::Affine3d return_pose = translation * avg_rotation_q;
129 if (translation_variance != nullptr) {
130 *translation_variance = Eigen::Vector3d();
131 }
132 if (rotation_variance != nullptr) {
133 LOG(INFO) << *rotation_variance;
134 }
135
136 return return_pose;
137}
138
139Eigen::Affine3d ComputeAveragePose(
140 std::vector<Eigen::Affine3d> &pose_list,
141 Eigen::Vector3d *translation_variance = nullptr,
142 Eigen::Vector3d *rotation_variance = nullptr) {
143 std::vector<Eigen::Vector3d> translation_list;
144 std::vector<Eigen::Vector4d> rotation_list;
145
146 for (Eigen::Affine3d pose : pose_list) {
147 translation_list.push_back(pose.translation());
148 Eigen::Quaterniond quat(pose.rotation().matrix());
149 rotation_list.push_back(
150 Eigen::Vector4d(quat.w(), quat.x(), quat.y(), quat.z()));
151 }
152
153 return ComputeAveragePose(translation_list, rotation_list,
154 translation_variance, rotation_variance);
155}
156
157Eigen::Affine3d ComputeAveragePose(
158 std::vector<TimestampedPiDetection> &pose_list,
159 Eigen::Vector3d *translation_variance = nullptr,
160 Eigen::Vector3d *rotation_variance = nullptr) {
161 std::vector<Eigen::Vector3d> translation_list;
162 std::vector<Eigen::Vector4d> rotation_list;
163
164 for (TimestampedPiDetection pose : pose_list) {
165 translation_list.push_back(pose.H_camera_target.translation());
166 Eigen::Quaterniond quat(pose.H_camera_target.rotation().matrix());
167 rotation_list.push_back(
168 Eigen::Vector4d(quat.w(), quat.x(), quat.y(), quat.z()));
169 }
170 return ComputeAveragePose(translation_list, rotation_list,
171 translation_variance, rotation_variance);
172}
173
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800174void HandlePoses(cv::Mat rgb_image,
175 std::vector<TargetMapper::TargetPose> target_poses,
176 aos::distributed_clock::time_point distributed_eof,
177 std::string node_name) {
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700178 // This is used to transform points for visualization
179 // Assumes targets are aligned with x->right, y->up, z->out of board
180 Eigen::Affine3d H_world_board;
181 H_world_board = Eigen::Translation3d::Identity() *
182 Eigen::AngleAxisd(M_PI / 2.0, Eigen::Vector3d::UnitX());
183 if (FLAGS_alt_view) {
184 // Don't rotate -- this is like viewing from the side
185 H_world_board = Eigen::Translation3d(0.0, 0.0, 3.0);
186 }
187
188 bool draw_vis = false;
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800189 CHECK_LE(target_poses.size(), 2u)
190 << "Can't handle more than two tags in field of view";
191 if (target_poses.size() == 2) {
192 draw_vis = true;
193 VLOG(1) << "Saw two boards in same view from " << node_name;
194 int from_index = 0;
195 int to_index = 1;
196 // Handle when we see two boards at once
197 // We'll store them referenced to the lower id board
198 if (target_poses[from_index].id > target_poses[to_index].id) {
199 std::swap<int>(from_index, to_index);
200 }
201
202 // Create "from" (A) and "to" (B) transforms
203 Eigen::Affine3d H_camera_boardA =
204 PoseUtils::Pose3dToAffine3d(target_poses[from_index].pose);
205 Eigen::Affine3d H_camera_boardB =
206 PoseUtils::Pose3dToAffine3d(target_poses[to_index].pose);
207
208 Eigen::Affine3d H_boardA_boardB =
209 H_camera_boardA.inverse() * H_camera_boardB;
210
211 TimestampedPiDetection boardA_boardB{
212 .time = distributed_eof,
213 .H_camera_target = H_boardA_boardB,
214 .pi_name = node_name,
215 .board_id = target_poses[from_index].id};
216
217 VLOG(1) << "Map from board " << from_index << " to " << to_index << " is\n"
218 << H_boardA_boardB.matrix();
219 // Store this observation of the transform between two boards
220 two_board_extrinsics_list.push_back(boardA_boardB);
221
222 if (FLAGS_visualize) {
223 vis_robot_.DrawFrameAxes(
224 H_world_board,
225 std::string("board ") + std::to_string(target_poses[from_index].id),
226 cv::Scalar(0, 255, 0));
227 vis_robot_.DrawFrameAxes(
228 H_world_board * boardA_boardB.H_camera_target,
229 std::string("board ") + std::to_string(target_poses[to_index].id),
230 cv::Scalar(255, 0, 0));
231 VLOG(2) << "Detection map from camera " << node_name << " to board "
232 << target_poses[from_index].id << " is\n"
233 << H_camera_boardA.matrix() << "\n and inverse is\n"
234 << H_camera_boardA.inverse().matrix()
235 << "\n and with world to board rotation is\n"
236 << H_world_board * H_camera_boardA.inverse().matrix();
237 vis_robot_.DrawRobotOutline(H_world_board * H_camera_boardA.inverse(),
238 node_name, cv::Scalar(0, 0, 255));
239 }
240 } else if (target_poses.size() == 1) {
241 VLOG(1) << "Saw single board in camera " << node_name;
242 Eigen::Affine3d H_camera2_board2 =
243 PoseUtils::Pose3dToAffine3d(target_poses[0].pose);
244 TimestampedPiDetection new_observation{.time = distributed_eof,
245 .H_camera_target = H_camera2_board2,
246 .pi_name = node_name,
247 .board_id = target_poses[0].id};
248
249 // Only take two observations if they're within half an image cycle of each
250 // other (i.e., as close in time as possible)
251 if (std::abs((distributed_eof - last_observation.time).count()) <
252 kImagePeriodMs / 2.0 * 1000000.0) {
253 // Sort by pi numbering, since this is how we will handle them
254 std::pair<TimestampedPiDetection, TimestampedPiDetection> new_pair;
255 if (last_observation.pi_name < new_observation.pi_name) {
256 new_pair = std::pair(last_observation, new_observation);
257 } else if (last_observation.pi_name > new_observation.pi_name) {
258 new_pair = std::pair(new_observation, last_observation);
259 } else {
260 LOG(WARNING) << "Got 2 observations in a row from same pi. Probably "
261 "not too much of an issue???";
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700262 }
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800263 detection_list.push_back(new_pair);
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700264
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800265 // This bit is just for visualization and checking purposes-- use the
266 // last two-board observation to figure out the current estimate
267 // between the two cameras
268 if (FLAGS_visualize && two_board_extrinsics_list.size() > 0) {
269 draw_vis = true;
270 TimestampedPiDetection &last_two_board_ext =
271 two_board_extrinsics_list[two_board_extrinsics_list.size() - 1];
272 Eigen::Affine3d &H_boardA_boardB = last_two_board_ext.H_camera_target;
273 int boardA_boardB_id = last_two_board_ext.board_id;
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700274
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800275 TimestampedPiDetection camera1_boardA = new_pair.first;
276 TimestampedPiDetection camera2_boardB = new_pair.second;
277 // If camera1_boardA doesn't point to the first target, then swap
278 // these two
279 if (camera1_boardA.board_id != boardA_boardB_id) {
280 camera1_boardA = new_pair.second;
281 camera2_boardB = new_pair.first;
282 }
283 VLOG(1) << "Camera " << camera1_boardA.pi_name << " seeing board "
284 << camera1_boardA.board_id << " and camera "
285 << camera2_boardB.pi_name << " seeing board "
286 << camera2_boardB.board_id;
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700287
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800288 vis_robot_.DrawRobotOutline(
289 H_world_board * camera1_boardA.H_camera_target.inverse(),
290 camera1_boardA.pi_name, cv::Scalar(0, 0, 255));
291 vis_robot_.DrawRobotOutline(
292 H_world_board * H_boardA_boardB *
293 camera2_boardB.H_camera_target.inverse(),
294 camera2_boardB.pi_name, cv::Scalar(128, 128, 0));
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700295 vis_robot_.DrawFrameAxes(
296 H_world_board,
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800297 std::string("Board ") + std::to_string(last_two_board_ext.board_id),
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700298 cv::Scalar(0, 255, 0));
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800299 vis_robot_.DrawFrameAxes(H_world_board * H_boardA_boardB, "Board B",
300 cv::Scalar(255, 0, 0));
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700301 }
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800302 VLOG(1) << "Storing observation between " << new_pair.first.pi_name
303 << ", target " << new_pair.first.board_id << " and "
304 << new_pair.second.pi_name << ", target "
305 << new_pair.second.board_id;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700306 } else {
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800307 VLOG(2) << "Storing observation for " << node_name << " at time "
308 << distributed_eof;
309 last_observation = new_observation;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700310 }
311 }
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700312
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700313 if (FLAGS_visualize) {
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800314 if (!rgb_image.empty()) {
315 std::string image_name = node_name + " Image";
316 cv::Mat rgb_small;
317 cv::resize(rgb_image, rgb_small, cv::Size(), 0.5, 0.5);
318 cv::imshow(image_name, rgb_small);
319 cv::waitKey(FLAGS_wait_key);
320 }
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700321
322 if (draw_vis) {
323 cv::imshow("View", vis_robot_.image_);
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800324 cv::waitKey(FLAGS_wait_key);
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700325 vis_robot_.ClearImage();
326 }
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700327 }
328}
329
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800330void HandleTargetMap(const TargetMap &map,
331 aos::distributed_clock::time_point distributed_eof,
332 std::string node_name) {
333 VLOG(1) << "Got april tag map call from node " << node_name;
334 // Create empty RGB image in this case
335 cv::Mat rgb_image;
336 std::vector<TargetMapper::TargetPose> target_poses;
337
338 for (const auto *target_pose_fbs : *map.target_poses()) {
339 // Skip detections with invalid ids
340 if (static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) <
341 FLAGS_min_target_id ||
342 static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) >
343 FLAGS_max_target_id) {
344 LOG(INFO) << "Skipping tag with invalid id of " << target_pose_fbs->id();
345 continue;
346 }
347
348 // Skip detections with high pose errors
349 if (target_pose_fbs->pose_error() > FLAGS_max_pose_error) {
350 LOG(INFO) << "Skipping tag " << target_pose_fbs->id()
351 << " due to pose error of " << target_pose_fbs->pose_error();
352 continue;
353 }
354 // Skip detections with high pose error ratios
355 if (target_pose_fbs->pose_error_ratio() > FLAGS_max_pose_error_ratio) {
356 LOG(INFO) << "Skipping tag " << target_pose_fbs->id()
357 << " due to pose error ratio of "
358 << target_pose_fbs->pose_error_ratio();
359 continue;
360 }
361
362 const TargetMapper::TargetPose target_pose =
363 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
364
365 target_poses.emplace_back(target_pose);
366
367 Eigen::Affine3d H_camera_target =
368 PoseUtils::Pose3dToAffine3d(target_pose.pose);
369 VLOG(2) << node_name << " saw target " << target_pose.id
370 << " from TargetMap at timestamp " << distributed_eof
371 << " with pose = " << H_camera_target.matrix();
372 }
373 HandlePoses(rgb_image, target_poses, distributed_eof, node_name);
374}
375
376void HandleImage(aos::EventLoop *event_loop, cv::Mat rgb_image,
377 const aos::monotonic_clock::time_point eof,
378 aos::distributed_clock::time_point distributed_eof,
379 frc971::vision::CharucoExtractor &charuco_extractor,
380 std::string node_name) {
381 std::vector<cv::Vec4i> charuco_ids;
382 std::vector<std::vector<cv::Point2f>> charuco_corners;
383 bool valid = false;
384 std::vector<Eigen::Vector3d> rvecs_eigen;
385 std::vector<Eigen::Vector3d> tvecs_eigen;
386 // Why eof vs. distributed_eof?
387 charuco_extractor.ProcessImage(rgb_image, eof, event_loop->monotonic_now(),
388 charuco_ids, charuco_corners, valid,
389 rvecs_eigen, tvecs_eigen);
390 if (rvecs_eigen.size() > 0 && !valid) {
391 LOG(WARNING) << "Charuco extractor returned not valid";
392 return;
393 }
394
395 std::vector<TargetMapper::TargetPose> target_poses;
396 for (size_t i = 0; i < tvecs_eigen.size(); i++) {
397 Eigen::Quaterniond rotation(
398 frc971::controls::ToQuaternionFromRotationVector(rvecs_eigen[i]));
399 ceres::examples::Pose3d pose(Eigen::Vector3d(tvecs_eigen[i]), rotation);
400 TargetMapper::TargetPose target_pose{charuco_ids[i][0], pose};
401 target_poses.emplace_back(target_pose);
402
403 Eigen::Affine3d H_camera_target = PoseUtils::Pose3dToAffine3d(pose);
404 VLOG(2) << node_name << " saw target " << target_pose.id
405 << " from image at timestamp " << distributed_eof
406 << " with pose = " << H_camera_target.matrix();
407 }
408 HandlePoses(rgb_image, target_poses, distributed_eof, node_name);
409}
410
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700411void ExtrinsicsMain(int argc, char *argv[]) {
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700412 vis_robot_ = VisualizeRobot(cv::Size(1000, 1000));
413 vis_robot_.ClearImage();
414 const double kFocalLength = 1000.0;
415 const int kImageWidth = 1000;
416 vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength);
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700417
418 std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config =
419 (FLAGS_config.empty()
420 ? std::nullopt
421 : std::make_optional(aos::configuration::ReadConfig(FLAGS_config)));
422
423 // open logfiles
424 aos::logger::LogReader reader(
425 aos::logger::SortParts(aos::logger::FindLogs(argc, argv)),
426 config.has_value() ? &config->message() : nullptr);
427
428 constexpr size_t kNumPis = 4;
429 for (size_t i = 1; i <= kNumPis; i++) {
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700430 reader.RemapLoggedChannel(absl::StrFormat("/pi%u/constants", i),
431 "y2023.Constants");
432 }
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800433
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700434 reader.RemapLoggedChannel("/imu/constants", "y2023.Constants");
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800435 reader.RemapLoggedChannel("/logger/constants", "y2023.Constants");
436 reader.RemapLoggedChannel("/roborio/constants", "y2023.Constants");
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700437 reader.Register();
438
439 SendSimulationConstants(reader.event_loop_factory(), FLAGS_team_number,
440 FLAGS_constants_path);
441
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700442 VLOG(1) << "Using target type " << FLAGS_target_type;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700443 std::vector<std::string> node_list;
444 node_list.push_back("pi1");
445 node_list.push_back("pi2");
446 node_list.push_back("pi3");
447 node_list.push_back("pi4");
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800448 std::vector<const calibration::CameraCalibration *> calibration_list;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700449
450 std::vector<std::unique_ptr<aos::EventLoop>> detection_event_loops;
451 std::vector<frc971::vision::CharucoExtractor *> charuco_extractors;
452 std::vector<frc971::vision::ImageCallback *> image_callbacks;
453 std::vector<Eigen::Affine3d> default_extrinsics;
454
455 for (uint i = 0; i < node_list.size(); i++) {
456 std::string node = node_list[i];
457 const aos::Node *pi =
458 aos::configuration::GetNode(reader.configuration(), node.c_str());
459
460 detection_event_loops.emplace_back(
461 reader.event_loop_factory()->MakeEventLoop(
462 (node + "_detection").c_str(), pi));
463
464 frc971::constants::ConstantsFetcher<y2023::Constants> constants_fetcher(
465 detection_event_loops.back().get());
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700466
467 const calibration::CameraCalibration *calibration =
468 FindCameraCalibration(constants_fetcher.constants(), node);
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800469 calibration_list.push_back(calibration);
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700470
471 frc971::vision::TargetType target_type =
472 frc971::vision::TargetTypeFromString(FLAGS_target_type);
473 frc971::vision::CharucoExtractor *charuco_ext =
474 new frc971::vision::CharucoExtractor(calibration, target_type);
475 charuco_extractors.emplace_back(charuco_ext);
476
477 cv::Mat extrinsics_cv = CameraExtrinsics(calibration).value();
478 Eigen::Matrix4d extrinsics_matrix;
479 cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
480 const auto ext_H_robot_pi = Eigen::Affine3d(extrinsics_matrix);
481 default_extrinsics.emplace_back(ext_H_robot_pi);
482
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700483 VLOG(1) << "Got extrinsics for " << node << " as\n"
484 << default_extrinsics.back().matrix();
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700485
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800486 if (FLAGS_use_full_logs) {
487 LOG(INFO) << "Set up image callback for node " << node_list[i];
488 frc971::vision::ImageCallback *image_callback =
489 new frc971::vision::ImageCallback(
490 detection_event_loops[i].get(), "/" + node_list[i] + "/camera",
491 [&reader, &charuco_extractors, &detection_event_loops, &node_list,
492 i](cv::Mat rgb_image,
493 const aos::monotonic_clock::time_point eof) {
494 aos::distributed_clock::time_point pi_distributed_time =
495 reader.event_loop_factory()
496 ->GetNodeEventLoopFactory(
497 detection_event_loops[i].get()->node())
498 ->ToDistributedClock(eof);
499 HandleImage(detection_event_loops[i].get(), rgb_image, eof,
500 pi_distributed_time, *charuco_extractors[i],
501 node_list[i]);
502 });
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700503
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800504 image_callbacks.emplace_back(image_callback);
505 } else {
506 detection_event_loops[i]->MakeWatcher(
507 "/camera", [&reader, &detection_event_loops, &node_list,
508 i](const TargetMap &map) {
509 aos::distributed_clock::time_point pi_distributed_time =
510 reader.event_loop_factory()
511 ->GetNodeEventLoopFactory(detection_event_loops[i]->node())
512 ->ToDistributedClock(aos::monotonic_clock::time_point(
513 aos::monotonic_clock::duration(
514 map.monotonic_timestamp_ns())));
515
516 HandleTargetMap(map, pi_distributed_time, node_list[i]);
517 });
518 LOG(INFO) << "Created watcher for using the detection event loop for "
519 << node_list[i] << " with i = " << i << " and size "
520 << detection_event_loops.size();
521 }
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700522 }
523
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700524 reader.event_loop_factory()->Run();
525
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700526 // Do quick check to see what averaged two-board pose for each pi is
527 // individually
528 CHECK_GT(two_board_extrinsics_list.size(), 0u)
529 << "Must have at least one view of both boards";
530 int base_target_id = two_board_extrinsics_list[0].board_id;
531 VLOG(1) << "Base id for two_board_extrinsics_list is " << base_target_id;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700532 for (auto node : node_list) {
533 std::vector<TimestampedPiDetection> pose_list;
534 for (auto ext : two_board_extrinsics_list) {
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700535 CHECK_EQ(base_target_id, ext.board_id)
536 << " All boards should have same reference id";
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700537 if (ext.pi_name == node) {
538 pose_list.push_back(ext);
539 }
540 }
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700541 Eigen::Affine3d avg_pose_from_pi = ComputeAveragePose(pose_list);
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700542 VLOG(1) << "Estimate from " << node << " with " << pose_list.size()
543 << " observations is:\n"
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700544 << avg_pose_from_pi.matrix();
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700545 }
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700546 Eigen::Affine3d H_boardA_boardB_avg =
547 ComputeAveragePose(two_board_extrinsics_list);
548 // TODO: Should probably do some outlier rejection
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700549 LOG(INFO) << "Estimate of two board pose using all nodes with "
550 << two_board_extrinsics_list.size() << " observations is:\n"
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700551 << H_boardA_boardB_avg.matrix() << "\n";
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700552
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700553 // Next, compute the relative camera poses
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700554 LOG(INFO) << "Got " << detection_list.size() << " extrinsic observations";
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700555 std::vector<Eigen::Affine3d> H_camera1_camera2_list;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700556 std::vector<Eigen::Affine3d> updated_extrinsics;
557 // Use the first node's extrinsics as our base, and fix from there
558 updated_extrinsics.push_back(default_extrinsics[0]);
559 LOG(INFO) << "Default extrinsic for node " << node_list[0] << " is "
560 << default_extrinsics[0].matrix();
561 for (uint i = 0; i < node_list.size() - 1; i++) {
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700562 H_camera1_camera2_list.clear();
563 // Go through the list, and find successive pairs of cameras
564 for (auto [pose1, pose2] : detection_list) {
565 if ((pose1.pi_name == node_list[i]) &&
566 (pose2.pi_name == node_list[i + 1])) {
567 Eigen::Affine3d H_camera1_boardA = pose1.H_camera_target;
568 // If pose1 isn't referenced to base_target_id, correct that
569 if (pose1.board_id != base_target_id) {
570 // pose1.H_camera_target references boardB, so map back to boardA
571 H_camera1_boardA =
572 pose1.H_camera_target * H_boardA_boardB_avg.inverse();
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700573 }
574
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700575 // Now, get the camera2->boardA map (notice it's boardA, same as
576 // camera1, so we can compute the difference based both on boardA)
577 Eigen::Affine3d H_camera2_boardA = pose2.H_camera_target;
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800578 // If pose2 isn't referenced to boardA (base_target_id), correct
579 // that
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700580 if (pose2.board_id != base_target_id) {
581 // pose2.H_camera_target references boardB, so map back to boardA
582 H_camera2_boardA =
Jim Ostrowski1f7cdc62023-12-02 14:09:23 -0800583 pose2.H_camera_target * H_boardA_boardB_avg.inverse();
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700584 }
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700585
586 // Compute camera1->camera2 map
587 Eigen::Affine3d H_camera1_camera2 =
588 H_camera1_boardA * H_camera2_boardA.inverse();
589 H_camera1_camera2_list.push_back(H_camera1_camera2);
590 VLOG(1) << "Map from camera " << pose1.pi_name << " and tag "
591 << pose1.board_id << " with observation: \n"
592 << pose1.H_camera_target.matrix() << "\n to camera "
593 << pose2.pi_name << " and tag " << pose2.board_id
594 << " with observation: \n"
595 << pose2.H_camera_target.matrix() << "\ngot map as\n"
596 << H_camera1_camera2.matrix();
597
598 Eigen::Affine3d H_world_board;
599 H_world_board = Eigen::Translation3d::Identity() *
600 Eigen::AngleAxisd(M_PI / 2.0, Eigen::Vector3d::UnitX());
601 if (FLAGS_alt_view) {
602 H_world_board = Eigen::Translation3d(0.0, 0.0, 3.0);
603 }
604
605 VLOG(2) << "Camera1 " << pose1.pi_name << " in world frame is \n"
606 << (H_world_board * H_camera1_boardA.inverse()).matrix();
607 VLOG(2) << "Camera2 " << pose2.pi_name << " in world frame is \n"
608 << (H_world_board * H_camera2_boardA.inverse()).matrix();
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700609 }
610 }
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700611 // TODO<Jim>: If we don't get any matches, we could just use default
612 // extrinsics
613 CHECK(H_camera1_camera2_list.size() > 0)
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700614 << "Failed with zero poses for node " << node_list[i];
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700615 if (H_camera1_camera2_list.size() > 0) {
616 Eigen::Affine3d H_camera1_camera2_avg =
617 ComputeAveragePose(H_camera1_camera2_list);
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700618 LOG(INFO) << "From " << node_list[i] << " to " << node_list[i + 1]
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700619 << " found " << H_camera1_camera2_list.size()
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700620 << " observations, and the average pose is:\n"
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700621 << H_camera1_camera2_avg.matrix();
622 Eigen::Affine3d H_camera1_camera2_default =
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700623 default_extrinsics[i].inverse() * default_extrinsics[i + 1];
624 LOG(INFO) << "Compare this to that from default values:\n"
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700625 << H_camera1_camera2_default.matrix();
626 Eigen::Affine3d H_camera1_camera2_diff =
627 H_camera1_camera2_avg * H_camera1_camera2_default.inverse();
628 LOG(INFO)
629 << "Difference between averaged and default delta poses "
630 "has |T| = "
631 << H_camera1_camera2_diff.translation().norm() << "m and |R| = "
632 << Eigen::AngleAxisd(H_camera1_camera2_diff.rotation()).angle()
633 << " radians ("
634 << Eigen::AngleAxisd(H_camera1_camera2_diff.rotation()).angle() *
635 180.0 / M_PI
636 << " degrees)";
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700637 // Next extrinsic is just previous one * avg_delta_pose
638 Eigen::Affine3d next_extrinsic =
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700639 updated_extrinsics.back() * H_camera1_camera2_avg;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700640 updated_extrinsics.push_back(next_extrinsic);
641 LOG(INFO) << "Default Extrinsic for " << node_list[i + 1] << " is \n"
642 << default_extrinsics[i + 1].matrix();
643 LOG(INFO) << "--> Updated Extrinsic for " << node_list[i + 1] << " is \n"
644 << next_extrinsic.matrix();
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800645
646 // Wirte out this extrinsic to a file
647 flatbuffers::FlatBufferBuilder fbb;
648 flatbuffers::Offset<flatbuffers::Vector<float>> data_offset =
649 fbb.CreateVector(
650 frc971::vision::MatrixToVector(next_extrinsic.matrix()));
651 calibration::TransformationMatrix::Builder matrix_builder(fbb);
652 matrix_builder.add_data(data_offset);
653 flatbuffers::Offset<calibration::TransformationMatrix>
654 extrinsic_calibration_offset = matrix_builder.Finish();
655
656 calibration::CameraCalibration::Builder calibration_builder(fbb);
657 calibration_builder.add_fixed_extrinsics(extrinsic_calibration_offset);
658 const aos::realtime_clock::time_point realtime_now =
659 aos::realtime_clock::now();
660 calibration_builder.add_calibration_timestamp(
661 realtime_now.time_since_epoch().count());
662 fbb.Finish(calibration_builder.Finish());
663 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
664 solved_extrinsics = fbb.Release();
665
666 aos::FlatbufferDetachedBuffer<
667 frc971::vision::calibration::CameraCalibration>
668 cal_copy = aos::RecursiveCopyFlatBuffer(calibration_list[i + 1]);
669 cal_copy.mutable_message()->clear_fixed_extrinsics();
670 cal_copy.mutable_message()->clear_calibration_timestamp();
671 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
672 merged_calibration = aos::MergeFlatBuffers(
673 &cal_copy.message(), &solved_extrinsics.message());
674
675 std::stringstream time_ss;
676 time_ss << realtime_now;
677
678 // Assumes node_list name is of form "pi#" to create camera id
679 const std::string calibration_filename =
680 FLAGS_output_folder +
681 absl::StrFormat("/calibration_pi-%d-%s_cam-%s_%s.json",
682 FLAGS_team_number, node_list[i + 1].substr(2, 3),
683 calibration_list[i + 1]->camera_id()->data(),
684 time_ss.str());
685
686 LOG(INFO) << calibration_filename << " -> "
687 << aos::FlatbufferToJson(merged_calibration,
688 {.multi_line = true});
689
690 aos::util::WriteStringToFileOrDie(
691 calibration_filename,
692 aos::FlatbufferToJson(merged_calibration, {.multi_line = true}));
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700693 }
694 }
695
696 // Cleanup
697 for (uint i = 0; i < image_callbacks.size(); i++) {
698 delete charuco_extractors[i];
699 delete image_callbacks[i];
700 }
701}
702} // namespace vision
703} // namespace y2023
704
705int main(int argc, char **argv) {
706 aos::InitGoogle(&argc, &argv);
707 y2023::vision::ExtrinsicsMain(argc, argv);
708}