blob: 8861e2e6da79e7263c8d264c40cce5107a9a618d [file] [log] [blame]
Jim Ostrowskiaec5dd22023-02-27 22:17:53 -08001#include "aos/configuration.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -08002#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-u16e3a082023-01-21 13:53:43 -08006#include "frc971/vision/calibration_generated.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -08007#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-uc5a494f2023-02-24 15:39:22 -080016#include "y2023/constants/simulated_constants_sender.h"
milind-u09fb1252023-01-28 19:21:41 -080017#include "y2023/vision/aprilrobotics.h"
James Kuszmauld67f6d22023-02-05 17:37:25 -080018#include "y2023/vision/vision_util.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080019
milind-uc5a494f2023-02-24 15:39:22 -080020DEFINE_string(json_path, "y2023/vision/maps/target_map.json",
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080021 "Specify path for json with initial pose guesses.");
Jim Ostrowskiaec5dd22023-02-27 22:17:53 -080022DEFINE_string(config, "y2023/aos_config.json",
23 "Path to the config file to use.");
milind-uc5a494f2023-02-24 15:39:22 -080024DEFINE_string(constants_path, "y2023/constants/constants.json",
25 "Path to the constant file");
26DEFINE_string(output_dir, "y2023/vision/maps",
27 "Directory to write solved target map to");
28DEFINE_string(field_name, "charged_up",
29 "Field name, for the output json filename and flatbuffer field");
30DEFINE_int32(team_number, 7971,
31 "Use the calibration for a node with this team number");
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080032
milind-u16e3a082023-01-21 13:53:43 -080033namespace y2023 {
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080034namespace vision {
35using frc971::vision::DataAdapter;
milind-u16e3a082023-01-21 13:53:43 -080036using frc971::vision::ImageCallback;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080037using frc971::vision::PoseUtils;
milind-u09fb1252023-01-28 19:21:41 -080038using frc971::vision::TargetMap;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080039using frc971::vision::TargetMapper;
milind-u16e3a082023-01-21 13:53:43 -080040namespace calibration = frc971::vision::calibration;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080041
42// Change reference frame from camera to robot
milind-uee67abd2023-02-23 18:26:55 -080043Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080044 Eigen::Affine3d extrinsics) {
milind-uee67abd2023-02-23 18:26:55 -080045 const Eigen::Affine3d H_robot_camera = extrinsics;
46 const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080047 return H_robot_target;
48}
49
50// Add detected apriltag poses relative to the robot to
51// timestamped_target_detections
milind-u09fb1252023-01-28 19:21:41 -080052void HandleAprilTag(const TargetMap &map,
53 aos::distributed_clock::time_point pi_distributed_time,
Milind Upadhyay915d6002022-12-26 20:37:43 -080054 std::vector<DataAdapter::TimestampedDetection>
55 *timestamped_target_detections,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080056 Eigen::Affine3d extrinsics) {
milind-u3f5f83c2023-01-29 15:23:51 -080057 for (const auto *target_pose_fbs : *map.target_poses()) {
58 const TargetMapper::TargetPose target_pose =
59 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080060
milind-uee67abd2023-02-23 18:26:55 -080061 Eigen::Affine3d H_camera_target =
milind-u3f5f83c2023-01-29 15:23:51 -080062 Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080063 Eigen::Affine3d H_robot_target =
milind-uee67abd2023-02-23 18:26:55 -080064 CameraToRobotDetection(H_camera_target, extrinsics);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080065
Milind Upadhyayc5beba12022-12-17 17:41:20 -080066 ceres::examples::Pose3d target_pose_camera =
milind-uee67abd2023-02-23 18:26:55 -080067 PoseUtils::Affine3dToPose3d(H_camera_target);
Milind Upadhyayc5beba12022-12-17 17:41:20 -080068 double distance_from_camera = target_pose_camera.p.norm();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080069
milind-u09fb1252023-01-28 19:21:41 -080070 CHECK(map.has_monotonic_timestamp_ns())
71 << "Need detection timestamps for mapping";
72
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080073 timestamped_target_detections->emplace_back(
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080074 DataAdapter::TimestampedDetection{
75 .time = pi_distributed_time,
76 .H_robot_target = H_robot_target,
77 .distance_from_camera = distance_from_camera,
milind-u3f5f83c2023-01-29 15:23:51 -080078 .id = static_cast<TargetMapper::TargetId>(target_pose.id)});
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080079 }
80}
81
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080082// Get images from pi and pass apriltag positions to HandleAprilTag()
83void HandlePiCaptures(
milind-uf3ab8ba2023-02-04 17:56:16 -080084 aos::EventLoop *detection_event_loop, aos::EventLoop *mapping_event_loop,
85 aos::logger::LogReader *reader,
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080086 std::vector<DataAdapter::TimestampedDetection>
87 *timestamped_target_detections,
milind-u09fb1252023-01-28 19:21:41 -080088 std::vector<std::unique_ptr<AprilRoboticsDetector>> *detectors) {
milind-uf3ab8ba2023-02-04 17:56:16 -080089 static constexpr std::string_view kImageChannel = "/camera";
90 auto detector_ptr = std::make_unique<AprilRoboticsDetector>(
91 detection_event_loop, kImageChannel);
milind-uf2a4e322023-02-01 19:33:10 -080092 // Get the camera extrinsics
James Kuszmaul258e4ee2023-02-23 14:22:30 -080093 cv::Mat extrinsics_cv = detector_ptr->extrinsics().value();
milind-uf2a4e322023-02-01 19:33:10 -080094 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 Chainanid5c7f0d2022-11-19 17:05:57 -080099
milind-uf3ab8ba2023-02-04 17:56:16 -0800100 mapping_event_loop->MakeWatcher("/camera", [=](const TargetMap &map) {
milind-u09fb1252023-01-28 19:21:41 -0800101 aos::distributed_clock::time_point pi_distributed_time =
102 reader->event_loop_factory()
milind-uf3ab8ba2023-02-04 17:56:16 -0800103 ->GetNodeEventLoopFactory(mapping_event_loop->node())
milind-u09fb1252023-01-28 19:21:41 -0800104 ->ToDistributedClock(aos::monotonic_clock::time_point(
105 aos::monotonic_clock::duration(map.monotonic_timestamp_ns())));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800106
milind-u09fb1252023-01-28 19:21:41 -0800107 HandleAprilTag(map, pi_distributed_time, timestamped_target_detections,
108 extrinsics);
109 });
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800110}
111
112void MappingMain(int argc, char *argv[]) {
113 std::vector<std::string> unsorted_logfiles =
114 aos::logger::FindLogs(argc, argv);
115
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800116 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
117
Jim Ostrowskiaec5dd22023-02-27 22:17:53 -0800118 aos::FlatbufferDetachedBuffer<aos::Configuration> config =
119 aos::configuration::ReadConfig(FLAGS_config);
120
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800121 // open logfiles
Jim Ostrowskiaec5dd22023-02-27 22:17:53 -0800122 aos::logger::LogReader reader(aos::logger::SortParts(unsorted_logfiles),
123 &config.message());
milind-uf3ab8ba2023-02-04 17:56:16 -0800124 // 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-uc5a494f2023-02-24 15:39:22 -0800130 reader.RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i),
131 "foxglove.ImageAnnotations");
132 reader.RemapLoggedChannel(absl::StrFormat("/pi%u/constants", i),
133 "y2023.Constants");
milind-uf3ab8ba2023-02-04 17:56:16 -0800134 }
135
milind-uc5a494f2023-02-24 15:39:22 -0800136 reader.RemapLoggedChannel("/imu/constants", "y2023.Constants");
137
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800138 reader.Register();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800139
milind-uc5a494f2023-02-24 15:39:22 -0800140 SendSimulationConstants(reader.event_loop_factory(), FLAGS_team_number,
141 FLAGS_constants_path);
142
milind-u09fb1252023-01-28 19:21:41 -0800143 std::vector<std::unique_ptr<AprilRoboticsDetector>> detectors;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800144
145 const aos::Node *pi1 =
146 aos::configuration::GetNode(reader.configuration(), "pi1");
milind-uf3ab8ba2023-02-04 17:56:16 -0800147 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, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800153
154 const aos::Node *pi2 =
155 aos::configuration::GetNode(reader.configuration(), "pi2");
milind-uf3ab8ba2023-02-04 17:56:16 -0800156 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, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800162
163 const aos::Node *pi3 =
164 aos::configuration::GetNode(reader.configuration(), "pi3");
milind-uf3ab8ba2023-02-04 17:56:16 -0800165 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, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800171
172 const aos::Node *pi4 =
173 aos::configuration::GetNode(reader.configuration(), "pi4");
milind-uf3ab8ba2023-02-04 17:56:16 -0800174 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, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800180
181 reader.event_loop_factory()->Run();
182
183 auto target_constraints =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800184 DataAdapter::MatchTargetDetections(timestamped_target_detections);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800185
186 frc971::vision::TargetMapper mapper(FLAGS_json_path, target_constraints);
milind-uc5a494f2023-02-24 15:39:22 -0800187 mapper.Solve(FLAGS_field_name, FLAGS_output_dir);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800188
milind-u09fb1252023-01-28 19:21:41 -0800189 // Clean up all the pointers
190 for (auto &detector_ptr : detectors) {
191 detector_ptr.reset();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800192 }
193}
194
195} // namespace vision
milind-u16e3a082023-01-21 13:53:43 -0800196} // namespace y2023
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800197
198int main(int argc, char **argv) {
199 aos::InitGoogle(&argc, &argv);
milind-u16e3a082023-01-21 13:53:43 -0800200 y2023::vision::MappingMain(argc, argv);
Milind Upadhyay915d6002022-12-26 20:37:43 -0800201}