blob: c59414b4d0fcd3b795d1bffc503d23d4bd0079ff [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"
Jim Ostrowski68965cd2023-03-01 20:32:51 -08005#include "aos/util/mcap_logger.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -08006#include "frc971/control_loops/pose.h"
milind-u16e3a082023-01-21 13:53:43 -08007#include "frc971/vision/calibration_generated.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -08008#include "frc971/vision/charuco_lib.h"
9#include "frc971/vision/target_mapper.h"
10#include "opencv2/aruco.hpp"
11#include "opencv2/calib3d.hpp"
12#include "opencv2/core/eigen.hpp"
13#include "opencv2/features2d.hpp"
14#include "opencv2/highgui.hpp"
15#include "opencv2/highgui/highgui.hpp"
16#include "opencv2/imgproc.hpp"
milind-uc5a494f2023-02-24 15:39:22 -080017#include "y2023/constants/simulated_constants_sender.h"
milind-u09fb1252023-01-28 19:21:41 -080018#include "y2023/vision/aprilrobotics.h"
James Kuszmauld67f6d22023-02-05 17:37:25 -080019#include "y2023/vision/vision_util.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080020
milind-uc5a494f2023-02-24 15:39:22 -080021DEFINE_string(json_path, "y2023/vision/maps/target_map.json",
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080022 "Specify path for json with initial pose guesses.");
Jim Ostrowskiaec5dd22023-02-27 22:17:53 -080023DEFINE_string(config, "y2023/aos_config.json",
24 "Path to the config file to use.");
milind-uc5a494f2023-02-24 15:39:22 -080025DEFINE_string(constants_path, "y2023/constants/constants.json",
26 "Path to the constant file");
27DEFINE_string(output_dir, "y2023/vision/maps",
28 "Directory to write solved target map to");
29DEFINE_string(field_name, "charged_up",
30 "Field name, for the output json filename and flatbuffer field");
31DEFINE_int32(team_number, 7971,
32 "Use the calibration for a node with this team number");
Jim Ostrowski68965cd2023-03-01 20:32:51 -080033DEFINE_string(mcap_output_path, "/tmp/log.mcap", "Log to output.");
34DEFINE_string(pi, "pi1", "Pi name to generate mcap log for; defaults to pi1.");
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080035
milind-u16e3a082023-01-21 13:53:43 -080036namespace y2023 {
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080037namespace vision {
38using frc971::vision::DataAdapter;
milind-u16e3a082023-01-21 13:53:43 -080039using frc971::vision::ImageCallback;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080040using frc971::vision::PoseUtils;
milind-u09fb1252023-01-28 19:21:41 -080041using frc971::vision::TargetMap;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080042using frc971::vision::TargetMapper;
milind-u16e3a082023-01-21 13:53:43 -080043namespace calibration = frc971::vision::calibration;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080044
45// Change reference frame from camera to robot
milind-uee67abd2023-02-23 18:26:55 -080046Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080047 Eigen::Affine3d extrinsics) {
milind-uee67abd2023-02-23 18:26:55 -080048 const Eigen::Affine3d H_robot_camera = extrinsics;
49 const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080050 return H_robot_target;
51}
52
53// Add detected apriltag poses relative to the robot to
54// timestamped_target_detections
milind-u09fb1252023-01-28 19:21:41 -080055void HandleAprilTag(const TargetMap &map,
56 aos::distributed_clock::time_point pi_distributed_time,
Milind Upadhyay915d6002022-12-26 20:37:43 -080057 std::vector<DataAdapter::TimestampedDetection>
58 *timestamped_target_detections,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080059 Eigen::Affine3d extrinsics) {
milind-u3f5f83c2023-01-29 15:23:51 -080060 for (const auto *target_pose_fbs : *map.target_poses()) {
61 const TargetMapper::TargetPose target_pose =
62 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080063
milind-uee67abd2023-02-23 18:26:55 -080064 Eigen::Affine3d H_camera_target =
milind-u3f5f83c2023-01-29 15:23:51 -080065 Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080066 Eigen::Affine3d H_robot_target =
milind-uee67abd2023-02-23 18:26:55 -080067 CameraToRobotDetection(H_camera_target, extrinsics);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080068
Milind Upadhyayc5beba12022-12-17 17:41:20 -080069 ceres::examples::Pose3d target_pose_camera =
milind-uee67abd2023-02-23 18:26:55 -080070 PoseUtils::Affine3dToPose3d(H_camera_target);
Milind Upadhyayc5beba12022-12-17 17:41:20 -080071 double distance_from_camera = target_pose_camera.p.norm();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080072
milind-u09fb1252023-01-28 19:21:41 -080073 CHECK(map.has_monotonic_timestamp_ns())
74 << "Need detection timestamps for mapping";
75
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080076 timestamped_target_detections->emplace_back(
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080077 DataAdapter::TimestampedDetection{
78 .time = pi_distributed_time,
79 .H_robot_target = H_robot_target,
80 .distance_from_camera = distance_from_camera,
milind-u3f5f83c2023-01-29 15:23:51 -080081 .id = static_cast<TargetMapper::TargetId>(target_pose.id)});
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080082 }
83}
84
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080085// Get images from pi and pass apriltag positions to HandleAprilTag()
86void HandlePiCaptures(
milind-uf3ab8ba2023-02-04 17:56:16 -080087 aos::EventLoop *detection_event_loop, aos::EventLoop *mapping_event_loop,
88 aos::logger::LogReader *reader,
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080089 std::vector<DataAdapter::TimestampedDetection>
90 *timestamped_target_detections,
milind-u09fb1252023-01-28 19:21:41 -080091 std::vector<std::unique_ptr<AprilRoboticsDetector>> *detectors) {
milind-uf3ab8ba2023-02-04 17:56:16 -080092 static constexpr std::string_view kImageChannel = "/camera";
93 auto detector_ptr = std::make_unique<AprilRoboticsDetector>(
94 detection_event_loop, kImageChannel);
milind-uf2a4e322023-02-01 19:33:10 -080095 // Get the camera extrinsics
James Kuszmaul258e4ee2023-02-23 14:22:30 -080096 cv::Mat extrinsics_cv = detector_ptr->extrinsics().value();
milind-uf2a4e322023-02-01 19:33:10 -080097 Eigen::Matrix4d extrinsics_matrix;
98 cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
99 const auto extrinsics = Eigen::Affine3d(extrinsics_matrix);
100
101 detectors->emplace_back(std::move(detector_ptr));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800102
milind-uf3ab8ba2023-02-04 17:56:16 -0800103 mapping_event_loop->MakeWatcher("/camera", [=](const TargetMap &map) {
milind-u09fb1252023-01-28 19:21:41 -0800104 aos::distributed_clock::time_point pi_distributed_time =
105 reader->event_loop_factory()
milind-uf3ab8ba2023-02-04 17:56:16 -0800106 ->GetNodeEventLoopFactory(mapping_event_loop->node())
milind-u09fb1252023-01-28 19:21:41 -0800107 ->ToDistributedClock(aos::monotonic_clock::time_point(
108 aos::monotonic_clock::duration(map.monotonic_timestamp_ns())));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800109
milind-u09fb1252023-01-28 19:21:41 -0800110 HandleAprilTag(map, pi_distributed_time, timestamped_target_detections,
111 extrinsics);
112 });
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800113}
114
115void MappingMain(int argc, char *argv[]) {
116 std::vector<std::string> unsorted_logfiles =
117 aos::logger::FindLogs(argc, argv);
118
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800119 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
120
Jim Ostrowskiaec5dd22023-02-27 22:17:53 -0800121 aos::FlatbufferDetachedBuffer<aos::Configuration> config =
122 aos::configuration::ReadConfig(FLAGS_config);
123
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800124 // open logfiles
Jim Ostrowskiaec5dd22023-02-27 22:17:53 -0800125 aos::logger::LogReader reader(aos::logger::SortParts(unsorted_logfiles),
126 &config.message());
milind-uf3ab8ba2023-02-04 17:56:16 -0800127 // Send new april tag poses. This allows us to take a log of images, then play
128 // with the april detection code and see those changes take effect in mapping
129 constexpr size_t kNumPis = 4;
130 for (size_t i = 1; i <= kNumPis; i++) {
131 reader.RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i),
132 "frc971.vision.TargetMap");
milind-uc5a494f2023-02-24 15:39:22 -0800133 reader.RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i),
134 "foxglove.ImageAnnotations");
135 reader.RemapLoggedChannel(absl::StrFormat("/pi%u/constants", i),
136 "y2023.Constants");
milind-uf3ab8ba2023-02-04 17:56:16 -0800137 }
138
milind-uc5a494f2023-02-24 15:39:22 -0800139 reader.RemapLoggedChannel("/imu/constants", "y2023.Constants");
140
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800141 reader.Register();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800142
milind-uc5a494f2023-02-24 15:39:22 -0800143 SendSimulationConstants(reader.event_loop_factory(), FLAGS_team_number,
144 FLAGS_constants_path);
145
milind-u09fb1252023-01-28 19:21:41 -0800146 std::vector<std::unique_ptr<AprilRoboticsDetector>> detectors;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800147
148 const aos::Node *pi1 =
149 aos::configuration::GetNode(reader.configuration(), "pi1");
milind-uf3ab8ba2023-02-04 17:56:16 -0800150 std::unique_ptr<aos::EventLoop> pi1_detection_event_loop =
151 reader.event_loop_factory()->MakeEventLoop("pi1_detection", pi1);
152 std::unique_ptr<aos::EventLoop> pi1_mapping_event_loop =
153 reader.event_loop_factory()->MakeEventLoop("pi1_mapping", pi1);
154 HandlePiCaptures(pi1_detection_event_loop.get(), pi1_mapping_event_loop.get(),
155 &reader, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800156
157 const aos::Node *pi2 =
158 aos::configuration::GetNode(reader.configuration(), "pi2");
milind-uf3ab8ba2023-02-04 17:56:16 -0800159 std::unique_ptr<aos::EventLoop> pi2_detection_event_loop =
160 reader.event_loop_factory()->MakeEventLoop("pi2_detection", pi2);
161 std::unique_ptr<aos::EventLoop> pi2_mapping_event_loop =
162 reader.event_loop_factory()->MakeEventLoop("pi2_mapping", pi2);
163 HandlePiCaptures(pi2_detection_event_loop.get(), pi2_mapping_event_loop.get(),
164 &reader, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800165
166 const aos::Node *pi3 =
167 aos::configuration::GetNode(reader.configuration(), "pi3");
milind-uf3ab8ba2023-02-04 17:56:16 -0800168 std::unique_ptr<aos::EventLoop> pi3_detection_event_loop =
169 reader.event_loop_factory()->MakeEventLoop("pi3_detection", pi3);
170 std::unique_ptr<aos::EventLoop> pi3_mapping_event_loop =
171 reader.event_loop_factory()->MakeEventLoop("pi3_mapping", pi3);
172 HandlePiCaptures(pi3_detection_event_loop.get(), pi3_mapping_event_loop.get(),
173 &reader, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800174
175 const aos::Node *pi4 =
176 aos::configuration::GetNode(reader.configuration(), "pi4");
milind-uf3ab8ba2023-02-04 17:56:16 -0800177 std::unique_ptr<aos::EventLoop> pi4_detection_event_loop =
178 reader.event_loop_factory()->MakeEventLoop("pi4_detection", pi4);
179 std::unique_ptr<aos::EventLoop> pi4_mapping_event_loop =
180 reader.event_loop_factory()->MakeEventLoop("pi4_mapping", pi4);
181 HandlePiCaptures(pi4_detection_event_loop.get(), pi4_mapping_event_loop.get(),
182 &reader, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800183
Jim Ostrowski68965cd2023-03-01 20:32:51 -0800184 std::unique_ptr<aos::EventLoop> mcap_event_loop;
185 std::unique_ptr<aos::McapLogger> relogger;
186 if (!FLAGS_mcap_output_path.empty()) {
187 LOG(INFO) << "Writing out mcap file to " << FLAGS_mcap_output_path;
188 // TODO: Should make this work for any pi
189 const aos::Node *node =
190 aos::configuration::GetNode(reader.configuration(), FLAGS_pi);
191 reader.event_loop_factory()->GetNodeEventLoopFactory(node)->OnStartup(
192 [&relogger, &mcap_event_loop, &reader, node]() {
193 mcap_event_loop =
194 reader.event_loop_factory()->MakeEventLoop("mcap", node);
195 relogger = std::make_unique<aos::McapLogger>(
196 mcap_event_loop.get(), FLAGS_mcap_output_path,
197 aos::McapLogger::Serialization::kFlatbuffer,
198 aos::McapLogger::CanonicalChannelNames::kShortened,
199 aos::McapLogger::Compression::kLz4);
200 });
201 }
202
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800203 reader.event_loop_factory()->Run();
204
205 auto target_constraints =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800206 DataAdapter::MatchTargetDetections(timestamped_target_detections);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800207
208 frc971::vision::TargetMapper mapper(FLAGS_json_path, target_constraints);
milind-uc5a494f2023-02-24 15:39:22 -0800209 mapper.Solve(FLAGS_field_name, FLAGS_output_dir);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800210
milind-u09fb1252023-01-28 19:21:41 -0800211 // Clean up all the pointers
212 for (auto &detector_ptr : detectors) {
213 detector_ptr.reset();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800214 }
215}
216
217} // namespace vision
milind-u16e3a082023-01-21 13:53:43 -0800218} // namespace y2023
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800219
220int main(int argc, char **argv) {
221 aos::InitGoogle(&argc, &argv);
milind-u16e3a082023-01-21 13:53:43 -0800222 y2023::vision::MappingMain(argc, argv);
Milind Upadhyay915d6002022-12-26 20:37:43 -0800223}