Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 1 | #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" |
Jim Ostrowski | 3320898 | 2024-03-02 15:01:45 -0800 | [diff] [blame] | 14 | #include "frc971/vision/vision_util_lib.h" |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 15 | #include "frc971/vision/visualize_robot.h" |
| 16 | // clang-format off |
| 17 | // OpenCV eigen files must be included after Eigen includes |
| 18 | #include "opencv2/aruco.hpp" |
| 19 | #include "opencv2/calib3d.hpp" |
| 20 | #include "opencv2/core/eigen.hpp" |
| 21 | #include "opencv2/features2d.hpp" |
| 22 | #include "opencv2/highgui.hpp" |
| 23 | #include "opencv2/highgui/highgui.hpp" |
| 24 | #include "opencv2/imgproc.hpp" |
| 25 | // clang-format on |
| 26 | #include "frc971/constants/constants_sender_lib.h" |
| 27 | #include "frc971/vision/vision_util_lib.h" |
| 28 | #include "y2024/constants/simulated_constants_sender.h" |
| 29 | #include "y2024/vision/vision_util.h" |
| 30 | |
| 31 | DEFINE_bool(alt_view, false, |
| 32 | "If true, show visualization from field level, rather than above"); |
| 33 | DEFINE_string(config, "", |
| 34 | "If set, override the log's config file with this one."); |
Jim Ostrowski | ddebdcb | 2024-02-29 22:25:36 -0800 | [diff] [blame] | 35 | DEFINE_string(constants_path, "y2024/constants/constants.json", |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 36 | "Path to the constant file"); |
| 37 | DEFINE_double(max_pose_error, 5e-5, |
| 38 | "Throw out target poses with a higher pose error than this"); |
| 39 | DEFINE_double( |
| 40 | max_pose_error_ratio, 0.4, |
| 41 | "Throw out target poses with a higher pose error ratio than this"); |
| 42 | DEFINE_string(output_folder, "/tmp", |
| 43 | "Directory in which to store the updated calibration files"); |
| 44 | DEFINE_string(target_type, "charuco_diamond", |
| 45 | "Type of target being used [aruco, charuco, charuco_diamond]"); |
| 46 | DEFINE_int32(team_number, 0, |
| 47 | "Required: Use the calibration for a node with this team number"); |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 48 | DEFINE_uint64( |
| 49 | wait_key, 1, |
| 50 | "Time in ms to wait between images (0 to wait indefinitely until click)"); |
Maxwell Henderson | 9d7b186 | 2024-03-02 11:00:29 -0800 | [diff] [blame] | 51 | DEFINE_bool(robot, false, |
| 52 | "If true we're calibrating extrinsics for the robot, use the " |
| 53 | "correct node path for the robot."); |
| 54 | |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 55 | DECLARE_int32(min_target_id); |
| 56 | DECLARE_int32(max_target_id); |
| 57 | |
| 58 | // Calibrate extrinsic relationship between cameras using two targets |
| 59 | // seen jointly between cameras. Uses two types of information: 1) |
| 60 | // when a single camera sees two targets, we estimate the pose between |
| 61 | // targets, and 2) when two separate cameras each see a target, we can |
| 62 | // use the pose between targets to estimate the pose between cameras. |
| 63 | |
| 64 | // We then create the extrinsics for the robot by starting with the |
| 65 | // given extrinsic for camera 1 (between imu/robot and camera frames) |
| 66 | // and then map each subsequent camera based on the data collected and |
| 67 | // the extrinsic poses computed here. |
| 68 | |
Jim Ostrowski | ddebdcb | 2024-02-29 22:25:36 -0800 | [diff] [blame] | 69 | // TODO<Jim>: Not currently using estimate from first camera to last camera-- |
| 70 | // should do full estimation, and probably also include camera->imu extrinsics |
| 71 | // from all cameras, not just first camera |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 72 | |
Jim Ostrowski | ddebdcb | 2024-02-29 22:25:36 -0800 | [diff] [blame] | 73 | namespace y2024::vision { |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 74 | using frc971::vision::DataAdapter; |
| 75 | using frc971::vision::ImageCallback; |
| 76 | using frc971::vision::PoseUtils; |
| 77 | using frc971::vision::TargetMap; |
| 78 | using frc971::vision::TargetMapper; |
| 79 | using frc971::vision::VisualizeRobot; |
| 80 | namespace calibration = frc971::vision::calibration; |
| 81 | |
| 82 | static constexpr double kImagePeriodMs = |
Maxwell Henderson | 9d7b186 | 2024-03-02 11:00:29 -0800 | [diff] [blame] | 83 | 1.0 / 60.0 * 1000.0; // Image capture period in ms |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 84 | |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 85 | std::vector<CameraNode> node_list(y2024::vision::CreateNodeList()); |
| 86 | |
| 87 | std::map<std::string, int> ordering_map( |
| 88 | y2024::vision::CreateOrderingMap(node_list)); |
| 89 | |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 90 | // Change reference frame from camera to robot |
| 91 | Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target, |
| 92 | Eigen::Affine3d extrinsics) { |
| 93 | const Eigen::Affine3d H_robot_camera = extrinsics; |
| 94 | const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target; |
| 95 | return H_robot_target; |
| 96 | } |
| 97 | |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 98 | struct TimestampedCameraDetection { |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 99 | aos::distributed_clock::time_point time; |
| 100 | // Pose of target relative to robot |
| 101 | Eigen::Affine3d H_camera_target; |
| 102 | // name of pi |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 103 | std::string camera_name; |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 104 | int board_id; |
| 105 | }; |
| 106 | |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 107 | TimestampedCameraDetection last_observation; |
| 108 | std::vector<std::pair<TimestampedCameraDetection, TimestampedCameraDetection>> |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 109 | detection_list; |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 110 | std::vector<TimestampedCameraDetection> two_board_extrinsics_list; |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 111 | VisualizeRobot vis_robot_; |
| 112 | |
| 113 | // TODO<jim>: Implement variance calcs |
| 114 | Eigen::Affine3d ComputeAveragePose( |
| 115 | std::vector<Eigen::Vector3d> &translation_list, |
| 116 | std::vector<Eigen::Vector4d> &rotation_list, |
| 117 | Eigen::Vector3d *translation_variance = nullptr, |
| 118 | Eigen::Vector3d *rotation_variance = nullptr) { |
| 119 | Eigen::Vector3d avg_translation = |
| 120 | std::accumulate(translation_list.begin(), translation_list.end(), |
| 121 | Eigen::Vector3d{0, 0, 0}) / |
| 122 | translation_list.size(); |
| 123 | |
| 124 | // TODO<Jim>: Use QuaternionMean from quaternion_utils.cc (but this |
| 125 | // requires a fixed number of quaternions to be averaged |
| 126 | Eigen::Vector4d avg_rotation = |
| 127 | std::accumulate(rotation_list.begin(), rotation_list.end(), |
| 128 | Eigen::Vector4d{0, 0, 0, 0}) / |
| 129 | rotation_list.size(); |
| 130 | // Normalize, so it's a valid quaternion |
| 131 | avg_rotation = avg_rotation / avg_rotation.norm(); |
| 132 | Eigen::Quaterniond avg_rotation_q{avg_rotation[0], avg_rotation[1], |
| 133 | avg_rotation[2], avg_rotation[3]}; |
| 134 | Eigen::Translation3d translation(avg_translation); |
| 135 | Eigen::Affine3d return_pose = translation * avg_rotation_q; |
| 136 | if (translation_variance != nullptr) { |
| 137 | *translation_variance = Eigen::Vector3d(); |
| 138 | } |
| 139 | if (rotation_variance != nullptr) { |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 140 | *rotation_variance = Eigen::Vector3d(); |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 141 | } |
| 142 | |
| 143 | return return_pose; |
| 144 | } |
| 145 | |
| 146 | Eigen::Affine3d ComputeAveragePose( |
| 147 | std::vector<Eigen::Affine3d> &pose_list, |
| 148 | Eigen::Vector3d *translation_variance = nullptr, |
| 149 | Eigen::Vector3d *rotation_variance = nullptr) { |
| 150 | std::vector<Eigen::Vector3d> translation_list; |
| 151 | std::vector<Eigen::Vector4d> rotation_list; |
| 152 | |
| 153 | for (Eigen::Affine3d pose : pose_list) { |
| 154 | translation_list.push_back(pose.translation()); |
| 155 | Eigen::Quaterniond quat(pose.rotation().matrix()); |
| 156 | rotation_list.push_back( |
| 157 | Eigen::Vector4d(quat.w(), quat.x(), quat.y(), quat.z())); |
| 158 | } |
| 159 | |
| 160 | return ComputeAveragePose(translation_list, rotation_list, |
| 161 | translation_variance, rotation_variance); |
| 162 | } |
| 163 | |
| 164 | Eigen::Affine3d ComputeAveragePose( |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 165 | std::vector<TimestampedCameraDetection> &pose_list, |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 166 | Eigen::Vector3d *translation_variance = nullptr, |
| 167 | Eigen::Vector3d *rotation_variance = nullptr) { |
| 168 | std::vector<Eigen::Vector3d> translation_list; |
| 169 | std::vector<Eigen::Vector4d> rotation_list; |
| 170 | |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 171 | for (TimestampedCameraDetection pose : pose_list) { |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 172 | translation_list.push_back(pose.H_camera_target.translation()); |
| 173 | Eigen::Quaterniond quat(pose.H_camera_target.rotation().matrix()); |
| 174 | rotation_list.push_back( |
| 175 | Eigen::Vector4d(quat.w(), quat.x(), quat.y(), quat.z())); |
| 176 | } |
| 177 | return ComputeAveragePose(translation_list, rotation_list, |
| 178 | translation_variance, rotation_variance); |
| 179 | } |
| 180 | |
| 181 | void HandlePoses(cv::Mat rgb_image, |
| 182 | std::vector<TargetMapper::TargetPose> target_poses, |
| 183 | aos::distributed_clock::time_point distributed_eof, |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 184 | std::string camera_name) { |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 185 | // This is used to transform points for visualization |
| 186 | // Assumes targets are aligned with x->right, y->up, z->out of board |
| 187 | Eigen::Affine3d H_world_board; |
| 188 | H_world_board = Eigen::Translation3d::Identity() * |
| 189 | Eigen::AngleAxisd(M_PI / 2.0, Eigen::Vector3d::UnitX()); |
| 190 | if (FLAGS_alt_view) { |
| 191 | // Don't rotate -- this is like viewing from the side |
| 192 | H_world_board = Eigen::Translation3d(0.0, 0.0, 3.0); |
| 193 | } |
| 194 | |
| 195 | bool draw_vis = false; |
| 196 | CHECK_LE(target_poses.size(), 2u) |
| 197 | << "Can't handle more than two tags in field of view"; |
| 198 | if (target_poses.size() == 2) { |
| 199 | draw_vis = true; |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 200 | VLOG(1) << "Saw two boards in same view from " << camera_name; |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 201 | int from_index = 0; |
| 202 | int to_index = 1; |
| 203 | // Handle when we see two boards at once |
| 204 | // We'll store them referenced to the lower id board |
| 205 | if (target_poses[from_index].id > target_poses[to_index].id) { |
| 206 | std::swap<int>(from_index, to_index); |
| 207 | } |
| 208 | |
| 209 | // Create "from" (A) and "to" (B) transforms |
| 210 | Eigen::Affine3d H_camera_boardA = |
| 211 | PoseUtils::Pose3dToAffine3d(target_poses[from_index].pose); |
| 212 | Eigen::Affine3d H_camera_boardB = |
| 213 | PoseUtils::Pose3dToAffine3d(target_poses[to_index].pose); |
| 214 | |
| 215 | Eigen::Affine3d H_boardA_boardB = |
| 216 | H_camera_boardA.inverse() * H_camera_boardB; |
| 217 | |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 218 | TimestampedCameraDetection boardA_boardB{ |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 219 | .time = distributed_eof, |
| 220 | .H_camera_target = H_boardA_boardB, |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 221 | .camera_name = camera_name, |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 222 | .board_id = target_poses[from_index].id}; |
| 223 | |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 224 | VLOG(1) << "Two boards seen by " << camera_name << ". Map from board " |
| 225 | << target_poses[from_index].id << " to " |
| 226 | << target_poses[to_index].id << " is\n" |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 227 | << H_boardA_boardB.matrix(); |
| 228 | // Store this observation of the transform between two boards |
| 229 | two_board_extrinsics_list.push_back(boardA_boardB); |
| 230 | |
| 231 | if (FLAGS_visualize) { |
| 232 | vis_robot_.DrawFrameAxes( |
| 233 | H_world_board, |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 234 | std::string("Board ") + std::to_string(target_poses[from_index].id), |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 235 | cv::Scalar(0, 255, 0)); |
| 236 | vis_robot_.DrawFrameAxes( |
| 237 | H_world_board * boardA_boardB.H_camera_target, |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 238 | std::string("Board ") + std::to_string(target_poses[to_index].id), |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 239 | cv::Scalar(255, 0, 0)); |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 240 | vis_robot_.DrawRobotOutline(H_world_board * H_camera_boardA.inverse(), |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 241 | camera_name, kOrinColors.at(camera_name)); |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 242 | } |
| 243 | } else if (target_poses.size() == 1) { |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 244 | VLOG(1) << camera_name << " saw single board " << target_poses[0].id; |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 245 | Eigen::Affine3d H_camera2_board2 = |
| 246 | PoseUtils::Pose3dToAffine3d(target_poses[0].pose); |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 247 | TimestampedCameraDetection new_observation{ |
| 248 | .time = distributed_eof, |
| 249 | .H_camera_target = H_camera2_board2, |
| 250 | .camera_name = camera_name, |
| 251 | .board_id = target_poses[0].id}; |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 252 | |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 253 | // Only take two observations if they're within half an image cycle of |
| 254 | // each other (i.e., as close in time as possible) And, if two consecutive |
| 255 | // observations are from the same camera, just replace with the newest one |
| 256 | if ((new_observation.camera_name != last_observation.camera_name) && |
| 257 | (std::abs((distributed_eof - last_observation.time).count()) < |
| 258 | kImagePeriodMs / 2.0 * 1000000.0)) { |
| 259 | // Sort by camera numbering, since this is how we will handle them |
| 260 | std::pair<TimestampedCameraDetection, TimestampedCameraDetection> |
| 261 | new_pair; |
| 262 | if (ordering_map.at(last_observation.camera_name) < |
| 263 | ordering_map.at(new_observation.camera_name)) { |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 264 | new_pair = std::pair(last_observation, new_observation); |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 265 | } else if (ordering_map.at(last_observation.camera_name) > |
| 266 | ordering_map.at(new_observation.camera_name)) { |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 267 | new_pair = std::pair(new_observation, last_observation); |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 268 | } |
Maxwell Henderson | 9d7b186 | 2024-03-02 11:00:29 -0800 | [diff] [blame] | 269 | |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 270 | detection_list.push_back(new_pair); |
| 271 | |
| 272 | // This bit is just for visualization and checking purposes-- use the |
| 273 | // last two-board observation to figure out the current estimate |
| 274 | // between the two cameras |
| 275 | if (FLAGS_visualize && two_board_extrinsics_list.size() > 0) { |
| 276 | draw_vis = true; |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 277 | TimestampedCameraDetection &last_two_board_ext = |
| 278 | two_board_extrinsics_list.back(); |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 279 | Eigen::Affine3d &H_boardA_boardB = last_two_board_ext.H_camera_target; |
| 280 | int boardA_boardB_id = last_two_board_ext.board_id; |
| 281 | |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 282 | TimestampedCameraDetection camera1_boardA = new_pair.first; |
| 283 | TimestampedCameraDetection camera2_boardB = new_pair.second; |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 284 | // If camera1_boardA doesn't point to the first target, then swap |
| 285 | // these two |
| 286 | if (camera1_boardA.board_id != boardA_boardB_id) { |
| 287 | camera1_boardA = new_pair.second; |
| 288 | camera2_boardB = new_pair.first; |
| 289 | } |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 290 | VLOG(1) << "Camera " << camera1_boardA.camera_name << " seeing board " |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 291 | << camera1_boardA.board_id << " and camera " |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 292 | << camera2_boardB.camera_name << " seeing board " |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 293 | << camera2_boardB.board_id; |
| 294 | |
| 295 | vis_robot_.DrawRobotOutline( |
| 296 | H_world_board * camera1_boardA.H_camera_target.inverse(), |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 297 | camera1_boardA.camera_name, |
| 298 | kOrinColors.at(camera1_boardA.camera_name)); |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 299 | vis_robot_.DrawRobotOutline( |
| 300 | H_world_board * H_boardA_boardB * |
| 301 | camera2_boardB.H_camera_target.inverse(), |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 302 | camera2_boardB.camera_name, |
| 303 | kOrinColors.at(camera2_boardB.camera_name)); |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 304 | vis_robot_.DrawFrameAxes( |
| 305 | H_world_board, |
| 306 | std::string("Board ") + std::to_string(last_two_board_ext.board_id), |
| 307 | cv::Scalar(0, 255, 0)); |
| 308 | vis_robot_.DrawFrameAxes(H_world_board * H_boardA_boardB, "Board B", |
| 309 | cv::Scalar(255, 0, 0)); |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 310 | VLOG(1) << "Storing observation between " << new_pair.first.camera_name |
| 311 | << ", target " << new_pair.first.board_id << " and " |
| 312 | << new_pair.second.camera_name << ", target " |
| 313 | << new_pair.second.board_id; |
| 314 | } else if (two_board_extrinsics_list.size() == 0) { |
| 315 | VLOG(1) << "Not drawing observation yet, since we don't have a two " |
| 316 | "board estimate"; |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 317 | } |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 318 | } else { |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 319 | if (new_observation.camera_name == last_observation.camera_name) { |
| 320 | VLOG(2) << "Updating repeated observation for " << camera_name; |
| 321 | } else { |
| 322 | VLOG(1) << "Storing observation for " << camera_name << " at time " |
| 323 | << distributed_eof << " since last observation was " |
| 324 | << std::abs((distributed_eof - last_observation.time).count()) / |
| 325 | 1000000.0 |
| 326 | << "ms ago"; |
| 327 | } |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 328 | last_observation = new_observation; |
| 329 | } |
| 330 | } |
| 331 | |
| 332 | if (FLAGS_visualize) { |
| 333 | if (!rgb_image.empty()) { |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 334 | std::string image_name = camera_name + " Image"; |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 335 | cv::Mat rgb_small; |
| 336 | cv::resize(rgb_image, rgb_small, cv::Size(), 0.5, 0.5); |
| 337 | cv::imshow(image_name, rgb_small); |
| 338 | cv::waitKey(FLAGS_wait_key); |
| 339 | } |
| 340 | |
| 341 | if (draw_vis) { |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 342 | cv::imshow("Overhead View", vis_robot_.image_); |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 343 | cv::waitKey(FLAGS_wait_key); |
| 344 | vis_robot_.ClearImage(); |
| 345 | } |
| 346 | } |
| 347 | } |
| 348 | |
| 349 | void HandleTargetMap(const TargetMap &map, |
| 350 | aos::distributed_clock::time_point distributed_eof, |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 351 | std::string camera_name) { |
| 352 | VLOG(1) << "Got april tag map call from camera " << camera_name; |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 353 | // Create empty RGB image in this case |
| 354 | cv::Mat rgb_image; |
| 355 | std::vector<TargetMapper::TargetPose> target_poses; |
| 356 | |
| 357 | for (const auto *target_pose_fbs : *map.target_poses()) { |
| 358 | // Skip detections with invalid ids |
| 359 | if (static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) < |
| 360 | FLAGS_min_target_id || |
| 361 | static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) > |
| 362 | FLAGS_max_target_id) { |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 363 | VLOG(1) << "Skipping tag from " << camera_name << " with invalid id of " |
| 364 | << target_pose_fbs->id(); |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 365 | continue; |
| 366 | } |
| 367 | |
| 368 | // Skip detections with high pose errors |
| 369 | if (target_pose_fbs->pose_error() > FLAGS_max_pose_error) { |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 370 | LOG(INFO) << "Skipping tag from " << camera_name << " with id " |
| 371 | << target_pose_fbs->id() << " due to pose error of " |
| 372 | << target_pose_fbs->pose_error(); |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 373 | continue; |
| 374 | } |
| 375 | // Skip detections with high pose error ratios |
| 376 | if (target_pose_fbs->pose_error_ratio() > FLAGS_max_pose_error_ratio) { |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 377 | LOG(INFO) << "Skipping tag from " << camera_name << " with id " |
| 378 | << target_pose_fbs->id() << " due to pose error ratio of " |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 379 | << target_pose_fbs->pose_error_ratio(); |
| 380 | continue; |
| 381 | } |
| 382 | |
| 383 | const TargetMapper::TargetPose target_pose = |
| 384 | PoseUtils::TargetPoseFromFbs(*target_pose_fbs); |
| 385 | |
| 386 | target_poses.emplace_back(target_pose); |
| 387 | |
| 388 | Eigen::Affine3d H_camera_target = |
| 389 | PoseUtils::Pose3dToAffine3d(target_pose.pose); |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 390 | VLOG(1) << camera_name << " saw target " << target_pose.id |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 391 | << " from TargetMap at timestamp " << distributed_eof |
| 392 | << " with pose = " << H_camera_target.matrix(); |
| 393 | } |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 394 | HandlePoses(rgb_image, target_poses, distributed_eof, camera_name); |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 395 | } |
| 396 | |
| 397 | void HandleImage(aos::EventLoop *event_loop, cv::Mat rgb_image, |
| 398 | const aos::monotonic_clock::time_point eof, |
| 399 | aos::distributed_clock::time_point distributed_eof, |
| 400 | frc971::vision::CharucoExtractor &charuco_extractor, |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 401 | std::string camera_name) { |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 402 | std::vector<cv::Vec4i> charuco_ids; |
| 403 | std::vector<std::vector<cv::Point2f>> charuco_corners; |
| 404 | bool valid = false; |
| 405 | std::vector<Eigen::Vector3d> rvecs_eigen; |
| 406 | std::vector<Eigen::Vector3d> tvecs_eigen; |
| 407 | // Why eof vs. distributed_eof? |
| 408 | charuco_extractor.ProcessImage(rgb_image, eof, event_loop->monotonic_now(), |
| 409 | charuco_ids, charuco_corners, valid, |
| 410 | rvecs_eigen, tvecs_eigen); |
| 411 | if (rvecs_eigen.size() > 0 && !valid) { |
| 412 | LOG(WARNING) << "Charuco extractor returned not valid"; |
| 413 | return; |
| 414 | } |
| 415 | |
| 416 | std::vector<TargetMapper::TargetPose> target_poses; |
| 417 | for (size_t i = 0; i < tvecs_eigen.size(); i++) { |
| 418 | Eigen::Quaterniond rotation( |
| 419 | frc971::controls::ToQuaternionFromRotationVector(rvecs_eigen[i])); |
| 420 | ceres::examples::Pose3d pose(Eigen::Vector3d(tvecs_eigen[i]), rotation); |
| 421 | TargetMapper::TargetPose target_pose{charuco_ids[i][0], pose}; |
| 422 | target_poses.emplace_back(target_pose); |
| 423 | |
| 424 | Eigen::Affine3d H_camera_target = PoseUtils::Pose3dToAffine3d(pose); |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 425 | VLOG(2) << camera_name << " saw target " << target_pose.id |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 426 | << " from image at timestamp " << distributed_eof |
| 427 | << " with pose = " << H_camera_target.matrix(); |
| 428 | } |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 429 | HandlePoses(rgb_image, target_poses, distributed_eof, camera_name); |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 430 | } |
| 431 | |
| 432 | void ExtrinsicsMain(int argc, char *argv[]) { |
| 433 | vis_robot_ = VisualizeRobot(cv::Size(1000, 1000)); |
| 434 | vis_robot_.ClearImage(); |
| 435 | const double kFocalLength = 1000.0; |
| 436 | const int kImageWidth = 1000; |
| 437 | vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength); |
| 438 | |
| 439 | std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config = |
| 440 | (FLAGS_config.empty() |
| 441 | ? std::nullopt |
| 442 | : std::make_optional(aos::configuration::ReadConfig(FLAGS_config))); |
| 443 | |
| 444 | // open logfiles |
| 445 | aos::logger::LogReader reader( |
| 446 | aos::logger::SortParts(aos::logger::FindLogs(argc, argv)), |
| 447 | config.has_value() ? &config->message() : nullptr); |
| 448 | |
Jim Ostrowski | ddebdcb | 2024-02-29 22:25:36 -0800 | [diff] [blame] | 449 | reader.RemapLoggedChannel("/imu/constants", "y2024.Constants"); |
| 450 | reader.RemapLoggedChannel("/orin1/constants", "y2024.Constants"); |
Maxwell Henderson | 9d7b186 | 2024-03-02 11:00:29 -0800 | [diff] [blame] | 451 | if (FLAGS_robot) { |
| 452 | reader.RemapLoggedChannel("/roborio/constants", "y2024.Constants"); |
| 453 | } |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 454 | reader.Register(); |
| 455 | |
| 456 | y2024::SendSimulationConstants(reader.event_loop_factory(), FLAGS_team_number, |
| 457 | FLAGS_constants_path); |
| 458 | |
| 459 | VLOG(1) << "Using target type " << FLAGS_target_type; |
Maxwell Henderson | 9d7b186 | 2024-03-02 11:00:29 -0800 | [diff] [blame] | 460 | |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 461 | std::vector<const calibration::CameraCalibration *> calibration_list; |
| 462 | |
| 463 | std::vector<std::unique_ptr<aos::EventLoop>> detection_event_loops; |
| 464 | std::vector<frc971::vision::CharucoExtractor *> charuco_extractors; |
| 465 | std::vector<frc971::vision::ImageCallback *> image_callbacks; |
| 466 | std::vector<Eigen::Affine3d> default_extrinsics; |
| 467 | |
Maxwell Henderson | 9d7b186 | 2024-03-02 11:00:29 -0800 | [diff] [blame] | 468 | for (const CameraNode &camera_node : node_list) { |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 469 | const aos::Node *node = aos::configuration::GetNode( |
Maxwell Henderson | 9d7b186 | 2024-03-02 11:00:29 -0800 | [diff] [blame] | 470 | reader.configuration(), camera_node.node_name.c_str()); |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 471 | |
Maxwell Henderson | 9d7b186 | 2024-03-02 11:00:29 -0800 | [diff] [blame] | 472 | detection_event_loops.emplace_back( |
| 473 | reader.event_loop_factory()->MakeEventLoop( |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 474 | (camera_node.camera_name() + "_detection").c_str(), node)); |
| 475 | |
Maxwell Henderson | 9beb569 | 2024-03-17 18:36:11 -0700 | [diff] [blame] | 476 | aos::EventLoop *const event_loop = detection_event_loops.back().get(); |
Maxwell Henderson | 9d7b186 | 2024-03-02 11:00:29 -0800 | [diff] [blame] | 477 | frc971::constants::ConstantsFetcher<y2024::Constants> constants_fetcher( |
Maxwell Henderson | 9beb569 | 2024-03-17 18:36:11 -0700 | [diff] [blame] | 478 | event_loop); |
Maxwell Henderson | 9d7b186 | 2024-03-02 11:00:29 -0800 | [diff] [blame] | 479 | // Get the calibration for this orin/camera pair |
| 480 | const calibration::CameraCalibration *calibration = |
| 481 | y2024::vision::FindCameraCalibration(constants_fetcher.constants(), |
| 482 | camera_node.node_name, |
| 483 | camera_node.camera_number); |
| 484 | calibration_list.push_back(calibration); |
Maxwell Henderson | 69ec45e | 2024-03-01 22:52:21 -0800 | [diff] [blame] | 485 | |
Maxwell Henderson | 9d7b186 | 2024-03-02 11:00:29 -0800 | [diff] [blame] | 486 | // Extract the extrinsics from the calibration, and save as "defaults" |
| 487 | cv::Mat extrinsics_cv = |
| 488 | frc971::vision::CameraExtrinsics(calibration).value(); |
| 489 | Eigen::Matrix4d extrinsics_matrix; |
| 490 | cv::cv2eigen(extrinsics_cv, extrinsics_matrix); |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 491 | const auto ext_H_robot_camera = Eigen::Affine3d(extrinsics_matrix); |
| 492 | default_extrinsics.emplace_back(ext_H_robot_camera); |
Maxwell Henderson | 69ec45e | 2024-03-01 22:52:21 -0800 | [diff] [blame] | 493 | |
Maxwell Henderson | 9d7b186 | 2024-03-02 11:00:29 -0800 | [diff] [blame] | 494 | VLOG(1) << "Got extrinsics for " << camera_node.camera_name() << " as\n" |
| 495 | << default_extrinsics.back().matrix(); |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 496 | |
Maxwell Henderson | 9beb569 | 2024-03-17 18:36:11 -0700 | [diff] [blame] | 497 | event_loop->MakeWatcher( |
Maxwell Henderson | 9d7b186 | 2024-03-02 11:00:29 -0800 | [diff] [blame] | 498 | camera_node.camera_name(), |
Maxwell Henderson | 9beb569 | 2024-03-17 18:36:11 -0700 | [diff] [blame] | 499 | [&reader, event_loop, camera_node](const TargetMap &map) { |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 500 | aos::distributed_clock::time_point camera_distributed_time = |
Maxwell Henderson | 9d7b186 | 2024-03-02 11:00:29 -0800 | [diff] [blame] | 501 | reader.event_loop_factory() |
Maxwell Henderson | 9beb569 | 2024-03-17 18:36:11 -0700 | [diff] [blame] | 502 | ->GetNodeEventLoopFactory(event_loop->node()) |
Maxwell Henderson | 9d7b186 | 2024-03-02 11:00:29 -0800 | [diff] [blame] | 503 | ->ToDistributedClock(aos::monotonic_clock::time_point( |
| 504 | aos::monotonic_clock::duration( |
| 505 | map.monotonic_timestamp_ns()))); |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 506 | |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 507 | HandleTargetMap(map, camera_distributed_time, |
| 508 | camera_node.camera_name()); |
Maxwell Henderson | 9d7b186 | 2024-03-02 11:00:29 -0800 | [diff] [blame] | 509 | }); |
Jim Ostrowski | 3320898 | 2024-03-02 15:01:45 -0800 | [diff] [blame] | 510 | VLOG(1) << "Created watcher for using the detection event loop for " |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 511 | << camera_node.camera_name(); |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 512 | } |
| 513 | |
| 514 | reader.event_loop_factory()->Run(); |
| 515 | |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 516 | // Do quick check to see what averaged two-board pose for |
| 517 | // each camera is individually |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 518 | CHECK_GT(two_board_extrinsics_list.size(), 0u) |
| 519 | << "Must have at least one view of both boards"; |
| 520 | int base_target_id = two_board_extrinsics_list[0].board_id; |
| 521 | VLOG(1) << "Base id for two_board_extrinsics_list is " << base_target_id; |
Maxwell Henderson | 9d7b186 | 2024-03-02 11:00:29 -0800 | [diff] [blame] | 522 | |
| 523 | for (auto camera_node : node_list) { |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 524 | std::vector<TimestampedCameraDetection> pose_list; |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 525 | for (auto ext : two_board_extrinsics_list) { |
| 526 | CHECK_EQ(base_target_id, ext.board_id) |
| 527 | << " All boards should have same reference id"; |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 528 | if (ext.camera_name == camera_node.camera_name()) { |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 529 | pose_list.push_back(ext); |
| 530 | } |
| 531 | } |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 532 | Eigen::Affine3d avg_pose_from_camera = ComputeAveragePose(pose_list); |
Maxwell Henderson | 9d7b186 | 2024-03-02 11:00:29 -0800 | [diff] [blame] | 533 | VLOG(1) << "Estimate from " << camera_node.camera_name() << " with " |
| 534 | << pose_list.size() << " observations is:\n" |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 535 | << avg_pose_from_camera.matrix(); |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 536 | } |
| 537 | Eigen::Affine3d H_boardA_boardB_avg = |
| 538 | ComputeAveragePose(two_board_extrinsics_list); |
| 539 | // TODO: Should probably do some outlier rejection |
Maxwell Henderson | 9d7b186 | 2024-03-02 11:00:29 -0800 | [diff] [blame] | 540 | VLOG(1) << "Estimate of two board pose using all nodes with " |
| 541 | << two_board_extrinsics_list.size() << " observations is:\n" |
| 542 | << H_boardA_boardB_avg.matrix() << "\n"; |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 543 | |
| 544 | // Next, compute the relative camera poses |
| 545 | LOG(INFO) << "Got " << detection_list.size() << " extrinsic observations"; |
| 546 | std::vector<Eigen::Affine3d> H_camera1_camera2_list; |
| 547 | std::vector<Eigen::Affine3d> updated_extrinsics; |
| 548 | // Use the first node's extrinsics as our base, and fix from there |
| 549 | updated_extrinsics.push_back(default_extrinsics[0]); |
Maxwell Henderson | 9d7b186 | 2024-03-02 11:00:29 -0800 | [diff] [blame] | 550 | LOG(INFO) << "Default extrinsic for camera " << node_list.at(0).camera_name() |
| 551 | << " is " << default_extrinsics[0].matrix(); |
| 552 | for (uint i = 0; i < node_list.size() - 1; i++) { |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 553 | H_camera1_camera2_list.clear(); |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 554 | // Go through the list, and find successive pairs of |
| 555 | // cameras We'll be calculating and writing the second |
| 556 | // of the pair (the i+1'th camera) |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 557 | for (auto [pose1, pose2] : detection_list) { |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 558 | if ((pose1.camera_name == node_list.at(i).camera_name()) && |
| 559 | (pose2.camera_name == node_list.at(i + 1).camera_name())) { |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 560 | Eigen::Affine3d H_camera1_boardA = pose1.H_camera_target; |
| 561 | // If pose1 isn't referenced to base_target_id, correct that |
| 562 | if (pose1.board_id != base_target_id) { |
| 563 | // pose1.H_camera_target references boardB, so map back to boardA |
| 564 | H_camera1_boardA = |
| 565 | pose1.H_camera_target * H_boardA_boardB_avg.inverse(); |
| 566 | } |
| 567 | |
| 568 | // Now, get the camera2->boardA map (notice it's boardA, same as |
Jim Ostrowski | 3320898 | 2024-03-02 15:01:45 -0800 | [diff] [blame] | 569 | // camera1, so we can compute the difference between the cameras with |
| 570 | // both referenced to boardA) |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 571 | Eigen::Affine3d H_camera2_boardA = pose2.H_camera_target; |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 572 | // If pose2 isn't referenced to boardA (base_target_id), correct that |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 573 | if (pose2.board_id != base_target_id) { |
| 574 | // pose2.H_camera_target references boardB, so map back to boardA |
| 575 | H_camera2_boardA = |
| 576 | pose2.H_camera_target * H_boardA_boardB_avg.inverse(); |
| 577 | } |
| 578 | |
| 579 | // Compute camera1->camera2 map |
| 580 | Eigen::Affine3d H_camera1_camera2 = |
| 581 | H_camera1_boardA * H_camera2_boardA.inverse(); |
| 582 | H_camera1_camera2_list.push_back(H_camera1_camera2); |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 583 | VLOG(1) << "Map from camera " << pose1.camera_name << " and tag " |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 584 | << pose1.board_id << " with observation: \n" |
| 585 | << pose1.H_camera_target.matrix() << "\n to camera " |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 586 | << pose2.camera_name << " and tag " << pose2.board_id |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 587 | << " with observation: \n" |
| 588 | << pose2.H_camera_target.matrix() << "\ngot map as\n" |
| 589 | << H_camera1_camera2.matrix(); |
| 590 | |
| 591 | Eigen::Affine3d H_world_board; |
| 592 | H_world_board = Eigen::Translation3d::Identity() * |
| 593 | Eigen::AngleAxisd(M_PI / 2.0, Eigen::Vector3d::UnitX()); |
| 594 | if (FLAGS_alt_view) { |
| 595 | H_world_board = Eigen::Translation3d(0.0, 0.0, 3.0); |
| 596 | } |
| 597 | |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 598 | VLOG(2) << "Camera1 " << pose1.camera_name << " in world frame is \n" |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 599 | << (H_world_board * H_camera1_boardA.inverse()).matrix(); |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 600 | VLOG(2) << "Camera2 " << pose2.camera_name << " in world frame is \n" |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 601 | << (H_world_board * H_camera2_boardA.inverse()).matrix(); |
| 602 | } |
| 603 | } |
| 604 | // TODO<Jim>: If we don't get any matches, we could just use default |
| 605 | // extrinsics |
| 606 | CHECK(H_camera1_camera2_list.size() > 0) |
Maxwell Henderson | 9d7b186 | 2024-03-02 11:00:29 -0800 | [diff] [blame] | 607 | << "Failed with zero poses for node " << node_list.at(i).camera_name() |
| 608 | << " and " << node_list.at(i + 1).camera_name(); |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 609 | if (H_camera1_camera2_list.size() > 0) { |
| 610 | Eigen::Affine3d H_camera1_camera2_avg = |
| 611 | ComputeAveragePose(H_camera1_camera2_list); |
Maxwell Henderson | 9d7b186 | 2024-03-02 11:00:29 -0800 | [diff] [blame] | 612 | LOG(INFO) << "From " << node_list.at(i).camera_name() << " to " |
| 613 | << node_list.at(i + 1).camera_name() << " found " |
| 614 | << H_camera1_camera2_list.size() |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 615 | << " observations, and the average pose is:\n" |
| 616 | << H_camera1_camera2_avg.matrix(); |
| 617 | Eigen::Affine3d H_camera1_camera2_default = |
| 618 | default_extrinsics[i].inverse() * default_extrinsics[i + 1]; |
| 619 | LOG(INFO) << "Compare this to that from default values:\n" |
| 620 | << H_camera1_camera2_default.matrix(); |
| 621 | Eigen::Affine3d H_camera1_camera2_diff = |
| 622 | H_camera1_camera2_avg * H_camera1_camera2_default.inverse(); |
| 623 | LOG(INFO) |
| 624 | << "Difference between averaged and default delta poses " |
| 625 | "has |T| = " |
| 626 | << H_camera1_camera2_diff.translation().norm() << "m and |R| = " |
| 627 | << Eigen::AngleAxisd(H_camera1_camera2_diff.rotation()).angle() |
| 628 | << " radians (" |
| 629 | << Eigen::AngleAxisd(H_camera1_camera2_diff.rotation()).angle() * |
| 630 | 180.0 / M_PI |
| 631 | << " degrees)"; |
| 632 | // Next extrinsic is just previous one * avg_delta_pose |
| 633 | Eigen::Affine3d next_extrinsic = |
| 634 | updated_extrinsics.back() * H_camera1_camera2_avg; |
| 635 | updated_extrinsics.push_back(next_extrinsic); |
Maxwell Henderson | 9d7b186 | 2024-03-02 11:00:29 -0800 | [diff] [blame] | 636 | LOG(INFO) << "Default Extrinsic for " << node_list.at(i + 1).camera_name() |
Jim Ostrowski | ddebdcb | 2024-02-29 22:25:36 -0800 | [diff] [blame] | 637 | << " is \n" |
Maxwell Henderson | 9d7b186 | 2024-03-02 11:00:29 -0800 | [diff] [blame] | 638 | << default_extrinsics[i + 1].matrix(); |
| 639 | LOG(INFO) << "--> Updated Extrinsic for " |
| 640 | << node_list.at(i + 1).camera_name() << " is \n" |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 641 | << next_extrinsic.matrix(); |
| 642 | |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 643 | // Write out this extrinsic to a file |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 644 | flatbuffers::FlatBufferBuilder fbb; |
| 645 | flatbuffers::Offset<flatbuffers::Vector<float>> data_offset = |
| 646 | fbb.CreateVector( |
| 647 | frc971::vision::MatrixToVector(next_extrinsic.matrix())); |
| 648 | calibration::TransformationMatrix::Builder matrix_builder(fbb); |
| 649 | matrix_builder.add_data(data_offset); |
| 650 | flatbuffers::Offset<calibration::TransformationMatrix> |
| 651 | extrinsic_calibration_offset = matrix_builder.Finish(); |
| 652 | |
| 653 | calibration::CameraCalibration::Builder calibration_builder(fbb); |
| 654 | calibration_builder.add_fixed_extrinsics(extrinsic_calibration_offset); |
| 655 | const aos::realtime_clock::time_point realtime_now = |
| 656 | aos::realtime_clock::now(); |
| 657 | calibration_builder.add_calibration_timestamp( |
| 658 | realtime_now.time_since_epoch().count()); |
| 659 | fbb.Finish(calibration_builder.Finish()); |
| 660 | aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> |
| 661 | solved_extrinsics = fbb.Release(); |
| 662 | |
| 663 | aos::FlatbufferDetachedBuffer< |
| 664 | frc971::vision::calibration::CameraCalibration> |
| 665 | cal_copy = aos::RecursiveCopyFlatBuffer(calibration_list[i + 1]); |
| 666 | cal_copy.mutable_message()->clear_fixed_extrinsics(); |
| 667 | cal_copy.mutable_message()->clear_calibration_timestamp(); |
| 668 | aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> |
| 669 | merged_calibration = aos::MergeFlatBuffers( |
| 670 | &cal_copy.message(), &solved_extrinsics.message()); |
| 671 | |
| 672 | std::stringstream time_ss; |
| 673 | time_ss << realtime_now; |
| 674 | |
Jim Ostrowski | 3320898 | 2024-03-02 15:01:45 -0800 | [diff] [blame] | 675 | CameraNode &camera_node = node_list[i + 1]; |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 676 | const std::string calibration_filename = |
Jim Ostrowski | 3320898 | 2024-03-02 15:01:45 -0800 | [diff] [blame] | 677 | frc971::vision::CalibrationFilename( |
| 678 | FLAGS_output_folder, camera_node.node_name, FLAGS_team_number, |
| 679 | camera_node.camera_number, cal_copy.message().camera_id()->data(), |
| 680 | time_ss.str()); |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 681 | LOG(INFO) << calibration_filename << " -> " |
| 682 | << aos::FlatbufferToJson(merged_calibration, |
| 683 | {.multi_line = true}); |
| 684 | |
| 685 | aos::util::WriteStringToFileOrDie( |
| 686 | calibration_filename, |
| 687 | aos::FlatbufferToJson(merged_calibration, {.multi_line = true})); |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 688 | |
| 689 | if (FLAGS_visualize) { |
| 690 | // Draw each of the updated extrinsic camera locations |
| 691 | vis_robot_.SetDefaultViewpoint(1000.0, 1500.0); |
| 692 | vis_robot_.DrawFrameAxes( |
| 693 | updated_extrinsics.back(), node_list.at(i + 1).camera_name(), |
| 694 | kOrinColors.at(node_list.at(i + 1).camera_name())); |
| 695 | } |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 696 | } |
| 697 | } |
Jim Ostrowski | 6772628 | 2024-03-24 14:39:33 -0700 | [diff] [blame] | 698 | if (FLAGS_visualize) { |
| 699 | // And don't forget to draw the base camera location |
| 700 | vis_robot_.DrawFrameAxes(updated_extrinsics[0], |
| 701 | node_list.at(0).camera_name(), |
| 702 | kOrinColors.at(node_list.at(0).camera_name())); |
| 703 | cv::imshow("Extrinsic visualization", vis_robot_.image_); |
| 704 | // Add a bit extra time, so that we don't go right through the extrinsics |
| 705 | cv::waitKey(3000); |
| 706 | cv::waitKey(0); |
| 707 | } |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 708 | |
| 709 | // Cleanup |
| 710 | for (uint i = 0; i < image_callbacks.size(); i++) { |
| 711 | delete charuco_extractors[i]; |
| 712 | delete image_callbacks[i]; |
| 713 | } |
| 714 | } |
Jim Ostrowski | ddebdcb | 2024-02-29 22:25:36 -0800 | [diff] [blame] | 715 | } // namespace y2024::vision |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 716 | |
| 717 | int main(int argc, char **argv) { |
| 718 | aos::InitGoogle(&argc, &argv); |
Jim Ostrowski | ddebdcb | 2024-02-29 22:25:36 -0800 | [diff] [blame] | 719 | y2024::vision::ExtrinsicsMain(argc, argv); |
Jim Ostrowski | 9bf206a | 2024-01-26 23:31:58 -0800 | [diff] [blame] | 720 | } |