blob: a94192319f8b19dcf6d1ef2393d5c809c148dcd1 [file] [log] [blame]
Yash Chainanid5c7f0d2022-11-19 17:05:57 -08001#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-u16e3a082023-01-21 13:53:43 -08005#include "frc971/vision/calibration_generated.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -08006#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-uc5a494f2023-02-24 15:39:22 -080015#include "y2023/constants/simulated_constants_sender.h"
milind-u09fb1252023-01-28 19:21:41 -080016#include "y2023/vision/aprilrobotics.h"
James Kuszmauld67f6d22023-02-05 17:37:25 -080017#include "y2023/vision/vision_util.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080018
milind-uc5a494f2023-02-24 15:39:22 -080019DEFINE_string(json_path, "y2023/vision/maps/target_map.json",
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080020 "Specify path for json with initial pose guesses.");
milind-uc5a494f2023-02-24 15:39:22 -080021DEFINE_string(constants_path, "y2023/constants/constants.json",
22 "Path to the constant file");
23DEFINE_string(output_dir, "y2023/vision/maps",
24 "Directory to write solved target map to");
25DEFINE_string(field_name, "charged_up",
26 "Field name, for the output json filename and flatbuffer field");
27DEFINE_int32(team_number, 7971,
28 "Use the calibration for a node with this team number");
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080029
milind-u16e3a082023-01-21 13:53:43 -080030namespace y2023 {
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080031namespace vision {
32using frc971::vision::DataAdapter;
milind-u16e3a082023-01-21 13:53:43 -080033using frc971::vision::ImageCallback;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080034using frc971::vision::PoseUtils;
milind-u09fb1252023-01-28 19:21:41 -080035using frc971::vision::TargetMap;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080036using frc971::vision::TargetMapper;
milind-u16e3a082023-01-21 13:53:43 -080037namespace calibration = frc971::vision::calibration;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080038
39// Change reference frame from camera to robot
milind-uee67abd2023-02-23 18:26:55 -080040Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080041 Eigen::Affine3d extrinsics) {
milind-uee67abd2023-02-23 18:26:55 -080042 const Eigen::Affine3d H_robot_camera = extrinsics;
43 const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080044 return H_robot_target;
45}
46
47// Add detected apriltag poses relative to the robot to
48// timestamped_target_detections
milind-u09fb1252023-01-28 19:21:41 -080049void HandleAprilTag(const TargetMap &map,
50 aos::distributed_clock::time_point pi_distributed_time,
Milind Upadhyay915d6002022-12-26 20:37:43 -080051 std::vector<DataAdapter::TimestampedDetection>
52 *timestamped_target_detections,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080053 Eigen::Affine3d extrinsics) {
milind-u3f5f83c2023-01-29 15:23:51 -080054 for (const auto *target_pose_fbs : *map.target_poses()) {
55 const TargetMapper::TargetPose target_pose =
56 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080057
milind-uee67abd2023-02-23 18:26:55 -080058 Eigen::Affine3d H_camera_target =
milind-u3f5f83c2023-01-29 15:23:51 -080059 Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080060 Eigen::Affine3d H_robot_target =
milind-uee67abd2023-02-23 18:26:55 -080061 CameraToRobotDetection(H_camera_target, extrinsics);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080062
Milind Upadhyayc5beba12022-12-17 17:41:20 -080063 ceres::examples::Pose3d target_pose_camera =
milind-uee67abd2023-02-23 18:26:55 -080064 PoseUtils::Affine3dToPose3d(H_camera_target);
Milind Upadhyayc5beba12022-12-17 17:41:20 -080065 double distance_from_camera = target_pose_camera.p.norm();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080066
milind-u09fb1252023-01-28 19:21:41 -080067 CHECK(map.has_monotonic_timestamp_ns())
68 << "Need detection timestamps for mapping";
69
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080070 timestamped_target_detections->emplace_back(
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080071 DataAdapter::TimestampedDetection{
72 .time = pi_distributed_time,
73 .H_robot_target = H_robot_target,
74 .distance_from_camera = distance_from_camera,
milind-u3f5f83c2023-01-29 15:23:51 -080075 .id = static_cast<TargetMapper::TargetId>(target_pose.id)});
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080076 }
77}
78
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080079// Get images from pi and pass apriltag positions to HandleAprilTag()
80void HandlePiCaptures(
milind-uf3ab8ba2023-02-04 17:56:16 -080081 aos::EventLoop *detection_event_loop, aos::EventLoop *mapping_event_loop,
82 aos::logger::LogReader *reader,
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080083 std::vector<DataAdapter::TimestampedDetection>
84 *timestamped_target_detections,
milind-u09fb1252023-01-28 19:21:41 -080085 std::vector<std::unique_ptr<AprilRoboticsDetector>> *detectors) {
milind-uf3ab8ba2023-02-04 17:56:16 -080086 static constexpr std::string_view kImageChannel = "/camera";
87 auto detector_ptr = std::make_unique<AprilRoboticsDetector>(
88 detection_event_loop, kImageChannel);
milind-uf2a4e322023-02-01 19:33:10 -080089 // Get the camera extrinsics
James Kuszmaul258e4ee2023-02-23 14:22:30 -080090 cv::Mat extrinsics_cv = detector_ptr->extrinsics().value();
milind-uf2a4e322023-02-01 19:33:10 -080091 Eigen::Matrix4d extrinsics_matrix;
92 cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
93 const auto extrinsics = Eigen::Affine3d(extrinsics_matrix);
94
95 detectors->emplace_back(std::move(detector_ptr));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080096
milind-uf3ab8ba2023-02-04 17:56:16 -080097 mapping_event_loop->MakeWatcher("/camera", [=](const TargetMap &map) {
milind-u09fb1252023-01-28 19:21:41 -080098 aos::distributed_clock::time_point pi_distributed_time =
99 reader->event_loop_factory()
milind-uf3ab8ba2023-02-04 17:56:16 -0800100 ->GetNodeEventLoopFactory(mapping_event_loop->node())
milind-u09fb1252023-01-28 19:21:41 -0800101 ->ToDistributedClock(aos::monotonic_clock::time_point(
102 aos::monotonic_clock::duration(map.monotonic_timestamp_ns())));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800103
milind-u09fb1252023-01-28 19:21:41 -0800104 HandleAprilTag(map, pi_distributed_time, timestamped_target_detections,
105 extrinsics);
106 });
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800107}
108
109void MappingMain(int argc, char *argv[]) {
110 std::vector<std::string> unsorted_logfiles =
111 aos::logger::FindLogs(argc, argv);
112
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800113 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
114
115 // open logfiles
116 aos::logger::LogReader reader(aos::logger::SortParts(unsorted_logfiles));
milind-uf3ab8ba2023-02-04 17:56:16 -0800117 // Send new april tag poses. This allows us to take a log of images, then play
118 // with the april detection code and see those changes take effect in mapping
119 constexpr size_t kNumPis = 4;
120 for (size_t i = 1; i <= kNumPis; i++) {
121 reader.RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i),
122 "frc971.vision.TargetMap");
milind-uc5a494f2023-02-24 15:39:22 -0800123 reader.RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i),
124 "foxglove.ImageAnnotations");
125 reader.RemapLoggedChannel(absl::StrFormat("/pi%u/constants", i),
126 "y2023.Constants");
milind-uf3ab8ba2023-02-04 17:56:16 -0800127 }
128
milind-uc5a494f2023-02-24 15:39:22 -0800129 reader.RemapLoggedChannel("/imu/constants", "y2023.Constants");
130
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800131 reader.Register();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800132
milind-uc5a494f2023-02-24 15:39:22 -0800133 SendSimulationConstants(reader.event_loop_factory(), FLAGS_team_number,
134 FLAGS_constants_path);
135
milind-u09fb1252023-01-28 19:21:41 -0800136 std::vector<std::unique_ptr<AprilRoboticsDetector>> detectors;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800137
138 const aos::Node *pi1 =
139 aos::configuration::GetNode(reader.configuration(), "pi1");
milind-uf3ab8ba2023-02-04 17:56:16 -0800140 std::unique_ptr<aos::EventLoop> pi1_detection_event_loop =
141 reader.event_loop_factory()->MakeEventLoop("pi1_detection", pi1);
142 std::unique_ptr<aos::EventLoop> pi1_mapping_event_loop =
143 reader.event_loop_factory()->MakeEventLoop("pi1_mapping", pi1);
144 HandlePiCaptures(pi1_detection_event_loop.get(), pi1_mapping_event_loop.get(),
145 &reader, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800146
147 const aos::Node *pi2 =
148 aos::configuration::GetNode(reader.configuration(), "pi2");
milind-uf3ab8ba2023-02-04 17:56:16 -0800149 std::unique_ptr<aos::EventLoop> pi2_detection_event_loop =
150 reader.event_loop_factory()->MakeEventLoop("pi2_detection", pi2);
151 std::unique_ptr<aos::EventLoop> pi2_mapping_event_loop =
152 reader.event_loop_factory()->MakeEventLoop("pi2_mapping", pi2);
153 HandlePiCaptures(pi2_detection_event_loop.get(), pi2_mapping_event_loop.get(),
154 &reader, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800155
156 const aos::Node *pi3 =
157 aos::configuration::GetNode(reader.configuration(), "pi3");
milind-uf3ab8ba2023-02-04 17:56:16 -0800158 std::unique_ptr<aos::EventLoop> pi3_detection_event_loop =
159 reader.event_loop_factory()->MakeEventLoop("pi3_detection", pi3);
160 std::unique_ptr<aos::EventLoop> pi3_mapping_event_loop =
161 reader.event_loop_factory()->MakeEventLoop("pi3_mapping", pi3);
162 HandlePiCaptures(pi3_detection_event_loop.get(), pi3_mapping_event_loop.get(),
163 &reader, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800164
165 const aos::Node *pi4 =
166 aos::configuration::GetNode(reader.configuration(), "pi4");
milind-uf3ab8ba2023-02-04 17:56:16 -0800167 std::unique_ptr<aos::EventLoop> pi4_detection_event_loop =
168 reader.event_loop_factory()->MakeEventLoop("pi4_detection", pi4);
169 std::unique_ptr<aos::EventLoop> pi4_mapping_event_loop =
170 reader.event_loop_factory()->MakeEventLoop("pi4_mapping", pi4);
171 HandlePiCaptures(pi4_detection_event_loop.get(), pi4_mapping_event_loop.get(),
172 &reader, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800173
174 reader.event_loop_factory()->Run();
175
176 auto target_constraints =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800177 DataAdapter::MatchTargetDetections(timestamped_target_detections);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800178
179 frc971::vision::TargetMapper mapper(FLAGS_json_path, target_constraints);
milind-uc5a494f2023-02-24 15:39:22 -0800180 mapper.Solve(FLAGS_field_name, FLAGS_output_dir);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800181
milind-u09fb1252023-01-28 19:21:41 -0800182 // Clean up all the pointers
183 for (auto &detector_ptr : detectors) {
184 detector_ptr.reset();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800185 }
186}
187
188} // namespace vision
milind-u16e3a082023-01-21 13:53:43 -0800189} // namespace y2023
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800190
191int main(int argc, char **argv) {
192 aos::InitGoogle(&argc, &argv);
milind-u16e3a082023-01-21 13:53:43 -0800193 y2023::vision::MappingMain(argc, argv);
Milind Upadhyay915d6002022-12-26 20:37:43 -0800194}