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 | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 15 | #include "y2023/vision/aprilrobotics.h" |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 16 | #include "y2023/vision/calibration_data.h" |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 17 | |
| 18 | DEFINE_string(json_path, "target_map.json", |
| 19 | "Specify path for json with initial pose guesses."); |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 20 | DECLARE_int32(team_number); |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 21 | |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 22 | namespace y2023 { |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 23 | namespace vision { |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 24 | using frc971::vision::CharucoExtractor; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 25 | using frc971::vision::DataAdapter; |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 26 | using frc971::vision::ImageCallback; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 27 | using frc971::vision::PoseUtils; |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 28 | using frc971::vision::TargetMap; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 29 | using frc971::vision::TargetMapper; |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 30 | namespace calibration = frc971::vision::calibration; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 31 | |
| 32 | // Change reference frame from camera to robot |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 33 | Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camrob_target, |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 34 | Eigen::Affine3d extrinsics) { |
| 35 | const Eigen::Affine3d H_robot_camrob = extrinsics; |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 36 | const Eigen::Affine3d H_robot_target = H_robot_camrob * H_camrob_target; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 37 | return H_robot_target; |
| 38 | } |
| 39 | |
| 40 | // Add detected apriltag poses relative to the robot to |
| 41 | // timestamped_target_detections |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 42 | void HandleAprilTag(const TargetMap &map, |
| 43 | aos::distributed_clock::time_point pi_distributed_time, |
Milind Upadhyay | 915d600 | 2022-12-26 20:37:43 -0800 | [diff] [blame] | 44 | std::vector<DataAdapter::TimestampedDetection> |
| 45 | *timestamped_target_detections, |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 46 | Eigen::Affine3d extrinsics) { |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 47 | for (const auto *target_pose_fbs : *map.target_poses()) { |
| 48 | const TargetMapper::TargetPose target_pose = |
| 49 | PoseUtils::TargetPoseFromFbs(*target_pose_fbs); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 50 | |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 51 | Eigen::Affine3d H_camcv_target = |
| 52 | Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q; |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 53 | // With X, Y, Z being robot axes and x, y, z being camera axes, |
| 54 | // x = -Y, y = -Z, z = X |
| 55 | static const Eigen::Affine3d H_camcv_camrob = |
| 56 | Eigen::Affine3d((Eigen::Matrix4d() << 0.0, -1.0, 0.0, 0.0, 0.0, 0.0, |
| 57 | -1.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0) |
| 58 | .finished()); |
| 59 | Eigen::Affine3d H_camrob_target = H_camcv_camrob.inverse() * H_camcv_target; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 60 | Eigen::Affine3d H_robot_target = |
| 61 | CameraToRobotDetection(H_camrob_target, extrinsics); |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 62 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 63 | ceres::examples::Pose3d target_pose_camera = |
| 64 | PoseUtils::Affine3dToPose3d(H_camrob_target); |
| 65 | double distance_from_camera = target_pose_camera.p.norm(); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 66 | |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 67 | CHECK(map.has_monotonic_timestamp_ns()) |
| 68 | << "Need detection timestamps for mapping"; |
| 69 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 70 | timestamped_target_detections->emplace_back( |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 71 | DataAdapter::TimestampedDetection{ |
| 72 | .time = pi_distributed_time, |
| 73 | .H_robot_target = H_robot_target, |
| 74 | .distance_from_camera = distance_from_camera, |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 75 | .id = static_cast<TargetMapper::TargetId>(target_pose.id)}); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 76 | } |
| 77 | } |
| 78 | |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 79 | const calibration::CameraCalibration *FindCameraCalibration( |
| 80 | const calibration::CalibrationData *calibration_data, |
| 81 | std::string_view node_name) { |
| 82 | for (const calibration::CameraCalibration *candidate : |
| 83 | *calibration_data->camera_calibrations()) { |
| 84 | if (candidate->node_name()->string_view() != node_name) { |
| 85 | continue; |
| 86 | } |
| 87 | if (candidate->team_number() != FLAGS_team_number) { |
| 88 | continue; |
| 89 | } |
| 90 | return candidate; |
| 91 | } |
| 92 | LOG(FATAL) << ": Failed to find camera calibration for " << node_name |
| 93 | << " on " << FLAGS_team_number; |
| 94 | } |
| 95 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 96 | Eigen::Affine3d CameraExtrinsics( |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 97 | const calibration::CameraCalibration *camera_calibration) { |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 98 | const frc971::vision::calibration::TransformationMatrix *transform = |
| 99 | camera_calibration->has_turret_extrinsics() |
| 100 | ? camera_calibration->turret_extrinsics() |
| 101 | : camera_calibration->fixed_extrinsics(); |
| 102 | |
| 103 | cv::Mat result( |
| 104 | 4, 4, CV_32F, |
| 105 | const_cast<void *>(static_cast<const void *>(transform->data()->data()))); |
| 106 | result.convertTo(result, CV_64F); |
| 107 | CHECK_EQ(result.total(), transform->data()->size()); |
| 108 | |
| 109 | Eigen::Matrix4d result_eigen; |
| 110 | cv::cv2eigen(result, result_eigen); |
| 111 | return Eigen::Affine3d(result_eigen); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 112 | } |
| 113 | |
| 114 | // Get images from pi and pass apriltag positions to HandleAprilTag() |
| 115 | void HandlePiCaptures( |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 116 | aos::EventLoop *pi_event_loop, aos::logger::LogReader *reader, |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 117 | std::vector<DataAdapter::TimestampedDetection> |
| 118 | *timestamped_target_detections, |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 119 | std::vector<std::unique_ptr<AprilRoboticsDetector>> *detectors) { |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 120 | const aos::FlatbufferSpan<calibration::CalibrationData> calibration_data( |
| 121 | CalibrationData()); |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 122 | |
| 123 | const auto node_name = pi_event_loop->node()->name()->string_view(); |
| 124 | const calibration::CameraCalibration *calibration = |
| 125 | FindCameraCalibration(&calibration_data.message(), node_name); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 126 | const auto extrinsics = CameraExtrinsics(calibration); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 127 | |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 128 | // TODO(milind): change to /camera once we log at full frequency |
| 129 | static constexpr std::string_view kImageChannel = "/camera/decimated"; |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 130 | detectors->emplace_back( |
| 131 | std::make_unique<AprilRoboticsDetector>(pi_event_loop, kImageChannel)); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 132 | |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 133 | pi_event_loop->MakeWatcher("/camera", [=](const TargetMap &map) { |
| 134 | aos::distributed_clock::time_point pi_distributed_time = |
| 135 | reader->event_loop_factory() |
| 136 | ->GetNodeEventLoopFactory(pi_event_loop->node()) |
| 137 | ->ToDistributedClock(aos::monotonic_clock::time_point( |
| 138 | aos::monotonic_clock::duration(map.monotonic_timestamp_ns()))); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 139 | |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 140 | HandleAprilTag(map, pi_distributed_time, timestamped_target_detections, |
| 141 | extrinsics); |
| 142 | }); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 143 | } |
| 144 | |
| 145 | void MappingMain(int argc, char *argv[]) { |
| 146 | std::vector<std::string> unsorted_logfiles = |
| 147 | aos::logger::FindLogs(argc, argv); |
| 148 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 149 | std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections; |
| 150 | |
| 151 | // open logfiles |
| 152 | aos::logger::LogReader reader(aos::logger::SortParts(unsorted_logfiles)); |
| 153 | reader.Register(); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 154 | |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 155 | std::vector<std::unique_ptr<AprilRoboticsDetector>> detectors; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 156 | |
| 157 | const aos::Node *pi1 = |
| 158 | aos::configuration::GetNode(reader.configuration(), "pi1"); |
| 159 | std::unique_ptr<aos::EventLoop> pi1_event_loop = |
| 160 | reader.event_loop_factory()->MakeEventLoop("pi1", pi1); |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 161 | HandlePiCaptures(pi1_event_loop.get(), &reader, |
| 162 | ×tamped_target_detections, &detectors); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 163 | |
| 164 | const aos::Node *pi2 = |
| 165 | aos::configuration::GetNode(reader.configuration(), "pi2"); |
| 166 | std::unique_ptr<aos::EventLoop> pi2_event_loop = |
| 167 | reader.event_loop_factory()->MakeEventLoop("pi2", pi2); |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 168 | HandlePiCaptures(pi2_event_loop.get(), &reader, |
| 169 | ×tamped_target_detections, &detectors); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 170 | |
| 171 | const aos::Node *pi3 = |
| 172 | aos::configuration::GetNode(reader.configuration(), "pi3"); |
| 173 | std::unique_ptr<aos::EventLoop> pi3_event_loop = |
| 174 | reader.event_loop_factory()->MakeEventLoop("pi3", pi3); |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 175 | HandlePiCaptures(pi3_event_loop.get(), &reader, |
| 176 | ×tamped_target_detections, &detectors); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 177 | |
| 178 | const aos::Node *pi4 = |
| 179 | aos::configuration::GetNode(reader.configuration(), "pi4"); |
| 180 | std::unique_ptr<aos::EventLoop> pi4_event_loop = |
| 181 | reader.event_loop_factory()->MakeEventLoop("pi4", pi4); |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 182 | HandlePiCaptures(pi4_event_loop.get(), &reader, |
| 183 | ×tamped_target_detections, &detectors); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 184 | |
| 185 | reader.event_loop_factory()->Run(); |
| 186 | |
| 187 | auto target_constraints = |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 188 | DataAdapter::MatchTargetDetections(timestamped_target_detections); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 189 | |
| 190 | frc971::vision::TargetMapper mapper(FLAGS_json_path, target_constraints); |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 191 | mapper.Solve("charged_up"); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 192 | |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 193 | // Clean up all the pointers |
| 194 | for (auto &detector_ptr : detectors) { |
| 195 | detector_ptr.reset(); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 196 | } |
| 197 | } |
| 198 | |
| 199 | } // namespace vision |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 200 | } // namespace y2023 |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 201 | |
| 202 | int main(int argc, char **argv) { |
| 203 | aos::InitGoogle(&argc, &argv); |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 204 | y2023::vision::MappingMain(argc, argv); |
Milind Upadhyay | 915d600 | 2022-12-26 20:37:43 -0800 | [diff] [blame] | 205 | } |