Jim Ostrowski | aec5dd2 | 2023-02-27 22:17:53 -0800 | [diff] [blame^] | 1 | #include "aos/configuration.h" |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 2 | #include "aos/events/logging/log_reader.h" |
| 3 | #include "aos/events/simulated_event_loop.h" |
| 4 | #include "aos/init.h" |
| 5 | #include "frc971/control_loops/pose.h" |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 6 | #include "frc971/vision/calibration_generated.h" |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 7 | #include "frc971/vision/charuco_lib.h" |
| 8 | #include "frc971/vision/target_mapper.h" |
| 9 | #include "opencv2/aruco.hpp" |
| 10 | #include "opencv2/calib3d.hpp" |
| 11 | #include "opencv2/core/eigen.hpp" |
| 12 | #include "opencv2/features2d.hpp" |
| 13 | #include "opencv2/highgui.hpp" |
| 14 | #include "opencv2/highgui/highgui.hpp" |
| 15 | #include "opencv2/imgproc.hpp" |
milind-u | c5a494f | 2023-02-24 15:39:22 -0800 | [diff] [blame] | 16 | #include "y2023/constants/simulated_constants_sender.h" |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 17 | #include "y2023/vision/aprilrobotics.h" |
James Kuszmaul | d67f6d2 | 2023-02-05 17:37:25 -0800 | [diff] [blame] | 18 | #include "y2023/vision/vision_util.h" |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 19 | |
milind-u | c5a494f | 2023-02-24 15:39:22 -0800 | [diff] [blame] | 20 | DEFINE_string(json_path, "y2023/vision/maps/target_map.json", |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 21 | "Specify path for json with initial pose guesses."); |
Jim Ostrowski | aec5dd2 | 2023-02-27 22:17:53 -0800 | [diff] [blame^] | 22 | DEFINE_string(config, "y2023/aos_config.json", |
| 23 | "Path to the config file to use."); |
milind-u | c5a494f | 2023-02-24 15:39:22 -0800 | [diff] [blame] | 24 | DEFINE_string(constants_path, "y2023/constants/constants.json", |
| 25 | "Path to the constant file"); |
| 26 | DEFINE_string(output_dir, "y2023/vision/maps", |
| 27 | "Directory to write solved target map to"); |
| 28 | DEFINE_string(field_name, "charged_up", |
| 29 | "Field name, for the output json filename and flatbuffer field"); |
| 30 | DEFINE_int32(team_number, 7971, |
| 31 | "Use the calibration for a node with this team number"); |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 32 | |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 33 | namespace y2023 { |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 34 | namespace vision { |
| 35 | using frc971::vision::DataAdapter; |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 36 | using frc971::vision::ImageCallback; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 37 | using frc971::vision::PoseUtils; |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 38 | using frc971::vision::TargetMap; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 39 | using frc971::vision::TargetMapper; |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 40 | namespace calibration = frc971::vision::calibration; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 41 | |
| 42 | // Change reference frame from camera to robot |
milind-u | ee67abd | 2023-02-23 18:26:55 -0800 | [diff] [blame] | 43 | Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target, |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 44 | Eigen::Affine3d extrinsics) { |
milind-u | ee67abd | 2023-02-23 18:26:55 -0800 | [diff] [blame] | 45 | const Eigen::Affine3d H_robot_camera = extrinsics; |
| 46 | const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 47 | return H_robot_target; |
| 48 | } |
| 49 | |
| 50 | // Add detected apriltag poses relative to the robot to |
| 51 | // timestamped_target_detections |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 52 | void HandleAprilTag(const TargetMap &map, |
| 53 | aos::distributed_clock::time_point pi_distributed_time, |
Milind Upadhyay | 915d600 | 2022-12-26 20:37:43 -0800 | [diff] [blame] | 54 | std::vector<DataAdapter::TimestampedDetection> |
| 55 | *timestamped_target_detections, |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 56 | Eigen::Affine3d extrinsics) { |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 57 | for (const auto *target_pose_fbs : *map.target_poses()) { |
| 58 | const TargetMapper::TargetPose target_pose = |
| 59 | PoseUtils::TargetPoseFromFbs(*target_pose_fbs); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 60 | |
milind-u | ee67abd | 2023-02-23 18:26:55 -0800 | [diff] [blame] | 61 | Eigen::Affine3d H_camera_target = |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 62 | Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 63 | Eigen::Affine3d H_robot_target = |
milind-u | ee67abd | 2023-02-23 18:26:55 -0800 | [diff] [blame] | 64 | CameraToRobotDetection(H_camera_target, extrinsics); |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 65 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 66 | ceres::examples::Pose3d target_pose_camera = |
milind-u | ee67abd | 2023-02-23 18:26:55 -0800 | [diff] [blame] | 67 | PoseUtils::Affine3dToPose3d(H_camera_target); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 68 | double distance_from_camera = target_pose_camera.p.norm(); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 69 | |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 70 | CHECK(map.has_monotonic_timestamp_ns()) |
| 71 | << "Need detection timestamps for mapping"; |
| 72 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 73 | timestamped_target_detections->emplace_back( |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 74 | DataAdapter::TimestampedDetection{ |
| 75 | .time = pi_distributed_time, |
| 76 | .H_robot_target = H_robot_target, |
| 77 | .distance_from_camera = distance_from_camera, |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 78 | .id = static_cast<TargetMapper::TargetId>(target_pose.id)}); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 79 | } |
| 80 | } |
| 81 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 82 | // Get images from pi and pass apriltag positions to HandleAprilTag() |
| 83 | void HandlePiCaptures( |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 84 | aos::EventLoop *detection_event_loop, aos::EventLoop *mapping_event_loop, |
| 85 | aos::logger::LogReader *reader, |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 86 | std::vector<DataAdapter::TimestampedDetection> |
| 87 | *timestamped_target_detections, |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 88 | std::vector<std::unique_ptr<AprilRoboticsDetector>> *detectors) { |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 89 | static constexpr std::string_view kImageChannel = "/camera"; |
| 90 | auto detector_ptr = std::make_unique<AprilRoboticsDetector>( |
| 91 | detection_event_loop, kImageChannel); |
milind-u | f2a4e32 | 2023-02-01 19:33:10 -0800 | [diff] [blame] | 92 | // Get the camera extrinsics |
James Kuszmaul | 258e4ee | 2023-02-23 14:22:30 -0800 | [diff] [blame] | 93 | cv::Mat extrinsics_cv = detector_ptr->extrinsics().value(); |
milind-u | f2a4e32 | 2023-02-01 19:33:10 -0800 | [diff] [blame] | 94 | Eigen::Matrix4d extrinsics_matrix; |
| 95 | cv::cv2eigen(extrinsics_cv, extrinsics_matrix); |
| 96 | const auto extrinsics = Eigen::Affine3d(extrinsics_matrix); |
| 97 | |
| 98 | detectors->emplace_back(std::move(detector_ptr)); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 99 | |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 100 | mapping_event_loop->MakeWatcher("/camera", [=](const TargetMap &map) { |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 101 | aos::distributed_clock::time_point pi_distributed_time = |
| 102 | reader->event_loop_factory() |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 103 | ->GetNodeEventLoopFactory(mapping_event_loop->node()) |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 104 | ->ToDistributedClock(aos::monotonic_clock::time_point( |
| 105 | aos::monotonic_clock::duration(map.monotonic_timestamp_ns()))); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 106 | |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 107 | HandleAprilTag(map, pi_distributed_time, timestamped_target_detections, |
| 108 | extrinsics); |
| 109 | }); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 110 | } |
| 111 | |
| 112 | void MappingMain(int argc, char *argv[]) { |
| 113 | std::vector<std::string> unsorted_logfiles = |
| 114 | aos::logger::FindLogs(argc, argv); |
| 115 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 116 | std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections; |
| 117 | |
Jim Ostrowski | aec5dd2 | 2023-02-27 22:17:53 -0800 | [diff] [blame^] | 118 | aos::FlatbufferDetachedBuffer<aos::Configuration> config = |
| 119 | aos::configuration::ReadConfig(FLAGS_config); |
| 120 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 121 | // open logfiles |
Jim Ostrowski | aec5dd2 | 2023-02-27 22:17:53 -0800 | [diff] [blame^] | 122 | aos::logger::LogReader reader(aos::logger::SortParts(unsorted_logfiles), |
| 123 | &config.message()); |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 124 | // Send new april tag poses. This allows us to take a log of images, then play |
| 125 | // with the april detection code and see those changes take effect in mapping |
| 126 | constexpr size_t kNumPis = 4; |
| 127 | for (size_t i = 1; i <= kNumPis; i++) { |
| 128 | reader.RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i), |
| 129 | "frc971.vision.TargetMap"); |
milind-u | c5a494f | 2023-02-24 15:39:22 -0800 | [diff] [blame] | 130 | reader.RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i), |
| 131 | "foxglove.ImageAnnotations"); |
| 132 | reader.RemapLoggedChannel(absl::StrFormat("/pi%u/constants", i), |
| 133 | "y2023.Constants"); |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 134 | } |
| 135 | |
milind-u | c5a494f | 2023-02-24 15:39:22 -0800 | [diff] [blame] | 136 | reader.RemapLoggedChannel("/imu/constants", "y2023.Constants"); |
| 137 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 138 | reader.Register(); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 139 | |
milind-u | c5a494f | 2023-02-24 15:39:22 -0800 | [diff] [blame] | 140 | SendSimulationConstants(reader.event_loop_factory(), FLAGS_team_number, |
| 141 | FLAGS_constants_path); |
| 142 | |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 143 | std::vector<std::unique_ptr<AprilRoboticsDetector>> detectors; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 144 | |
| 145 | const aos::Node *pi1 = |
| 146 | aos::configuration::GetNode(reader.configuration(), "pi1"); |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 147 | std::unique_ptr<aos::EventLoop> pi1_detection_event_loop = |
| 148 | reader.event_loop_factory()->MakeEventLoop("pi1_detection", pi1); |
| 149 | std::unique_ptr<aos::EventLoop> pi1_mapping_event_loop = |
| 150 | reader.event_loop_factory()->MakeEventLoop("pi1_mapping", pi1); |
| 151 | HandlePiCaptures(pi1_detection_event_loop.get(), pi1_mapping_event_loop.get(), |
| 152 | &reader, ×tamped_target_detections, &detectors); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 153 | |
| 154 | const aos::Node *pi2 = |
| 155 | aos::configuration::GetNode(reader.configuration(), "pi2"); |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 156 | std::unique_ptr<aos::EventLoop> pi2_detection_event_loop = |
| 157 | reader.event_loop_factory()->MakeEventLoop("pi2_detection", pi2); |
| 158 | std::unique_ptr<aos::EventLoop> pi2_mapping_event_loop = |
| 159 | reader.event_loop_factory()->MakeEventLoop("pi2_mapping", pi2); |
| 160 | HandlePiCaptures(pi2_detection_event_loop.get(), pi2_mapping_event_loop.get(), |
| 161 | &reader, ×tamped_target_detections, &detectors); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 162 | |
| 163 | const aos::Node *pi3 = |
| 164 | aos::configuration::GetNode(reader.configuration(), "pi3"); |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 165 | std::unique_ptr<aos::EventLoop> pi3_detection_event_loop = |
| 166 | reader.event_loop_factory()->MakeEventLoop("pi3_detection", pi3); |
| 167 | std::unique_ptr<aos::EventLoop> pi3_mapping_event_loop = |
| 168 | reader.event_loop_factory()->MakeEventLoop("pi3_mapping", pi3); |
| 169 | HandlePiCaptures(pi3_detection_event_loop.get(), pi3_mapping_event_loop.get(), |
| 170 | &reader, ×tamped_target_detections, &detectors); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 171 | |
| 172 | const aos::Node *pi4 = |
| 173 | aos::configuration::GetNode(reader.configuration(), "pi4"); |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 174 | std::unique_ptr<aos::EventLoop> pi4_detection_event_loop = |
| 175 | reader.event_loop_factory()->MakeEventLoop("pi4_detection", pi4); |
| 176 | std::unique_ptr<aos::EventLoop> pi4_mapping_event_loop = |
| 177 | reader.event_loop_factory()->MakeEventLoop("pi4_mapping", pi4); |
| 178 | HandlePiCaptures(pi4_detection_event_loop.get(), pi4_mapping_event_loop.get(), |
| 179 | &reader, ×tamped_target_detections, &detectors); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 180 | |
| 181 | reader.event_loop_factory()->Run(); |
| 182 | |
| 183 | auto target_constraints = |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 184 | DataAdapter::MatchTargetDetections(timestamped_target_detections); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 185 | |
| 186 | frc971::vision::TargetMapper mapper(FLAGS_json_path, target_constraints); |
milind-u | c5a494f | 2023-02-24 15:39:22 -0800 | [diff] [blame] | 187 | mapper.Solve(FLAGS_field_name, FLAGS_output_dir); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 188 | |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 189 | // Clean up all the pointers |
| 190 | for (auto &detector_ptr : detectors) { |
| 191 | detector_ptr.reset(); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 192 | } |
| 193 | } |
| 194 | |
| 195 | } // namespace vision |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 196 | } // namespace y2023 |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 197 | |
| 198 | int main(int argc, char **argv) { |
| 199 | aos::InitGoogle(&argc, &argv); |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 200 | y2023::vision::MappingMain(argc, argv); |
Milind Upadhyay | 915d600 | 2022-12-26 20:37:43 -0800 | [diff] [blame] | 201 | } |