Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 1 | #include "aos/events/logging/log_reader.h" |
| 2 | #include "aos/events/simulated_event_loop.h" |
| 3 | #include "aos/init.h" |
| 4 | #include "frc971/control_loops/pose.h" |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame^] | 5 | #include "frc971/vision/calibration_generated.h" |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 6 | #include "frc971/vision/charuco_lib.h" |
| 7 | #include "frc971/vision/target_mapper.h" |
| 8 | #include "opencv2/aruco.hpp" |
| 9 | #include "opencv2/calib3d.hpp" |
| 10 | #include "opencv2/core/eigen.hpp" |
| 11 | #include "opencv2/features2d.hpp" |
| 12 | #include "opencv2/highgui.hpp" |
| 13 | #include "opencv2/highgui/highgui.hpp" |
| 14 | #include "opencv2/imgproc.hpp" |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame^] | 15 | #include "y2023/vision/calibration_data.h" |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 16 | |
| 17 | DEFINE_string(json_path, "target_map.json", |
| 18 | "Specify path for json with initial pose guesses."); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 19 | DEFINE_int32(team_number, 7971, |
Milind Upadhyay | 915d600 | 2022-12-26 20:37:43 -0800 | [diff] [blame] | 20 | "Use the calibration for a node with this team number"); |
| 21 | |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 22 | DECLARE_string(image_channel); |
| 23 | |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame^] | 24 | namespace y2023 { |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 25 | namespace vision { |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame^] | 26 | using frc971::vision::CharucoExtractor; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 27 | using frc971::vision::DataAdapter; |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame^] | 28 | using frc971::vision::ImageCallback; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 29 | using frc971::vision::PoseUtils; |
| 30 | using frc971::vision::TargetMapper; |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame^] | 31 | namespace calibration = frc971::vision::calibration; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 32 | |
| 33 | // Change reference frame from camera to robot |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 34 | Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camrob_target, |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 35 | Eigen::Affine3d extrinsics) { |
| 36 | const Eigen::Affine3d H_robot_camrob = extrinsics; |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 37 | const Eigen::Affine3d H_robot_target = H_robot_camrob * H_camrob_target; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 38 | return H_robot_target; |
| 39 | } |
| 40 | |
| 41 | // Add detected apriltag poses relative to the robot to |
| 42 | // timestamped_target_detections |
Milind Upadhyay | 915d600 | 2022-12-26 20:37:43 -0800 | [diff] [blame] | 43 | void HandleAprilTag(aos::distributed_clock::time_point pi_distributed_time, |
| 44 | std::vector<cv::Vec4i> april_ids, |
| 45 | std::vector<Eigen::Vector3d> rvecs_eigen, |
| 46 | std::vector<Eigen::Vector3d> tvecs_eigen, |
| 47 | std::vector<DataAdapter::TimestampedDetection> |
| 48 | *timestamped_target_detections, |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 49 | Eigen::Affine3d extrinsics) { |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 50 | for (size_t tag = 0; tag < april_ids.size(); tag++) { |
| 51 | Eigen::Translation3d T_camera_target = Eigen::Translation3d( |
| 52 | tvecs_eigen[tag][0], tvecs_eigen[tag][1], tvecs_eigen[tag][2]); |
| 53 | Eigen::AngleAxisd r_angle = Eigen::AngleAxisd( |
| 54 | rvecs_eigen[tag].norm(), rvecs_eigen[tag] / rvecs_eigen[tag].norm()); |
| 55 | CHECK(rvecs_eigen[tag].norm() != 0) << "rvecs norm = 0; divide by 0"; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 56 | |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 57 | Eigen::Affine3d H_camcv_target = T_camera_target * r_angle; |
| 58 | // With X, Y, Z being robot axes and x, y, z being camera axes, |
| 59 | // x = -Y, y = -Z, z = X |
| 60 | static const Eigen::Affine3d H_camcv_camrob = |
| 61 | Eigen::Affine3d((Eigen::Matrix4d() << 0.0, -1.0, 0.0, 0.0, 0.0, 0.0, |
| 62 | -1.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0) |
| 63 | .finished()); |
| 64 | Eigen::Affine3d H_camrob_target = H_camcv_camrob.inverse() * H_camcv_target; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 65 | Eigen::Affine3d H_robot_target = |
| 66 | CameraToRobotDetection(H_camrob_target, extrinsics); |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 67 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 68 | ceres::examples::Pose3d target_pose_camera = |
| 69 | PoseUtils::Affine3dToPose3d(H_camrob_target); |
| 70 | double distance_from_camera = target_pose_camera.p.norm(); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 71 | |
| 72 | timestamped_target_detections->emplace_back( |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 73 | DataAdapter::TimestampedDetection{ |
| 74 | .time = pi_distributed_time, |
| 75 | .H_robot_target = H_robot_target, |
| 76 | .distance_from_camera = distance_from_camera, |
| 77 | .id = april_ids[tag][0]}); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 78 | } |
| 79 | } |
| 80 | |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame^] | 81 | const calibration::CameraCalibration *FindCameraCalibration( |
| 82 | const calibration::CalibrationData *calibration_data, |
| 83 | std::string_view node_name) { |
| 84 | for (const calibration::CameraCalibration *candidate : |
| 85 | *calibration_data->camera_calibrations()) { |
| 86 | if (candidate->node_name()->string_view() != node_name) { |
| 87 | continue; |
| 88 | } |
| 89 | if (candidate->team_number() != FLAGS_team_number) { |
| 90 | continue; |
| 91 | } |
| 92 | return candidate; |
| 93 | } |
| 94 | LOG(FATAL) << ": Failed to find camera calibration for " << node_name |
| 95 | << " on " << FLAGS_team_number; |
| 96 | } |
| 97 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 98 | Eigen::Affine3d CameraExtrinsics( |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 99 | const calibration::CameraCalibration *camera_calibration) { |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame^] | 100 | const frc971::vision::calibration::TransformationMatrix *transform = |
| 101 | camera_calibration->has_turret_extrinsics() |
| 102 | ? camera_calibration->turret_extrinsics() |
| 103 | : camera_calibration->fixed_extrinsics(); |
| 104 | |
| 105 | cv::Mat result( |
| 106 | 4, 4, CV_32F, |
| 107 | const_cast<void *>(static_cast<const void *>(transform->data()->data()))); |
| 108 | result.convertTo(result, CV_64F); |
| 109 | CHECK_EQ(result.total(), transform->data()->size()); |
| 110 | |
| 111 | Eigen::Matrix4d result_eigen; |
| 112 | cv::cv2eigen(result, result_eigen); |
| 113 | return Eigen::Affine3d(result_eigen); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 114 | } |
| 115 | |
| 116 | // Get images from pi and pass apriltag positions to HandleAprilTag() |
| 117 | void HandlePiCaptures( |
| 118 | int pi_number, aos::EventLoop *pi_event_loop, |
| 119 | aos::logger::LogReader *reader, |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 120 | std::vector<DataAdapter::TimestampedDetection> |
| 121 | *timestamped_target_detections, |
| 122 | std::vector<std::unique_ptr<CharucoExtractor>> *charuco_extractors, |
| 123 | std::vector<std::unique_ptr<ImageCallback>> *image_callbacks) { |
| 124 | const aos::FlatbufferSpan<calibration::CalibrationData> calibration_data( |
| 125 | CalibrationData()); |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame^] | 126 | const calibration::CameraCalibration *calibration = FindCameraCalibration( |
| 127 | &calibration_data.message(), "pi" + std::to_string(pi_number)); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 128 | const auto extrinsics = CameraExtrinsics(calibration); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 129 | |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 130 | // TODO(milind): change to /camera once we log at full frequency |
| 131 | static constexpr std::string_view kImageChannel = "/camera/decimated"; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 132 | charuco_extractors->emplace_back(std::make_unique<CharucoExtractor>( |
| 133 | pi_event_loop, |
| 134 | "pi-" + std::to_string(FLAGS_team_number) + "-" + |
| 135 | std::to_string(pi_number), |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame^] | 136 | frc971::vision::TargetType::kAprilTag, kImageChannel, |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 137 | [=](cv::Mat /*rgb_image*/, aos::monotonic_clock::time_point eof, |
| 138 | std::vector<cv::Vec4i> april_ids, |
| 139 | std::vector<std::vector<cv::Point2f>> /*april_corners*/, bool valid, |
| 140 | std::vector<Eigen::Vector3d> rvecs_eigen, |
| 141 | std::vector<Eigen::Vector3d> tvecs_eigen) { |
| 142 | aos::distributed_clock::time_point pi_distributed_time = |
| 143 | reader->event_loop_factory() |
| 144 | ->GetNodeEventLoopFactory(pi_event_loop->node()) |
| 145 | ->ToDistributedClock(eof); |
| 146 | |
| 147 | if (valid) { |
| 148 | HandleAprilTag(pi_distributed_time, april_ids, rvecs_eigen, |
| 149 | tvecs_eigen, timestamped_target_detections, |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 150 | extrinsics); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 151 | } |
| 152 | })); |
| 153 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 154 | image_callbacks->emplace_back(std::make_unique<ImageCallback>( |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 155 | pi_event_loop, kImageChannel, |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 156 | [&, charuco_extractor = |
| 157 | charuco_extractors->at(charuco_extractors->size() - 1).get()]( |
| 158 | cv::Mat rgb_image, const aos::monotonic_clock::time_point eof) { |
| 159 | charuco_extractor->HandleImage(rgb_image, eof); |
| 160 | })); |
| 161 | } |
| 162 | |
| 163 | void MappingMain(int argc, char *argv[]) { |
| 164 | std::vector<std::string> unsorted_logfiles = |
| 165 | aos::logger::FindLogs(argc, argv); |
| 166 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 167 | std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections; |
| 168 | |
| 169 | // open logfiles |
| 170 | aos::logger::LogReader reader(aos::logger::SortParts(unsorted_logfiles)); |
| 171 | reader.Register(); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 172 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 173 | std::vector<std::unique_ptr<CharucoExtractor>> charuco_extractors; |
| 174 | std::vector<std::unique_ptr<ImageCallback>> image_callbacks; |
| 175 | |
| 176 | const aos::Node *pi1 = |
| 177 | aos::configuration::GetNode(reader.configuration(), "pi1"); |
| 178 | std::unique_ptr<aos::EventLoop> pi1_event_loop = |
| 179 | reader.event_loop_factory()->MakeEventLoop("pi1", pi1); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 180 | HandlePiCaptures(1, pi1_event_loop.get(), &reader, |
| 181 | ×tamped_target_detections, &charuco_extractors, |
| 182 | &image_callbacks); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 183 | |
| 184 | const aos::Node *pi2 = |
| 185 | aos::configuration::GetNode(reader.configuration(), "pi2"); |
| 186 | std::unique_ptr<aos::EventLoop> pi2_event_loop = |
| 187 | reader.event_loop_factory()->MakeEventLoop("pi2", pi2); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 188 | HandlePiCaptures(2, pi2_event_loop.get(), &reader, |
| 189 | ×tamped_target_detections, &charuco_extractors, |
| 190 | &image_callbacks); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 191 | |
| 192 | const aos::Node *pi3 = |
| 193 | aos::configuration::GetNode(reader.configuration(), "pi3"); |
| 194 | std::unique_ptr<aos::EventLoop> pi3_event_loop = |
| 195 | reader.event_loop_factory()->MakeEventLoop("pi3", pi3); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 196 | HandlePiCaptures(3, pi3_event_loop.get(), &reader, |
| 197 | ×tamped_target_detections, &charuco_extractors, |
| 198 | &image_callbacks); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 199 | |
| 200 | const aos::Node *pi4 = |
| 201 | aos::configuration::GetNode(reader.configuration(), "pi4"); |
| 202 | std::unique_ptr<aos::EventLoop> pi4_event_loop = |
| 203 | reader.event_loop_factory()->MakeEventLoop("pi4", pi4); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 204 | HandlePiCaptures(4, pi4_event_loop.get(), &reader, |
| 205 | ×tamped_target_detections, &charuco_extractors, |
| 206 | &image_callbacks); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 207 | |
| 208 | reader.event_loop_factory()->Run(); |
| 209 | |
| 210 | auto target_constraints = |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 211 | DataAdapter::MatchTargetDetections(timestamped_target_detections); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 212 | |
| 213 | frc971::vision::TargetMapper mapper(FLAGS_json_path, target_constraints); |
Yash Chainani | 0366963 | 2022-12-17 19:37:34 -0800 | [diff] [blame] | 214 | mapper.Solve("rapid_react"); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 215 | |
| 216 | // Pointers need to be deleted to destruct all fetchers |
| 217 | for (auto &charuco_extractor_ptr : charuco_extractors) { |
| 218 | charuco_extractor_ptr.reset(); |
| 219 | } |
| 220 | |
| 221 | for (auto &image_callback_ptr : image_callbacks) { |
| 222 | image_callback_ptr.reset(); |
| 223 | } |
| 224 | } |
| 225 | |
| 226 | } // namespace vision |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame^] | 227 | } // namespace y2023 |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 228 | |
| 229 | int main(int argc, char **argv) { |
| 230 | aos::InitGoogle(&argc, &argv); |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame^] | 231 | y2023::vision::MappingMain(argc, argv); |
Milind Upadhyay | 915d600 | 2022-12-26 20:37:43 -0800 | [diff] [blame] | 232 | } |