blob: 4cd70c219a9557965ad28947d4ef22a7c06a8b1e [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"
12#include "frc971/vision/target_mapper.h"
13#include "frc971/vision/visualize_robot.h"
14// clang-format off
15// OpenCV eigen files must be included after Eigen includes
16#include "opencv2/aruco.hpp"
17#include "opencv2/calib3d.hpp"
18#include "opencv2/core/eigen.hpp"
19#include "opencv2/features2d.hpp"
20#include "opencv2/highgui.hpp"
21#include "opencv2/highgui/highgui.hpp"
22#include "opencv2/imgproc.hpp"
23// clang-format on
24#include "y2023/constants/simulated_constants_sender.h"
25#include "y2023/vision/aprilrobotics.h"
26#include "y2023/vision/vision_util.h"
27
Jim Ostrowski2be78e32023-03-25 11:57:54 -070028DEFINE_bool(alt_view, false,
29 "If true, show visualization from field level, rather than above");
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070030DEFINE_string(config, "",
31 "If set, override the log's config file with this one.");
32DEFINE_string(constants_path, "y2023/constants/constants.json",
33 "Path to the constant file");
34DEFINE_string(target_type, "charuco_diamond",
35 "Type of target being used [aruco, charuco, charuco_diamond]");
36DEFINE_int32(team_number, 0,
37 "Required: Use the calibration for a node with this team number");
38DEFINE_uint64(
39 wait_key, 1,
40 "Time in ms to wait between images (0 to wait indefinitely until click)");
41
42// Calibrate extrinsic relationship between cameras using two targets
43// seen jointly between cameras. Uses two types of information: 1)
44// when a single camera sees two targets, we estimate the pose between
45// targets, and 2) when two separate cameras each see a target, we can
46// use the pose between targets to estimate the pose between cameras.
47
48// We then create the extrinsics for the robot by starting with the
49// given extrinsic for camera 1 (between imu/robot and camera frames)
50// and then map each subsequent camera based on the data collected and
51// the extrinsic poses computed here.
52
53// TODO<Jim>: Should export a new extrinsic file for each camera
54// TODO<Jim>: Not currently using estimate from pi1->pi4-- should do full
55// estimation, and probably also include camera->imu extrinsics from all
56// cameras, not just pi1
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070057
58namespace y2023 {
59namespace vision {
60using frc971::vision::DataAdapter;
61using frc971::vision::ImageCallback;
62using frc971::vision::PoseUtils;
63using frc971::vision::TargetMap;
64using frc971::vision::TargetMapper;
Jim Ostrowski2be78e32023-03-25 11:57:54 -070065using frc971::vision::VisualizeRobot;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070066namespace calibration = frc971::vision::calibration;
67
68static constexpr double kImagePeriodMs =
69 1.0 / 30.0 * 1000.0; // Image capture period in ms
70
71// Change reference frame from camera to robot
72Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target,
73 Eigen::Affine3d extrinsics) {
74 const Eigen::Affine3d H_robot_camera = extrinsics;
75 const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target;
76 return H_robot_target;
77}
78
79struct TimestampedPiDetection {
80 aos::distributed_clock::time_point time;
81 // Pose of target relative to robot
82 Eigen::Affine3d H_camera_target;
83 // name of pi
84 std::string pi_name;
85 int board_id;
86};
87
88TimestampedPiDetection last_observation;
89std::vector<std::pair<TimestampedPiDetection, TimestampedPiDetection>>
90 detection_list;
91std::vector<TimestampedPiDetection> two_board_extrinsics_list;
Jim Ostrowski2be78e32023-03-25 11:57:54 -070092VisualizeRobot vis_robot_;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070093
94// TODO<jim>: Implement variance calcs
95Eigen::Affine3d ComputeAveragePose(
96 std::vector<Eigen::Vector3d> &translation_list,
97 std::vector<Eigen::Vector4d> &rotation_list,
98 Eigen::Vector3d *translation_variance = nullptr,
99 Eigen::Vector3d *rotation_variance = nullptr) {
100 Eigen::Vector3d avg_translation =
101 std::accumulate(translation_list.begin(), translation_list.end(),
102 Eigen::Vector3d{0, 0, 0}) /
103 translation_list.size();
104
105 // TODO<Jim>: Use QuaternionMean from quaternion_utils.cc (but this
106 // requires a fixed number of quaternions to be averaged
107 Eigen::Vector4d avg_rotation =
108 std::accumulate(rotation_list.begin(), rotation_list.end(),
109 Eigen::Vector4d{0, 0, 0, 0}) /
110 rotation_list.size();
111 // Normalize, so it's a valid quaternion
112 avg_rotation = avg_rotation / avg_rotation.norm();
113 Eigen::Quaterniond avg_rotation_q{avg_rotation[0], avg_rotation[1],
114 avg_rotation[2], avg_rotation[3]};
115 Eigen::Translation3d translation(avg_translation);
116 Eigen::Affine3d return_pose = translation * avg_rotation_q;
117 if (translation_variance != nullptr) {
118 *translation_variance = Eigen::Vector3d();
119 }
120 if (rotation_variance != nullptr) {
121 LOG(INFO) << *rotation_variance;
122 }
123
124 return return_pose;
125}
126
127Eigen::Affine3d ComputeAveragePose(
128 std::vector<Eigen::Affine3d> &pose_list,
129 Eigen::Vector3d *translation_variance = nullptr,
130 Eigen::Vector3d *rotation_variance = nullptr) {
131 std::vector<Eigen::Vector3d> translation_list;
132 std::vector<Eigen::Vector4d> rotation_list;
133
134 for (Eigen::Affine3d pose : pose_list) {
135 translation_list.push_back(pose.translation());
136 Eigen::Quaterniond quat(pose.rotation().matrix());
137 rotation_list.push_back(
138 Eigen::Vector4d(quat.w(), quat.x(), quat.y(), quat.z()));
139 }
140
141 return ComputeAveragePose(translation_list, rotation_list,
142 translation_variance, rotation_variance);
143}
144
145Eigen::Affine3d ComputeAveragePose(
146 std::vector<TimestampedPiDetection> &pose_list,
147 Eigen::Vector3d *translation_variance = nullptr,
148 Eigen::Vector3d *rotation_variance = nullptr) {
149 std::vector<Eigen::Vector3d> translation_list;
150 std::vector<Eigen::Vector4d> rotation_list;
151
152 for (TimestampedPiDetection pose : pose_list) {
153 translation_list.push_back(pose.H_camera_target.translation());
154 Eigen::Quaterniond quat(pose.H_camera_target.rotation().matrix());
155 rotation_list.push_back(
156 Eigen::Vector4d(quat.w(), quat.x(), quat.y(), quat.z()));
157 }
158 return ComputeAveragePose(translation_list, rotation_list,
159 translation_variance, rotation_variance);
160}
161
162void ProcessImage(aos::EventLoop *event_loop, cv::Mat rgb_image,
163 const aos::monotonic_clock::time_point eof,
164 aos::distributed_clock::time_point distributed_eof,
165 frc971::vision::CharucoExtractor &charuco_extractor,
166 std::string pi_name) {
167 std::vector<cv::Vec4i> charuco_ids;
168 std::vector<std::vector<cv::Point2f>> charuco_corners;
169 bool valid = false;
170 std::vector<Eigen::Vector3d> rvecs_eigen;
171 std::vector<Eigen::Vector3d> tvecs_eigen;
172 charuco_extractor.ProcessImage(rgb_image, eof, event_loop->monotonic_now(),
173 charuco_ids, charuco_corners, valid,
174 rvecs_eigen, tvecs_eigen);
175
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700176 // This is used to transform points for visualization
177 // Assumes targets are aligned with x->right, y->up, z->out of board
178 Eigen::Affine3d H_world_board;
179 H_world_board = Eigen::Translation3d::Identity() *
180 Eigen::AngleAxisd(M_PI / 2.0, Eigen::Vector3d::UnitX());
181 if (FLAGS_alt_view) {
182 // Don't rotate -- this is like viewing from the side
183 H_world_board = Eigen::Translation3d(0.0, 0.0, 3.0);
184 }
185
186 bool draw_vis = false;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700187 if (valid) {
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700188 CHECK_LE(tvecs_eigen.size(), 2u)
189 << "Can't handle more than two tags in field of view";
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700190 if (tvecs_eigen.size() == 2) {
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700191 draw_vis = true;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700192 VLOG(2) << "Saw two boards in same view from " << pi_name;
193 // Handle when we see two boards at once
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700194 // We'll store them referenced to the lower id board
195 int from_index = 0;
196 int to_index = 1;
197 if (charuco_ids[from_index][0] > charuco_ids[to_index][0]) {
198 std::swap<int>(from_index, to_index);
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700199 }
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700200
201 // Create "from" (A) and "to" (B) transforms
202 Eigen::Quaternion<double> rotationA(
203 frc971::controls::ToQuaternionFromRotationVector(
204 rvecs_eigen[from_index]));
205 Eigen::Translation3d translationA(tvecs_eigen[from_index]);
206 Eigen::Affine3d H_camera_boardA = translationA * rotationA;
207
208 Eigen::Quaternion<double> rotationB(
209 frc971::controls::ToQuaternionFromRotationVector(
210 rvecs_eigen[to_index]));
211 Eigen::Translation3d translationB(tvecs_eigen[to_index]);
212 Eigen::Affine3d H_camera_boardB = translationB * rotationB;
213
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700214 Eigen::Affine3d H_boardA_boardB =
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700215 H_camera_boardA.inverse() * H_camera_boardB;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700216
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700217 TimestampedPiDetection boardA_boardB{
218 .time = distributed_eof,
219 .H_camera_target = H_boardA_boardB,
220 .pi_name = pi_name,
221 .board_id = charuco_ids[from_index][0]};
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700222
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700223 VLOG(1) << "Map from board " << from_index << " to " << to_index
224 << " is\n"
225 << H_boardA_boardB.matrix();
226 // Store this observation of the transform between two boards
227 two_board_extrinsics_list.push_back(boardA_boardB);
228
229 if (FLAGS_visualize) {
230 vis_robot_.DrawFrameAxes(
231 H_world_board,
232 std::string("board ") + std::to_string(charuco_ids[from_index][0]),
233 cv::Scalar(0, 255, 0));
234 vis_robot_.DrawFrameAxes(
235 H_world_board * boardA_boardB.H_camera_target,
236 std::string("board ") + std::to_string(charuco_ids[to_index][0]),
237 cv::Scalar(255, 0, 0));
238 VLOG(2) << "Detection map from camera " << pi_name << " to board "
239 << charuco_ids[from_index][0] << " is\n"
240 << H_camera_boardA.matrix() << "\n and inverse is\n"
241 << H_camera_boardA.inverse().matrix()
242 << "\n and with world to board rotation is\n"
243 << H_world_board * H_camera_boardA.inverse().matrix();
244 vis_robot_.DrawRobotOutline(H_world_board * H_camera_boardA.inverse(),
245 pi_name, cv::Scalar(0, 0, 255));
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700246 }
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700247
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700248 } else {
249 VLOG(1) << "Saw single board in camera " << pi_name;
250 Eigen::Quaternion<double> rotation(
251 frc971::controls::ToQuaternionFromRotationVector(rvecs_eigen[0]));
252 Eigen::Translation3d translation(tvecs_eigen[0]);
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700253 Eigen::Affine3d H_camera2_board2 = translation * rotation;
254 TimestampedPiDetection new_observation{
255 .time = distributed_eof,
256 .H_camera_target = H_camera2_board2,
257 .pi_name = pi_name,
258 .board_id = charuco_ids[0][0]};
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700259
260 VLOG(2) << "Checking versus last result from " << last_observation.pi_name
261 << " at time " << last_observation.time << " with delta time = "
262 << std::abs((distributed_eof - last_observation.time).count());
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700263 // Now, check if this new observation can be paired with a
264 // previous single board observation.
265
266 // Only take two observations if they're near enough to each
267 // other in time. This should be within +/- kImagePeriodMs of
268 // each other (e.g., +/-16.666ms for 30 Hz capture). This
269 // should make sure we're always getting the closest images, and
270 // not miss too many possible pairs, between cameras
271
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700272 // TODO<Jim>: Should also check that (rotational) velocity of the robot is
273 // small
274 if (std::abs((distributed_eof - last_observation.time).count()) <
275 static_cast<int>(kImagePeriodMs / 2.0 * 1000000)) {
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700276 // Sort by pi numbering, since this is how we will handle them
277 std::pair<TimestampedPiDetection, TimestampedPiDetection> new_pair;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700278 if (last_observation.pi_name < new_observation.pi_name) {
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700279 new_pair = std::pair(last_observation, new_observation);
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700280 } else if (last_observation.pi_name > new_observation.pi_name) {
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700281 new_pair = std::pair(new_observation, last_observation);
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700282 } else {
283 LOG(WARNING) << "Got 2 observations in a row from same pi. Probably "
284 "not too much of an issue???";
285 }
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700286 detection_list.push_back(new_pair);
287
288 // This bit is just for visualization and checking purposes-- use the
289 // last two-board observation to figure out the current estimate between
290 // the two cameras
291 if (FLAGS_visualize && two_board_extrinsics_list.size() > 0) {
292 draw_vis = true;
293 TimestampedPiDetection &last_two_board_ext =
294 two_board_extrinsics_list[two_board_extrinsics_list.size() - 1];
295 Eigen::Affine3d &H_boardA_boardB = last_two_board_ext.H_camera_target;
296 int boardA_boardB_id = last_two_board_ext.board_id;
297
298 TimestampedPiDetection camera1_boardA = new_pair.first;
299 TimestampedPiDetection camera2_boardB = new_pair.second;
300 // If camera1_boardA doesn't point to the first target, then swap
301 // these two
302 if (camera1_boardA.board_id != boardA_boardB_id) {
303 camera1_boardA = new_pair.second;
304 camera2_boardB = new_pair.first;
305 }
306 VLOG(1) << "Camera " << camera1_boardA.pi_name << " seeing board "
307 << camera1_boardA.board_id << " and camera "
308 << camera2_boardB.pi_name << " seeing board "
309 << camera2_boardB.board_id;
310
311 vis_robot_.DrawRobotOutline(
312 H_world_board * camera1_boardA.H_camera_target.inverse(),
313 camera1_boardA.pi_name, cv::Scalar(0, 0, 255));
314 vis_robot_.DrawRobotOutline(
315 H_world_board * H_boardA_boardB *
316 camera2_boardB.H_camera_target.inverse(),
317 camera2_boardB.pi_name, cv::Scalar(128, 128, 0));
318 vis_robot_.DrawFrameAxes(
319 H_world_board,
320 std::string("Board ") +
321 std::to_string(last_two_board_ext.board_id),
322 cv::Scalar(0, 255, 0));
323 vis_robot_.DrawFrameAxes(H_world_board * H_boardA_boardB, "Board B",
324 cv::Scalar(255, 0, 0));
325 Eigen::Affine3d H_camera1_camera2 =
326 camera1_boardA.H_camera_target * H_boardA_boardB *
327 camera2_boardB.H_camera_target.inverse();
328
329 VLOG(1) << "Storing observation between " << new_pair.first.pi_name
330 << ", target " << new_pair.first.board_id << " and "
331 << new_pair.second.pi_name << ", target "
332 << new_pair.second.board_id
333 << " and camera-to-camera offset:\n"
334 << H_camera1_camera2.matrix();
335 }
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700336 } else {
337 VLOG(2) << "Storing observation for " << pi_name << " at time "
338 << distributed_eof;
339 last_observation = new_observation;
340 }
341 }
342 }
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700343
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700344 if (FLAGS_visualize) {
345 std::string image_name = pi_name + " Image";
346 cv::Mat rgb_small;
347 cv::resize(rgb_image, rgb_small, cv::Size(), 0.5, 0.5);
348 cv::imshow(image_name, rgb_small);
349 cv::waitKey(FLAGS_wait_key);
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700350
351 if (draw_vis) {
352 cv::imshow("View", vis_robot_.image_);
353 cv::waitKey(1);
354 vis_robot_.ClearImage();
355 }
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700356 }
357}
358
359void ExtrinsicsMain(int argc, char *argv[]) {
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700360 vis_robot_ = VisualizeRobot(cv::Size(1000, 1000));
361 vis_robot_.ClearImage();
362 const double kFocalLength = 1000.0;
363 const int kImageWidth = 1000;
364 vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength);
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700365
366 std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config =
367 (FLAGS_config.empty()
368 ? std::nullopt
369 : std::make_optional(aos::configuration::ReadConfig(FLAGS_config)));
370
371 // open logfiles
372 aos::logger::LogReader reader(
373 aos::logger::SortParts(aos::logger::FindLogs(argc, argv)),
374 config.has_value() ? &config->message() : nullptr);
375
376 constexpr size_t kNumPis = 4;
377 for (size_t i = 1; i <= kNumPis; i++) {
378 reader.RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i),
379 "frc971.vision.TargetMap");
380 reader.RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i),
381 "foxglove.ImageAnnotations");
382 reader.RemapLoggedChannel(absl::StrFormat("/pi%u/constants", i),
383 "y2023.Constants");
384 }
385 reader.RemapLoggedChannel("/imu/constants", "y2023.Constants");
386 reader.Register();
387
388 SendSimulationConstants(reader.event_loop_factory(), FLAGS_team_number,
389 FLAGS_constants_path);
390
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700391 VLOG(1) << "Using target type " << FLAGS_target_type;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700392 std::vector<std::string> node_list;
393 node_list.push_back("pi1");
394 node_list.push_back("pi2");
395 node_list.push_back("pi3");
396 node_list.push_back("pi4");
397
398 std::vector<std::unique_ptr<aos::EventLoop>> detection_event_loops;
399 std::vector<frc971::vision::CharucoExtractor *> charuco_extractors;
400 std::vector<frc971::vision::ImageCallback *> image_callbacks;
401 std::vector<Eigen::Affine3d> default_extrinsics;
402
403 for (uint i = 0; i < node_list.size(); i++) {
404 std::string node = node_list[i];
405 const aos::Node *pi =
406 aos::configuration::GetNode(reader.configuration(), node.c_str());
407
408 detection_event_loops.emplace_back(
409 reader.event_loop_factory()->MakeEventLoop(
410 (node + "_detection").c_str(), pi));
411
412 frc971::constants::ConstantsFetcher<y2023::Constants> constants_fetcher(
413 detection_event_loops.back().get());
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700414
415 const calibration::CameraCalibration *calibration =
416 FindCameraCalibration(constants_fetcher.constants(), node);
417
418 frc971::vision::TargetType target_type =
419 frc971::vision::TargetTypeFromString(FLAGS_target_type);
420 frc971::vision::CharucoExtractor *charuco_ext =
421 new frc971::vision::CharucoExtractor(calibration, target_type);
422 charuco_extractors.emplace_back(charuco_ext);
423
424 cv::Mat extrinsics_cv = CameraExtrinsics(calibration).value();
425 Eigen::Matrix4d extrinsics_matrix;
426 cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
427 const auto ext_H_robot_pi = Eigen::Affine3d(extrinsics_matrix);
428 default_extrinsics.emplace_back(ext_H_robot_pi);
429
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700430 VLOG(1) << "Got extrinsics for " << node << " as\n"
431 << default_extrinsics.back().matrix();
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700432
433 frc971::vision::ImageCallback *image_callback =
434 new frc971::vision::ImageCallback(
435 detection_event_loops[i].get(), "/" + node_list[i] + "/camera",
436 [&reader, &charuco_extractors, &detection_event_loops, &node_list,
437 i](cv::Mat rgb_image, const aos::monotonic_clock::time_point eof) {
438 aos::distributed_clock::time_point pi_distributed_time =
439 reader.event_loop_factory()
440 ->GetNodeEventLoopFactory(
441 detection_event_loops[i].get()->node())
442 ->ToDistributedClock(eof);
443 ProcessImage(detection_event_loops[i].get(), rgb_image, eof,
444 pi_distributed_time, *charuco_extractors[i],
445 node_list[i]);
446 });
447
448 image_callbacks.emplace_back(image_callback);
449 }
450
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700451 reader.event_loop_factory()->Run();
452
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700453 // Do quick check to see what averaged two-board pose for each pi is
454 // individually
455 CHECK_GT(two_board_extrinsics_list.size(), 0u)
456 << "Must have at least one view of both boards";
457 int base_target_id = two_board_extrinsics_list[0].board_id;
458 VLOG(1) << "Base id for two_board_extrinsics_list is " << base_target_id;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700459 for (auto node : node_list) {
460 std::vector<TimestampedPiDetection> pose_list;
461 for (auto ext : two_board_extrinsics_list) {
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700462 CHECK_EQ(base_target_id, ext.board_id)
463 << " All boards should have same reference id";
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700464 if (ext.pi_name == node) {
465 pose_list.push_back(ext);
466 }
467 }
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700468 Eigen::Affine3d avg_pose_from_pi = ComputeAveragePose(pose_list);
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700469 VLOG(1) << "Estimate from " << node << " with " << pose_list.size()
470 << " observations is:\n"
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700471 << avg_pose_from_pi.matrix();
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700472 }
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700473 Eigen::Affine3d H_boardA_boardB_avg =
474 ComputeAveragePose(two_board_extrinsics_list);
475 // TODO: Should probably do some outlier rejection
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700476 LOG(INFO) << "Estimate of two board pose using all nodes with "
477 << two_board_extrinsics_list.size() << " observations is:\n"
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700478 << H_boardA_boardB_avg.matrix() << "\n";
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700479
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700480 // Next, compute the relative camera poses
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700481 LOG(INFO) << "Got " << detection_list.size() << " extrinsic observations";
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700482 std::vector<Eigen::Affine3d> H_camera1_camera2_list;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700483 std::vector<Eigen::Affine3d> updated_extrinsics;
484 // Use the first node's extrinsics as our base, and fix from there
485 updated_extrinsics.push_back(default_extrinsics[0]);
486 LOG(INFO) << "Default extrinsic for node " << node_list[0] << " is "
487 << default_extrinsics[0].matrix();
488 for (uint i = 0; i < node_list.size() - 1; i++) {
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700489 H_camera1_camera2_list.clear();
490 // Go through the list, and find successive pairs of cameras
491 for (auto [pose1, pose2] : detection_list) {
492 if ((pose1.pi_name == node_list[i]) &&
493 (pose2.pi_name == node_list[i + 1])) {
494 Eigen::Affine3d H_camera1_boardA = pose1.H_camera_target;
495 // If pose1 isn't referenced to base_target_id, correct that
496 if (pose1.board_id != base_target_id) {
497 // pose1.H_camera_target references boardB, so map back to boardA
498 H_camera1_boardA =
499 pose1.H_camera_target * H_boardA_boardB_avg.inverse();
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700500 }
501
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700502 // Now, get the camera2->boardA map (notice it's boardA, same as
503 // camera1, so we can compute the difference based both on boardA)
504 Eigen::Affine3d H_camera2_boardA = pose2.H_camera_target;
505 // If pose2 isn't referenced to boardA (base_target_id), correct that
506 if (pose2.board_id != base_target_id) {
507 // pose2.H_camera_target references boardB, so map back to boardA
508 H_camera2_boardA =
Jim Ostrowski1f7cdc62023-12-02 14:09:23 -0800509 pose2.H_camera_target * H_boardA_boardB_avg.inverse();
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700510 }
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700511
512 // Compute camera1->camera2 map
513 Eigen::Affine3d H_camera1_camera2 =
514 H_camera1_boardA * H_camera2_boardA.inverse();
515 H_camera1_camera2_list.push_back(H_camera1_camera2);
516 VLOG(1) << "Map from camera " << pose1.pi_name << " and tag "
517 << pose1.board_id << " with observation: \n"
518 << pose1.H_camera_target.matrix() << "\n to camera "
519 << pose2.pi_name << " and tag " << pose2.board_id
520 << " with observation: \n"
521 << pose2.H_camera_target.matrix() << "\ngot map as\n"
522 << H_camera1_camera2.matrix();
523
524 Eigen::Affine3d H_world_board;
525 H_world_board = Eigen::Translation3d::Identity() *
526 Eigen::AngleAxisd(M_PI / 2.0, Eigen::Vector3d::UnitX());
527 if (FLAGS_alt_view) {
528 H_world_board = Eigen::Translation3d(0.0, 0.0, 3.0);
529 }
530
531 VLOG(2) << "Camera1 " << pose1.pi_name << " in world frame is \n"
532 << (H_world_board * H_camera1_boardA.inverse()).matrix();
533 VLOG(2) << "Camera2 " << pose2.pi_name << " in world frame is \n"
534 << (H_world_board * H_camera2_boardA.inverse()).matrix();
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700535 }
536 }
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700537 // TODO<Jim>: If we don't get any matches, we could just use default
538 // extrinsics
539 CHECK(H_camera1_camera2_list.size() > 0)
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700540 << "Failed with zero poses for node " << node_list[i];
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700541 if (H_camera1_camera2_list.size() > 0) {
542 Eigen::Affine3d H_camera1_camera2_avg =
543 ComputeAveragePose(H_camera1_camera2_list);
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700544 LOG(INFO) << "From " << node_list[i] << " to " << node_list[i + 1]
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700545 << " found " << H_camera1_camera2_list.size()
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700546 << " observations, and the average pose is:\n"
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700547 << H_camera1_camera2_avg.matrix();
548 Eigen::Affine3d H_camera1_camera2_default =
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700549 default_extrinsics[i].inverse() * default_extrinsics[i + 1];
550 LOG(INFO) << "Compare this to that from default values:\n"
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700551 << H_camera1_camera2_default.matrix();
552 Eigen::Affine3d H_camera1_camera2_diff =
553 H_camera1_camera2_avg * H_camera1_camera2_default.inverse();
554 LOG(INFO)
555 << "Difference between averaged and default delta poses "
556 "has |T| = "
557 << H_camera1_camera2_diff.translation().norm() << "m and |R| = "
558 << Eigen::AngleAxisd(H_camera1_camera2_diff.rotation()).angle()
559 << " radians ("
560 << Eigen::AngleAxisd(H_camera1_camera2_diff.rotation()).angle() *
561 180.0 / M_PI
562 << " degrees)";
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700563 // Next extrinsic is just previous one * avg_delta_pose
564 Eigen::Affine3d next_extrinsic =
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700565 updated_extrinsics.back() * H_camera1_camera2_avg;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700566 updated_extrinsics.push_back(next_extrinsic);
567 LOG(INFO) << "Default Extrinsic for " << node_list[i + 1] << " is \n"
568 << default_extrinsics[i + 1].matrix();
569 LOG(INFO) << "--> Updated Extrinsic for " << node_list[i + 1] << " is \n"
570 << next_extrinsic.matrix();
571 }
572 }
573
574 // Cleanup
575 for (uint i = 0; i < image_callbacks.size(); i++) {
576 delete charuco_extractors[i];
577 delete image_callbacks[i];
578 }
579}
580} // namespace vision
581} // namespace y2023
582
583int main(int argc, char **argv) {
584 aos::InitGoogle(&argc, &argv);
585 y2023::vision::ExtrinsicsMain(argc, argv);
586}