blob: e399470d677ff1ea67e5907b9ec5b4aca5b25fa1 [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-u5ddd5152023-03-04 15:19:17 -080035DEFINE_double(max_pose_error, 1e-6,
36 "Throw out target poses with a higher pose error than this");
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080037
milind-u16e3a082023-01-21 13:53:43 -080038namespace y2023 {
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080039namespace vision {
40using frc971::vision::DataAdapter;
milind-u16e3a082023-01-21 13:53:43 -080041using frc971::vision::ImageCallback;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080042using frc971::vision::PoseUtils;
milind-u09fb1252023-01-28 19:21:41 -080043using frc971::vision::TargetMap;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080044using frc971::vision::TargetMapper;
milind-u16e3a082023-01-21 13:53:43 -080045namespace calibration = frc971::vision::calibration;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080046
47// Change reference frame from camera to robot
milind-uee67abd2023-02-23 18:26:55 -080048Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080049 Eigen::Affine3d extrinsics) {
milind-uee67abd2023-02-23 18:26:55 -080050 const Eigen::Affine3d H_robot_camera = extrinsics;
51 const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080052 return H_robot_target;
53}
54
55// Add detected apriltag poses relative to the robot to
56// timestamped_target_detections
milind-u5ddd5152023-03-04 15:19:17 -080057void HandleAprilTags(const TargetMap &map,
58 aos::distributed_clock::time_point pi_distributed_time,
59 std::vector<DataAdapter::TimestampedDetection>
60 *timestamped_target_detections,
61 Eigen::Affine3d extrinsics) {
milind-u3f5f83c2023-01-29 15:23:51 -080062 for (const auto *target_pose_fbs : *map.target_poses()) {
milind-u5ddd5152023-03-04 15:19:17 -080063 // Skip detections with high pose errors
64 if (target_pose_fbs->pose_error() > FLAGS_max_pose_error) {
65 continue;
66 }
67
milind-u3f5f83c2023-01-29 15:23:51 -080068 const TargetMapper::TargetPose target_pose =
69 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080070
milind-uee67abd2023-02-23 18:26:55 -080071 Eigen::Affine3d H_camera_target =
milind-u3f5f83c2023-01-29 15:23:51 -080072 Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080073 Eigen::Affine3d H_robot_target =
milind-uee67abd2023-02-23 18:26:55 -080074 CameraToRobotDetection(H_camera_target, extrinsics);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080075
Milind Upadhyayc5beba12022-12-17 17:41:20 -080076 ceres::examples::Pose3d target_pose_camera =
milind-uee67abd2023-02-23 18:26:55 -080077 PoseUtils::Affine3dToPose3d(H_camera_target);
Milind Upadhyayc5beba12022-12-17 17:41:20 -080078 double distance_from_camera = target_pose_camera.p.norm();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080079
milind-u09fb1252023-01-28 19:21:41 -080080 CHECK(map.has_monotonic_timestamp_ns())
81 << "Need detection timestamps for mapping";
82
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080083 timestamped_target_detections->emplace_back(
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080084 DataAdapter::TimestampedDetection{
85 .time = pi_distributed_time,
86 .H_robot_target = H_robot_target,
87 .distance_from_camera = distance_from_camera,
milind-u3f5f83c2023-01-29 15:23:51 -080088 .id = static_cast<TargetMapper::TargetId>(target_pose.id)});
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080089 }
90}
91
milind-u5ddd5152023-03-04 15:19:17 -080092// Get images from pi and pass apriltag positions to HandleAprilTags()
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080093void HandlePiCaptures(
milind-uf3ab8ba2023-02-04 17:56:16 -080094 aos::EventLoop *detection_event_loop, aos::EventLoop *mapping_event_loop,
95 aos::logger::LogReader *reader,
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080096 std::vector<DataAdapter::TimestampedDetection>
97 *timestamped_target_detections,
milind-u09fb1252023-01-28 19:21:41 -080098 std::vector<std::unique_ptr<AprilRoboticsDetector>> *detectors) {
milind-uf3ab8ba2023-02-04 17:56:16 -080099 static constexpr std::string_view kImageChannel = "/camera";
100 auto detector_ptr = std::make_unique<AprilRoboticsDetector>(
101 detection_event_loop, kImageChannel);
milind-uf2a4e322023-02-01 19:33:10 -0800102 // Get the camera extrinsics
James Kuszmaul258e4ee2023-02-23 14:22:30 -0800103 cv::Mat extrinsics_cv = detector_ptr->extrinsics().value();
milind-uf2a4e322023-02-01 19:33:10 -0800104 Eigen::Matrix4d extrinsics_matrix;
105 cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
106 const auto extrinsics = Eigen::Affine3d(extrinsics_matrix);
107
108 detectors->emplace_back(std::move(detector_ptr));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800109
milind-uf3ab8ba2023-02-04 17:56:16 -0800110 mapping_event_loop->MakeWatcher("/camera", [=](const TargetMap &map) {
milind-u09fb1252023-01-28 19:21:41 -0800111 aos::distributed_clock::time_point pi_distributed_time =
112 reader->event_loop_factory()
milind-uf3ab8ba2023-02-04 17:56:16 -0800113 ->GetNodeEventLoopFactory(mapping_event_loop->node())
milind-u09fb1252023-01-28 19:21:41 -0800114 ->ToDistributedClock(aos::monotonic_clock::time_point(
115 aos::monotonic_clock::duration(map.monotonic_timestamp_ns())));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800116
milind-u5ddd5152023-03-04 15:19:17 -0800117 HandleAprilTags(map, pi_distributed_time, timestamped_target_detections,
118 extrinsics);
milind-u09fb1252023-01-28 19:21:41 -0800119 });
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800120}
121
122void MappingMain(int argc, char *argv[]) {
123 std::vector<std::string> unsorted_logfiles =
124 aos::logger::FindLogs(argc, argv);
125
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800126 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
127
Jim Ostrowskiaec5dd22023-02-27 22:17:53 -0800128 aos::FlatbufferDetachedBuffer<aos::Configuration> config =
129 aos::configuration::ReadConfig(FLAGS_config);
130
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800131 // open logfiles
Jim Ostrowskiaec5dd22023-02-27 22:17:53 -0800132 aos::logger::LogReader reader(aos::logger::SortParts(unsorted_logfiles),
133 &config.message());
milind-uf3ab8ba2023-02-04 17:56:16 -0800134 // Send new april tag poses. This allows us to take a log of images, then play
135 // with the april detection code and see those changes take effect in mapping
136 constexpr size_t kNumPis = 4;
137 for (size_t i = 1; i <= kNumPis; i++) {
138 reader.RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i),
139 "frc971.vision.TargetMap");
milind-uc5a494f2023-02-24 15:39:22 -0800140 reader.RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i),
141 "foxglove.ImageAnnotations");
142 reader.RemapLoggedChannel(absl::StrFormat("/pi%u/constants", i),
143 "y2023.Constants");
milind-uf3ab8ba2023-02-04 17:56:16 -0800144 }
145
milind-uc5a494f2023-02-24 15:39:22 -0800146 reader.RemapLoggedChannel("/imu/constants", "y2023.Constants");
147
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800148 reader.Register();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800149
milind-uc5a494f2023-02-24 15:39:22 -0800150 SendSimulationConstants(reader.event_loop_factory(), FLAGS_team_number,
151 FLAGS_constants_path);
152
milind-u09fb1252023-01-28 19:21:41 -0800153 std::vector<std::unique_ptr<AprilRoboticsDetector>> detectors;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800154
155 const aos::Node *pi1 =
156 aos::configuration::GetNode(reader.configuration(), "pi1");
milind-uf3ab8ba2023-02-04 17:56:16 -0800157 std::unique_ptr<aos::EventLoop> pi1_detection_event_loop =
158 reader.event_loop_factory()->MakeEventLoop("pi1_detection", pi1);
159 std::unique_ptr<aos::EventLoop> pi1_mapping_event_loop =
160 reader.event_loop_factory()->MakeEventLoop("pi1_mapping", pi1);
161 HandlePiCaptures(pi1_detection_event_loop.get(), pi1_mapping_event_loop.get(),
162 &reader, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800163
164 const aos::Node *pi2 =
165 aos::configuration::GetNode(reader.configuration(), "pi2");
milind-uf3ab8ba2023-02-04 17:56:16 -0800166 std::unique_ptr<aos::EventLoop> pi2_detection_event_loop =
167 reader.event_loop_factory()->MakeEventLoop("pi2_detection", pi2);
168 std::unique_ptr<aos::EventLoop> pi2_mapping_event_loop =
169 reader.event_loop_factory()->MakeEventLoop("pi2_mapping", pi2);
170 HandlePiCaptures(pi2_detection_event_loop.get(), pi2_mapping_event_loop.get(),
171 &reader, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800172
173 const aos::Node *pi3 =
174 aos::configuration::GetNode(reader.configuration(), "pi3");
milind-uf3ab8ba2023-02-04 17:56:16 -0800175 std::unique_ptr<aos::EventLoop> pi3_detection_event_loop =
176 reader.event_loop_factory()->MakeEventLoop("pi3_detection", pi3);
177 std::unique_ptr<aos::EventLoop> pi3_mapping_event_loop =
178 reader.event_loop_factory()->MakeEventLoop("pi3_mapping", pi3);
179 HandlePiCaptures(pi3_detection_event_loop.get(), pi3_mapping_event_loop.get(),
180 &reader, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800181
182 const aos::Node *pi4 =
183 aos::configuration::GetNode(reader.configuration(), "pi4");
milind-uf3ab8ba2023-02-04 17:56:16 -0800184 std::unique_ptr<aos::EventLoop> pi4_detection_event_loop =
185 reader.event_loop_factory()->MakeEventLoop("pi4_detection", pi4);
186 std::unique_ptr<aos::EventLoop> pi4_mapping_event_loop =
187 reader.event_loop_factory()->MakeEventLoop("pi4_mapping", pi4);
188 HandlePiCaptures(pi4_detection_event_loop.get(), pi4_mapping_event_loop.get(),
189 &reader, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800190
Jim Ostrowski68965cd2023-03-01 20:32:51 -0800191 std::unique_ptr<aos::EventLoop> mcap_event_loop;
192 std::unique_ptr<aos::McapLogger> relogger;
193 if (!FLAGS_mcap_output_path.empty()) {
194 LOG(INFO) << "Writing out mcap file to " << FLAGS_mcap_output_path;
195 // TODO: Should make this work for any pi
196 const aos::Node *node =
197 aos::configuration::GetNode(reader.configuration(), FLAGS_pi);
198 reader.event_loop_factory()->GetNodeEventLoopFactory(node)->OnStartup(
199 [&relogger, &mcap_event_loop, &reader, node]() {
200 mcap_event_loop =
201 reader.event_loop_factory()->MakeEventLoop("mcap", node);
202 relogger = std::make_unique<aos::McapLogger>(
203 mcap_event_loop.get(), FLAGS_mcap_output_path,
204 aos::McapLogger::Serialization::kFlatbuffer,
205 aos::McapLogger::CanonicalChannelNames::kShortened,
206 aos::McapLogger::Compression::kLz4);
207 });
208 }
209
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800210 reader.event_loop_factory()->Run();
211
212 auto target_constraints =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800213 DataAdapter::MatchTargetDetections(timestamped_target_detections);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800214
215 frc971::vision::TargetMapper mapper(FLAGS_json_path, target_constraints);
milind-uc5a494f2023-02-24 15:39:22 -0800216 mapper.Solve(FLAGS_field_name, FLAGS_output_dir);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800217
milind-u09fb1252023-01-28 19:21:41 -0800218 // Clean up all the pointers
219 for (auto &detector_ptr : detectors) {
220 detector_ptr.reset();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800221 }
222}
223
224} // namespace vision
milind-u16e3a082023-01-21 13:53:43 -0800225} // namespace y2023
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800226
227int main(int argc, char **argv) {
228 aos::InitGoogle(&argc, &argv);
milind-u16e3a082023-01-21 13:53:43 -0800229 y2023::vision::MappingMain(argc, argv);
Milind Upadhyay915d6002022-12-26 20:37:43 -0800230}