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" |
James Kuszmaul | d67f6d2 | 2023-02-05 17:37:25 -0800 | [diff] [blame] | 16 | #include "y2023/vision/vision_util.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 { |
| 24 | using frc971::vision::DataAdapter; |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 25 | using frc971::vision::ImageCallback; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 26 | using frc971::vision::PoseUtils; |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 27 | using frc971::vision::TargetMap; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 28 | using frc971::vision::TargetMapper; |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 29 | namespace calibration = frc971::vision::calibration; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 30 | |
| 31 | // Change reference frame from camera to robot |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 32 | Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camrob_target, |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 33 | Eigen::Affine3d extrinsics) { |
| 34 | const Eigen::Affine3d H_robot_camrob = extrinsics; |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 35 | const Eigen::Affine3d H_robot_target = H_robot_camrob * H_camrob_target; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 36 | return H_robot_target; |
| 37 | } |
| 38 | |
| 39 | // Add detected apriltag poses relative to the robot to |
| 40 | // timestamped_target_detections |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 41 | void HandleAprilTag(const TargetMap &map, |
| 42 | aos::distributed_clock::time_point pi_distributed_time, |
Milind Upadhyay | 915d600 | 2022-12-26 20:37:43 -0800 | [diff] [blame] | 43 | std::vector<DataAdapter::TimestampedDetection> |
| 44 | *timestamped_target_detections, |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 45 | Eigen::Affine3d extrinsics) { |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 46 | for (const auto *target_pose_fbs : *map.target_poses()) { |
| 47 | const TargetMapper::TargetPose target_pose = |
| 48 | PoseUtils::TargetPoseFromFbs(*target_pose_fbs); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 49 | |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 50 | Eigen::Affine3d H_camcv_target = |
| 51 | Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q; |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 52 | // With X, Y, Z being robot axes and x, y, z being camera axes, |
| 53 | // x = -Y, y = -Z, z = X |
| 54 | static const Eigen::Affine3d H_camcv_camrob = |
| 55 | Eigen::Affine3d((Eigen::Matrix4d() << 0.0, -1.0, 0.0, 0.0, 0.0, 0.0, |
| 56 | -1.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0) |
| 57 | .finished()); |
| 58 | Eigen::Affine3d H_camrob_target = H_camcv_camrob.inverse() * H_camcv_target; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 59 | Eigen::Affine3d H_robot_target = |
| 60 | CameraToRobotDetection(H_camrob_target, extrinsics); |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 61 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 62 | ceres::examples::Pose3d target_pose_camera = |
| 63 | PoseUtils::Affine3dToPose3d(H_camrob_target); |
| 64 | double distance_from_camera = target_pose_camera.p.norm(); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 65 | |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 66 | CHECK(map.has_monotonic_timestamp_ns()) |
| 67 | << "Need detection timestamps for mapping"; |
| 68 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 69 | timestamped_target_detections->emplace_back( |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 70 | DataAdapter::TimestampedDetection{ |
| 71 | .time = pi_distributed_time, |
| 72 | .H_robot_target = H_robot_target, |
| 73 | .distance_from_camera = distance_from_camera, |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 74 | .id = static_cast<TargetMapper::TargetId>(target_pose.id)}); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 75 | } |
| 76 | } |
| 77 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 78 | // Get images from pi and pass apriltag positions to HandleAprilTag() |
| 79 | void HandlePiCaptures( |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 80 | aos::EventLoop *detection_event_loop, aos::EventLoop *mapping_event_loop, |
| 81 | aos::logger::LogReader *reader, |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 82 | std::vector<DataAdapter::TimestampedDetection> |
| 83 | *timestamped_target_detections, |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 84 | std::vector<std::unique_ptr<AprilRoboticsDetector>> *detectors) { |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 85 | static constexpr std::string_view kImageChannel = "/camera"; |
| 86 | auto detector_ptr = std::make_unique<AprilRoboticsDetector>( |
| 87 | detection_event_loop, kImageChannel); |
milind-u | f2a4e32 | 2023-02-01 19:33:10 -0800 | [diff] [blame] | 88 | // Get the camera extrinsics |
James Kuszmaul | 258e4ee | 2023-02-23 14:22:30 -0800 | [diff] [blame^] | 89 | cv::Mat extrinsics_cv = detector_ptr->extrinsics().value(); |
milind-u | f2a4e32 | 2023-02-01 19:33:10 -0800 | [diff] [blame] | 90 | Eigen::Matrix4d extrinsics_matrix; |
| 91 | cv::cv2eigen(extrinsics_cv, extrinsics_matrix); |
| 92 | const auto extrinsics = Eigen::Affine3d(extrinsics_matrix); |
| 93 | |
| 94 | detectors->emplace_back(std::move(detector_ptr)); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 95 | |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 96 | mapping_event_loop->MakeWatcher("/camera", [=](const TargetMap &map) { |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 97 | aos::distributed_clock::time_point pi_distributed_time = |
| 98 | reader->event_loop_factory() |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 99 | ->GetNodeEventLoopFactory(mapping_event_loop->node()) |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 100 | ->ToDistributedClock(aos::monotonic_clock::time_point( |
| 101 | aos::monotonic_clock::duration(map.monotonic_timestamp_ns()))); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 102 | |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 103 | HandleAprilTag(map, pi_distributed_time, timestamped_target_detections, |
| 104 | extrinsics); |
| 105 | }); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 106 | } |
| 107 | |
| 108 | void MappingMain(int argc, char *argv[]) { |
| 109 | std::vector<std::string> unsorted_logfiles = |
| 110 | aos::logger::FindLogs(argc, argv); |
| 111 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 112 | std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections; |
| 113 | |
| 114 | // open logfiles |
| 115 | aos::logger::LogReader reader(aos::logger::SortParts(unsorted_logfiles)); |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 116 | // Send new april tag poses. This allows us to take a log of images, then play |
| 117 | // with the april detection code and see those changes take effect in mapping |
| 118 | constexpr size_t kNumPis = 4; |
| 119 | for (size_t i = 1; i <= kNumPis; i++) { |
| 120 | reader.RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i), |
| 121 | "frc971.vision.TargetMap"); |
| 122 | } |
| 123 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 124 | reader.Register(); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 125 | |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 126 | std::vector<std::unique_ptr<AprilRoboticsDetector>> detectors; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 127 | |
| 128 | const aos::Node *pi1 = |
| 129 | aos::configuration::GetNode(reader.configuration(), "pi1"); |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 130 | std::unique_ptr<aos::EventLoop> pi1_detection_event_loop = |
| 131 | reader.event_loop_factory()->MakeEventLoop("pi1_detection", pi1); |
| 132 | std::unique_ptr<aos::EventLoop> pi1_mapping_event_loop = |
| 133 | reader.event_loop_factory()->MakeEventLoop("pi1_mapping", pi1); |
| 134 | HandlePiCaptures(pi1_detection_event_loop.get(), pi1_mapping_event_loop.get(), |
| 135 | &reader, ×tamped_target_detections, &detectors); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 136 | |
| 137 | const aos::Node *pi2 = |
| 138 | aos::configuration::GetNode(reader.configuration(), "pi2"); |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 139 | std::unique_ptr<aos::EventLoop> pi2_detection_event_loop = |
| 140 | reader.event_loop_factory()->MakeEventLoop("pi2_detection", pi2); |
| 141 | std::unique_ptr<aos::EventLoop> pi2_mapping_event_loop = |
| 142 | reader.event_loop_factory()->MakeEventLoop("pi2_mapping", pi2); |
| 143 | HandlePiCaptures(pi2_detection_event_loop.get(), pi2_mapping_event_loop.get(), |
| 144 | &reader, ×tamped_target_detections, &detectors); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 145 | |
| 146 | const aos::Node *pi3 = |
| 147 | aos::configuration::GetNode(reader.configuration(), "pi3"); |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 148 | std::unique_ptr<aos::EventLoop> pi3_detection_event_loop = |
| 149 | reader.event_loop_factory()->MakeEventLoop("pi3_detection", pi3); |
| 150 | std::unique_ptr<aos::EventLoop> pi3_mapping_event_loop = |
| 151 | reader.event_loop_factory()->MakeEventLoop("pi3_mapping", pi3); |
| 152 | HandlePiCaptures(pi3_detection_event_loop.get(), pi3_mapping_event_loop.get(), |
| 153 | &reader, ×tamped_target_detections, &detectors); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 154 | |
| 155 | const aos::Node *pi4 = |
| 156 | aos::configuration::GetNode(reader.configuration(), "pi4"); |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 157 | std::unique_ptr<aos::EventLoop> pi4_detection_event_loop = |
| 158 | reader.event_loop_factory()->MakeEventLoop("pi4_detection", pi4); |
| 159 | std::unique_ptr<aos::EventLoop> pi4_mapping_event_loop = |
| 160 | reader.event_loop_factory()->MakeEventLoop("pi4_mapping", pi4); |
| 161 | HandlePiCaptures(pi4_detection_event_loop.get(), pi4_mapping_event_loop.get(), |
| 162 | &reader, ×tamped_target_detections, &detectors); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 163 | |
| 164 | reader.event_loop_factory()->Run(); |
| 165 | |
| 166 | auto target_constraints = |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 167 | DataAdapter::MatchTargetDetections(timestamped_target_detections); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 168 | |
| 169 | frc971::vision::TargetMapper mapper(FLAGS_json_path, target_constraints); |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 170 | mapper.Solve("charged_up"); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 171 | |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 172 | // Clean up all the pointers |
| 173 | for (auto &detector_ptr : detectors) { |
| 174 | detector_ptr.reset(); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 175 | } |
| 176 | } |
| 177 | |
| 178 | } // namespace vision |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 179 | } // namespace y2023 |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 180 | |
| 181 | int main(int argc, char **argv) { |
| 182 | aos::InitGoogle(&argc, &argv); |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 183 | y2023::vision::MappingMain(argc, argv); |
Milind Upadhyay | 915d600 | 2022-12-26 20:37:43 -0800 | [diff] [blame] | 184 | } |