blob: 2c2ddd3003f8c643608f759b077c0ad7b9c50bf6 [file] [log] [blame]
Jim Ostrowski9bf206a2024-01-26 23:31:58 -08001#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"
12#include "frc971/vision/extrinsics_calibration.h"
13#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 "frc971/constants/constants_sender_lib.h"
26#include "frc971/vision/vision_util_lib.h"
27#include "y2024/constants/simulated_constants_sender.h"
28#include "y2024/vision/vision_util.h"
29
30DEFINE_bool(alt_view, false,
31 "If true, show visualization from field level, rather than above");
32DEFINE_string(config, "",
33 "If set, override the log's config file with this one.");
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -080034DEFINE_string(constants_path, "y2024/constants/constants.json",
Jim Ostrowski9bf206a2024-01-26 23:31:58 -080035 "Path to the constant file");
36DEFINE_double(max_pose_error, 5e-5,
37 "Throw out target poses with a higher pose error than this");
38DEFINE_double(
39 max_pose_error_ratio, 0.4,
40 "Throw out target poses with a higher pose error ratio than this");
41DEFINE_string(output_folder, "/tmp",
42 "Directory in which to store the updated calibration files");
43DEFINE_string(target_type, "charuco_diamond",
44 "Type of target being used [aruco, charuco, charuco_diamond]");
45DEFINE_int32(team_number, 0,
46 "Required: Use the calibration for a node with this team number");
47DEFINE_bool(use_full_logs, false,
48 "If true, extract data from logs with images");
49DEFINE_uint64(
50 wait_key, 1,
51 "Time in ms to wait between images (0 to wait indefinitely until click)");
52
53DECLARE_int32(min_target_id);
54DECLARE_int32(max_target_id);
55
56// Calibrate extrinsic relationship between cameras using two targets
57// seen jointly between cameras. Uses two types of information: 1)
58// when a single camera sees two targets, we estimate the pose between
59// targets, and 2) when two separate cameras each see a target, we can
60// use the pose between targets to estimate the pose between cameras.
61
62// We then create the extrinsics for the robot by starting with the
63// given extrinsic for camera 1 (between imu/robot and camera frames)
64// and then map each subsequent camera based on the data collected and
65// the extrinsic poses computed here.
66
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -080067// TODO<Jim>: Not currently using estimate from first camera to last camera--
68// should do full estimation, and probably also include camera->imu extrinsics
69// from all cameras, not just first camera
Jim Ostrowski9bf206a2024-01-26 23:31:58 -080070
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -080071namespace y2024::vision {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -080072using frc971::vision::DataAdapter;
73using frc971::vision::ImageCallback;
74using frc971::vision::PoseUtils;
75using frc971::vision::TargetMap;
76using frc971::vision::TargetMapper;
77using frc971::vision::VisualizeRobot;
78namespace 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;
104VisualizeRobot vis_robot_;
105
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
174void 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) {
178 // 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;
189 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);
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800259 }
260 detection_list.push_back(new_pair);
261
262 // This bit is just for visualization and checking purposes-- use the
263 // last two-board observation to figure out the current estimate
264 // between the two cameras
265 if (FLAGS_visualize && two_board_extrinsics_list.size() > 0) {
266 draw_vis = true;
267 TimestampedPiDetection &last_two_board_ext =
268 two_board_extrinsics_list[two_board_extrinsics_list.size() - 1];
269 Eigen::Affine3d &H_boardA_boardB = last_two_board_ext.H_camera_target;
270 int boardA_boardB_id = last_two_board_ext.board_id;
271
272 TimestampedPiDetection camera1_boardA = new_pair.first;
273 TimestampedPiDetection camera2_boardB = new_pair.second;
274 // If camera1_boardA doesn't point to the first target, then swap
275 // these two
276 if (camera1_boardA.board_id != boardA_boardB_id) {
277 camera1_boardA = new_pair.second;
278 camera2_boardB = new_pair.first;
279 }
280 VLOG(1) << "Camera " << camera1_boardA.pi_name << " seeing board "
281 << camera1_boardA.board_id << " and camera "
282 << camera2_boardB.pi_name << " seeing board "
283 << camera2_boardB.board_id;
284
285 vis_robot_.DrawRobotOutline(
286 H_world_board * camera1_boardA.H_camera_target.inverse(),
287 camera1_boardA.pi_name, cv::Scalar(0, 0, 255));
288 vis_robot_.DrawRobotOutline(
289 H_world_board * H_boardA_boardB *
290 camera2_boardB.H_camera_target.inverse(),
291 camera2_boardB.pi_name, cv::Scalar(128, 128, 0));
292 vis_robot_.DrawFrameAxes(
293 H_world_board,
294 std::string("Board ") + std::to_string(last_two_board_ext.board_id),
295 cv::Scalar(0, 255, 0));
296 vis_robot_.DrawFrameAxes(H_world_board * H_boardA_boardB, "Board B",
297 cv::Scalar(255, 0, 0));
298 }
299 VLOG(1) << "Storing observation between " << new_pair.first.pi_name
300 << ", target " << new_pair.first.board_id << " and "
301 << new_pair.second.pi_name << ", target "
302 << new_pair.second.board_id;
303 } else {
304 VLOG(2) << "Storing observation for " << node_name << " at time "
305 << distributed_eof;
306 last_observation = new_observation;
307 }
308 }
309
310 if (FLAGS_visualize) {
311 if (!rgb_image.empty()) {
312 std::string image_name = node_name + " Image";
313 cv::Mat rgb_small;
314 cv::resize(rgb_image, rgb_small, cv::Size(), 0.5, 0.5);
315 cv::imshow(image_name, rgb_small);
316 cv::waitKey(FLAGS_wait_key);
317 }
318
319 if (draw_vis) {
320 cv::imshow("View", vis_robot_.image_);
321 cv::waitKey(FLAGS_wait_key);
322 vis_robot_.ClearImage();
323 }
324 }
325}
326
327void HandleTargetMap(const TargetMap &map,
328 aos::distributed_clock::time_point distributed_eof,
329 std::string node_name) {
330 VLOG(1) << "Got april tag map call from node " << node_name;
331 // Create empty RGB image in this case
332 cv::Mat rgb_image;
333 std::vector<TargetMapper::TargetPose> target_poses;
334
335 for (const auto *target_pose_fbs : *map.target_poses()) {
336 // Skip detections with invalid ids
337 if (static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) <
338 FLAGS_min_target_id ||
339 static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) >
340 FLAGS_max_target_id) {
341 LOG(INFO) << "Skipping tag with invalid id of " << target_pose_fbs->id();
342 continue;
343 }
344
345 // Skip detections with high pose errors
346 if (target_pose_fbs->pose_error() > FLAGS_max_pose_error) {
347 LOG(INFO) << "Skipping tag " << target_pose_fbs->id()
348 << " due to pose error of " << target_pose_fbs->pose_error();
349 continue;
350 }
351 // Skip detections with high pose error ratios
352 if (target_pose_fbs->pose_error_ratio() > FLAGS_max_pose_error_ratio) {
353 LOG(INFO) << "Skipping tag " << target_pose_fbs->id()
354 << " due to pose error ratio of "
355 << target_pose_fbs->pose_error_ratio();
356 continue;
357 }
358
359 const TargetMapper::TargetPose target_pose =
360 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
361
362 target_poses.emplace_back(target_pose);
363
364 Eigen::Affine3d H_camera_target =
365 PoseUtils::Pose3dToAffine3d(target_pose.pose);
366 VLOG(2) << node_name << " saw target " << target_pose.id
367 << " from TargetMap at timestamp " << distributed_eof
368 << " with pose = " << H_camera_target.matrix();
369 }
370 HandlePoses(rgb_image, target_poses, distributed_eof, node_name);
371}
372
373void HandleImage(aos::EventLoop *event_loop, cv::Mat rgb_image,
374 const aos::monotonic_clock::time_point eof,
375 aos::distributed_clock::time_point distributed_eof,
376 frc971::vision::CharucoExtractor &charuco_extractor,
377 std::string node_name) {
378 std::vector<cv::Vec4i> charuco_ids;
379 std::vector<std::vector<cv::Point2f>> charuco_corners;
380 bool valid = false;
381 std::vector<Eigen::Vector3d> rvecs_eigen;
382 std::vector<Eigen::Vector3d> tvecs_eigen;
383 // Why eof vs. distributed_eof?
384 charuco_extractor.ProcessImage(rgb_image, eof, event_loop->monotonic_now(),
385 charuco_ids, charuco_corners, valid,
386 rvecs_eigen, tvecs_eigen);
387 if (rvecs_eigen.size() > 0 && !valid) {
388 LOG(WARNING) << "Charuco extractor returned not valid";
389 return;
390 }
391
392 std::vector<TargetMapper::TargetPose> target_poses;
393 for (size_t i = 0; i < tvecs_eigen.size(); i++) {
394 Eigen::Quaterniond rotation(
395 frc971::controls::ToQuaternionFromRotationVector(rvecs_eigen[i]));
396 ceres::examples::Pose3d pose(Eigen::Vector3d(tvecs_eigen[i]), rotation);
397 TargetMapper::TargetPose target_pose{charuco_ids[i][0], pose};
398 target_poses.emplace_back(target_pose);
399
400 Eigen::Affine3d H_camera_target = PoseUtils::Pose3dToAffine3d(pose);
401 VLOG(2) << node_name << " saw target " << target_pose.id
402 << " from image at timestamp " << distributed_eof
403 << " with pose = " << H_camera_target.matrix();
404 }
405 HandlePoses(rgb_image, target_poses, distributed_eof, node_name);
406}
407
408void ExtrinsicsMain(int argc, char *argv[]) {
409 vis_robot_ = VisualizeRobot(cv::Size(1000, 1000));
410 vis_robot_.ClearImage();
411 const double kFocalLength = 1000.0;
412 const int kImageWidth = 1000;
413 vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength);
414
415 std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config =
416 (FLAGS_config.empty()
417 ? std::nullopt
418 : std::make_optional(aos::configuration::ReadConfig(FLAGS_config)));
419
420 // open logfiles
421 aos::logger::LogReader reader(
422 aos::logger::SortParts(aos::logger::FindLogs(argc, argv)),
423 config.has_value() ? &config->message() : nullptr);
424
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800425 reader.RemapLoggedChannel("/imu/constants", "y2024.Constants");
426 reader.RemapLoggedChannel("/orin1/constants", "y2024.Constants");
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800427 reader.Register();
428
429 y2024::SendSimulationConstants(reader.event_loop_factory(), FLAGS_team_number,
430 FLAGS_constants_path);
431
432 VLOG(1) << "Using target type " << FLAGS_target_type;
433 std::vector<std::string> node_list;
Maxwell Henderson3279bc52024-03-01 09:50:53 -0800434 node_list.push_back("imu");
Maxwell Henderson69ec45e2024-03-01 22:52:21 -0800435 node_list.push_back("orin1");
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800436 std::vector<std::string> camera_list;
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800437 std::vector<const calibration::CameraCalibration *> calibration_list;
438
439 std::vector<std::unique_ptr<aos::EventLoop>> detection_event_loops;
440 std::vector<frc971::vision::CharucoExtractor *> charuco_extractors;
441 std::vector<frc971::vision::ImageCallback *> image_callbacks;
442 std::vector<Eigen::Affine3d> default_extrinsics;
443
444 for (uint i = 0; i < node_list.size(); i++) {
445 std::string node = node_list[i];
446 const aos::Node *pi =
447 aos::configuration::GetNode(reader.configuration(), node.c_str());
448
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800449 for (const std::string camera : {"/camera0", "/camera1"}) {
450 std::string camera_name = "/" + node + camera;
451 camera_list.push_back(camera_name);
Maxwell Henderson69ec45e2024-03-01 22:52:21 -0800452
453 detection_event_loops.emplace_back(
454 reader.event_loop_factory()->MakeEventLoop(
455 (camera_name + "_detection").c_str(), pi));
456
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800457 frc971::constants::ConstantsFetcher<y2024::Constants> constants_fetcher(
458 detection_event_loops.back().get());
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800459
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800460 // Get the calibration for this orin/camera pair
461 int camera_id = std::stoi(camera.substr(7, 1));
462 const calibration::CameraCalibration *calibration =
463 y2024::vision::FindCameraCalibration(constants_fetcher.constants(),
464 node, camera_id);
465 calibration_list.push_back(calibration);
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800466
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800467 // Extract the extrinsics from the calibration, and save as "defaults"
468 cv::Mat extrinsics_cv =
469 frc971::vision::CameraExtrinsics(calibration).value();
470 Eigen::Matrix4d extrinsics_matrix;
471 cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
472 const auto ext_H_robot_pi = Eigen::Affine3d(extrinsics_matrix);
473 default_extrinsics.emplace_back(ext_H_robot_pi);
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800474
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800475 VLOG(1) << "Got extrinsics for " << node << ", " << camera << " as\n"
476 << default_extrinsics.back().matrix();
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800477
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800478 // If we've got full logs, we need to set up a charuco/april tag extractor
479 // nd a call back to handle the data
480 if (FLAGS_use_full_logs) {
481 frc971::vision::TargetType target_type =
482 frc971::vision::TargetTypeFromString(FLAGS_target_type);
483 frc971::vision::CharucoExtractor *charuco_ext =
484 new frc971::vision::CharucoExtractor(calibration, target_type);
485 charuco_extractors.emplace_back(charuco_ext);
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800486
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800487 LOG(INFO) << "Set up image callback for node " << node << ", camera "
488 << camera;
489 frc971::vision::ImageCallback *image_callback =
490 new frc971::vision::ImageCallback(
491 detection_event_loops[i].get(), camera_name,
492 [&reader, &charuco_extractors, &detection_event_loops,
493 &node_list, i](cv::Mat rgb_image,
494 const aos::monotonic_clock::time_point eof) {
495 aos::distributed_clock::time_point pi_distributed_time =
496 reader.event_loop_factory()
497 ->GetNodeEventLoopFactory(
498 detection_event_loops[i].get()->node())
499 ->ToDistributedClock(eof);
500 HandleImage(detection_event_loops[i].get(), rgb_image, eof,
501 pi_distributed_time, *charuco_extractors[i],
502 node_list[i]);
503 });
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800504
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800505 image_callbacks.emplace_back(image_callback);
506 } else {
507 detection_event_loops[i]->MakeWatcher(
508 camera, [&reader, &detection_event_loops, camera_name,
509 i](const TargetMap &map) {
510 aos::distributed_clock::time_point pi_distributed_time =
511 reader.event_loop_factory()
512 ->GetNodeEventLoopFactory(
513 detection_event_loops[i]->node())
514 ->ToDistributedClock(aos::monotonic_clock::time_point(
515 aos::monotonic_clock::duration(
516 map.monotonic_timestamp_ns())));
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800517
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800518 HandleTargetMap(map, pi_distributed_time, camera_name);
519 });
520 LOG(INFO) << "Created watcher for using the detection event loop for "
521 << node << " with i = " << i << " and size "
522 << detection_event_loops.size() << " and camera " << camera;
523 }
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800524 }
525 }
526
527 reader.event_loop_factory()->Run();
528
529 // Do quick check to see what averaged two-board pose for each pi is
530 // individually
531 CHECK_GT(two_board_extrinsics_list.size(), 0u)
532 << "Must have at least one view of both boards";
533 int base_target_id = two_board_extrinsics_list[0].board_id;
534 VLOG(1) << "Base id for two_board_extrinsics_list is " << base_target_id;
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800535 for (auto camera : camera_list) {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800536 std::vector<TimestampedPiDetection> pose_list;
537 for (auto ext : two_board_extrinsics_list) {
538 CHECK_EQ(base_target_id, ext.board_id)
539 << " All boards should have same reference id";
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800540 if (ext.pi_name == camera) {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800541 pose_list.push_back(ext);
542 }
543 }
544 Eigen::Affine3d avg_pose_from_pi = ComputeAveragePose(pose_list);
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800545 VLOG(1) << "Estimate from " << camera << " with " << pose_list.size()
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800546 << " observations is:\n"
547 << avg_pose_from_pi.matrix();
548 }
549 Eigen::Affine3d H_boardA_boardB_avg =
550 ComputeAveragePose(two_board_extrinsics_list);
551 // TODO: Should probably do some outlier rejection
552 LOG(INFO) << "Estimate of two board pose using all nodes with "
553 << two_board_extrinsics_list.size() << " observations is:\n"
554 << H_boardA_boardB_avg.matrix() << "\n";
555
556 // Next, compute the relative camera poses
557 LOG(INFO) << "Got " << detection_list.size() << " extrinsic observations";
558 std::vector<Eigen::Affine3d> H_camera1_camera2_list;
559 std::vector<Eigen::Affine3d> updated_extrinsics;
560 // Use the first node's extrinsics as our base, and fix from there
561 updated_extrinsics.push_back(default_extrinsics[0]);
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800562 LOG(INFO) << "Default extrinsic for camera " << camera_list[0] << " is "
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800563 << default_extrinsics[0].matrix();
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800564 for (uint i = 0; i < camera_list.size() - 1; i++) {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800565 H_camera1_camera2_list.clear();
566 // Go through the list, and find successive pairs of cameras
567 for (auto [pose1, pose2] : detection_list) {
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800568 if ((pose1.pi_name == camera_list[i]) &&
569 (pose2.pi_name == camera_list[i + 1])) {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800570 Eigen::Affine3d H_camera1_boardA = pose1.H_camera_target;
571 // If pose1 isn't referenced to base_target_id, correct that
572 if (pose1.board_id != base_target_id) {
573 // pose1.H_camera_target references boardB, so map back to boardA
574 H_camera1_boardA =
575 pose1.H_camera_target * H_boardA_boardB_avg.inverse();
576 }
577
578 // Now, get the camera2->boardA map (notice it's boardA, same as
579 // camera1, so we can compute the difference based both on boardA)
580 Eigen::Affine3d H_camera2_boardA = pose2.H_camera_target;
581 // If pose2 isn't referenced to boardA (base_target_id), correct
582 // that
583 if (pose2.board_id != base_target_id) {
584 // pose2.H_camera_target references boardB, so map back to boardA
585 H_camera2_boardA =
586 pose2.H_camera_target * H_boardA_boardB_avg.inverse();
587 }
588
589 // Compute camera1->camera2 map
590 Eigen::Affine3d H_camera1_camera2 =
591 H_camera1_boardA * H_camera2_boardA.inverse();
592 H_camera1_camera2_list.push_back(H_camera1_camera2);
593 VLOG(1) << "Map from camera " << pose1.pi_name << " and tag "
594 << pose1.board_id << " with observation: \n"
595 << pose1.H_camera_target.matrix() << "\n to camera "
596 << pose2.pi_name << " and tag " << pose2.board_id
597 << " with observation: \n"
598 << pose2.H_camera_target.matrix() << "\ngot map as\n"
599 << H_camera1_camera2.matrix();
600
601 Eigen::Affine3d H_world_board;
602 H_world_board = Eigen::Translation3d::Identity() *
603 Eigen::AngleAxisd(M_PI / 2.0, Eigen::Vector3d::UnitX());
604 if (FLAGS_alt_view) {
605 H_world_board = Eigen::Translation3d(0.0, 0.0, 3.0);
606 }
607
608 VLOG(2) << "Camera1 " << pose1.pi_name << " in world frame is \n"
609 << (H_world_board * H_camera1_boardA.inverse()).matrix();
610 VLOG(2) << "Camera2 " << pose2.pi_name << " in world frame is \n"
611 << (H_world_board * H_camera2_boardA.inverse()).matrix();
612 }
613 }
614 // TODO<Jim>: If we don't get any matches, we could just use default
615 // extrinsics
616 CHECK(H_camera1_camera2_list.size() > 0)
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800617 << "Failed with zero poses for node " << camera_list[i];
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800618 if (H_camera1_camera2_list.size() > 0) {
619 Eigen::Affine3d H_camera1_camera2_avg =
620 ComputeAveragePose(H_camera1_camera2_list);
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800621 LOG(INFO) << "From " << camera_list[i] << " to " << camera_list[i + 1]
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800622 << " found " << H_camera1_camera2_list.size()
623 << " observations, and the average pose is:\n"
624 << H_camera1_camera2_avg.matrix();
625 Eigen::Affine3d H_camera1_camera2_default =
626 default_extrinsics[i].inverse() * default_extrinsics[i + 1];
627 LOG(INFO) << "Compare this to that from default values:\n"
628 << H_camera1_camera2_default.matrix();
629 Eigen::Affine3d H_camera1_camera2_diff =
630 H_camera1_camera2_avg * H_camera1_camera2_default.inverse();
631 LOG(INFO)
632 << "Difference between averaged and default delta poses "
633 "has |T| = "
634 << H_camera1_camera2_diff.translation().norm() << "m and |R| = "
635 << Eigen::AngleAxisd(H_camera1_camera2_diff.rotation()).angle()
636 << " radians ("
637 << Eigen::AngleAxisd(H_camera1_camera2_diff.rotation()).angle() *
638 180.0 / M_PI
639 << " degrees)";
640 // Next extrinsic is just previous one * avg_delta_pose
641 Eigen::Affine3d next_extrinsic =
642 updated_extrinsics.back() * H_camera1_camera2_avg;
643 updated_extrinsics.push_back(next_extrinsic);
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800644 LOG(INFO) << "Default Extrinsic for " << camera_list[i + 1] << " is \n"
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800645 << default_extrinsics[i + 1].matrix();
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800646 LOG(INFO) << "--> Updated Extrinsic for " << camera_list[i + 1]
647 << " is \n"
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800648 << next_extrinsic.matrix();
649
650 // Wirte out this extrinsic to a file
651 flatbuffers::FlatBufferBuilder fbb;
652 flatbuffers::Offset<flatbuffers::Vector<float>> data_offset =
653 fbb.CreateVector(
654 frc971::vision::MatrixToVector(next_extrinsic.matrix()));
655 calibration::TransformationMatrix::Builder matrix_builder(fbb);
656 matrix_builder.add_data(data_offset);
657 flatbuffers::Offset<calibration::TransformationMatrix>
658 extrinsic_calibration_offset = matrix_builder.Finish();
659
660 calibration::CameraCalibration::Builder calibration_builder(fbb);
661 calibration_builder.add_fixed_extrinsics(extrinsic_calibration_offset);
662 const aos::realtime_clock::time_point realtime_now =
663 aos::realtime_clock::now();
664 calibration_builder.add_calibration_timestamp(
665 realtime_now.time_since_epoch().count());
666 fbb.Finish(calibration_builder.Finish());
667 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
668 solved_extrinsics = fbb.Release();
669
670 aos::FlatbufferDetachedBuffer<
671 frc971::vision::calibration::CameraCalibration>
672 cal_copy = aos::RecursiveCopyFlatBuffer(calibration_list[i + 1]);
673 cal_copy.mutable_message()->clear_fixed_extrinsics();
674 cal_copy.mutable_message()->clear_calibration_timestamp();
675 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
676 merged_calibration = aos::MergeFlatBuffers(
677 &cal_copy.message(), &solved_extrinsics.message());
678
679 std::stringstream time_ss;
680 time_ss << realtime_now;
681
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800682 // TODO: This breaks because we're naming orin1 and imu as nodes
683 // Assumes camera_list name is of form "/orin#/cameraX" to create
684 // calibration filename
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800685 const std::string calibration_filename =
686 FLAGS_output_folder +
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800687 absl::StrFormat("/calibration_orin-%d-%s-%d_cam-%s_%s.json",
688 FLAGS_team_number, camera_list[i + 1].substr(5, 1),
689 calibration_list[i + 1]->camera_number(),
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800690 calibration_list[i + 1]->camera_id()->data(),
691 time_ss.str());
692
693 LOG(INFO) << calibration_filename << " -> "
694 << aos::FlatbufferToJson(merged_calibration,
695 {.multi_line = true});
696
697 aos::util::WriteStringToFileOrDie(
698 calibration_filename,
699 aos::FlatbufferToJson(merged_calibration, {.multi_line = true}));
700 }
701 }
702
703 // Cleanup
704 for (uint i = 0; i < image_callbacks.size(); i++) {
705 delete charuco_extractors[i];
706 delete image_callbacks[i];
707 }
708}
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800709} // namespace y2024::vision
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800710
711int main(int argc, char **argv) {
712 aos::InitGoogle(&argc, &argv);
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800713 y2024::vision::ExtrinsicsMain(argc, argv);
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800714}