blob: a1107943dbf47b43940403e9b76fe58448781248 [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"
Jim Ostrowski49be8232023-03-23 01:00:14 -070010#include "frc971/vision/visualize_robot.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080011#include "opencv2/aruco.hpp"
12#include "opencv2/calib3d.hpp"
13#include "opencv2/core/eigen.hpp"
14#include "opencv2/features2d.hpp"
15#include "opencv2/highgui.hpp"
16#include "opencv2/highgui/highgui.hpp"
17#include "opencv2/imgproc.hpp"
milind-uc5a494f2023-02-24 15:39:22 -080018#include "y2023/constants/simulated_constants_sender.h"
milind-u09fb1252023-01-28 19:21:41 -080019#include "y2023/vision/aprilrobotics.h"
James Kuszmauld67f6d22023-02-05 17:37:25 -080020#include "y2023/vision/vision_util.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080021
milind-uc5a494f2023-02-24 15:39:22 -080022DEFINE_string(json_path, "y2023/vision/maps/target_map.json",
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080023 "Specify path for json with initial pose guesses.");
milind-u4a5ef8a2023-03-05 14:10:23 -080024DEFINE_string(config, "",
25 "If set, override the log's config file with this one.");
milind-uc5a494f2023-02-24 15:39:22 -080026DEFINE_string(constants_path, "y2023/constants/constants.json",
27 "Path to the constant file");
28DEFINE_string(output_dir, "y2023/vision/maps",
29 "Directory to write solved target map to");
30DEFINE_string(field_name, "charged_up",
31 "Field name, for the output json filename and flatbuffer field");
Jim Ostrowski49be8232023-03-23 01:00:14 -070032DEFINE_int32(team_number, 0,
33 "Required: Use the calibration for a node with this team number");
Jim Ostrowski68965cd2023-03-01 20:32:51 -080034DEFINE_string(mcap_output_path, "/tmp/log.mcap", "Log to output.");
35DEFINE_string(pi, "pi1", "Pi name to generate mcap log for; defaults to pi1.");
milind-u5ddd5152023-03-04 15:19:17 -080036DEFINE_double(max_pose_error, 1e-6,
37 "Throw out target poses with a higher pose error than this");
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080038
milind-u16e3a082023-01-21 13:53:43 -080039namespace y2023 {
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080040namespace vision {
41using frc971::vision::DataAdapter;
milind-u16e3a082023-01-21 13:53:43 -080042using frc971::vision::ImageCallback;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080043using frc971::vision::PoseUtils;
milind-u09fb1252023-01-28 19:21:41 -080044using frc971::vision::TargetMap;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080045using frc971::vision::TargetMapper;
milind-u16e3a082023-01-21 13:53:43 -080046namespace calibration = frc971::vision::calibration;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080047
48// Change reference frame from camera to robot
milind-uee67abd2023-02-23 18:26:55 -080049Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080050 Eigen::Affine3d extrinsics) {
milind-uee67abd2023-02-23 18:26:55 -080051 const Eigen::Affine3d H_robot_camera = extrinsics;
52 const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080053 return H_robot_target;
54}
55
Jim Ostrowski49be8232023-03-23 01:00:14 -070056frc971::vision::VisualizeRobot vis_robot_;
57const int kImageWidth = 1000;
58
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080059// Add detected apriltag poses relative to the robot to
60// timestamped_target_detections
milind-u5ddd5152023-03-04 15:19:17 -080061void HandleAprilTags(const TargetMap &map,
62 aos::distributed_clock::time_point pi_distributed_time,
63 std::vector<DataAdapter::TimestampedDetection>
64 *timestamped_target_detections,
Jim Ostrowski49be8232023-03-23 01:00:14 -070065 Eigen::Affine3d extrinsics, std::string node_name,
66 frc971::vision::TargetMapper mapper) {
milind-u3f5f83c2023-01-29 15:23:51 -080067 for (const auto *target_pose_fbs : *map.target_poses()) {
milind-u5ddd5152023-03-04 15:19:17 -080068 // Skip detections with high pose errors
69 if (target_pose_fbs->pose_error() > FLAGS_max_pose_error) {
Jim Ostrowski49be8232023-03-23 01:00:14 -070070 LOG(INFO) << " Skipping tag " << target_pose_fbs->id()
71 << " due to pose error of " << target_pose_fbs->pose_error();
milind-u5ddd5152023-03-04 15:19:17 -080072 continue;
73 }
74
milind-u3f5f83c2023-01-29 15:23:51 -080075 const TargetMapper::TargetPose target_pose =
76 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080077
milind-uee67abd2023-02-23 18:26:55 -080078 Eigen::Affine3d H_camera_target =
milind-u3f5f83c2023-01-29 15:23:51 -080079 Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080080 Eigen::Affine3d H_robot_target =
milind-uee67abd2023-02-23 18:26:55 -080081 CameraToRobotDetection(H_camera_target, extrinsics);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080082
Milind Upadhyayc5beba12022-12-17 17:41:20 -080083 ceres::examples::Pose3d target_pose_camera =
milind-uee67abd2023-02-23 18:26:55 -080084 PoseUtils::Affine3dToPose3d(H_camera_target);
Milind Upadhyayc5beba12022-12-17 17:41:20 -080085 double distance_from_camera = target_pose_camera.p.norm();
milind-ud62f80a2023-03-04 16:37:09 -080086 double distortion_factor = target_pose_fbs->distortion_factor();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080087
milind-u09fb1252023-01-28 19:21:41 -080088 CHECK(map.has_monotonic_timestamp_ns())
89 << "Need detection timestamps for mapping";
90
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080091 timestamped_target_detections->emplace_back(
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080092 DataAdapter::TimestampedDetection{
93 .time = pi_distributed_time,
94 .H_robot_target = H_robot_target,
95 .distance_from_camera = distance_from_camera,
milind-ud62f80a2023-03-04 16:37:09 -080096 .distortion_factor = distortion_factor,
milind-u3f5f83c2023-01-29 15:23:51 -080097 .id = static_cast<TargetMapper::TargetId>(target_pose.id)});
Jim Ostrowski49be8232023-03-23 01:00:14 -070098
99 if (FLAGS_visualize) {
100 Eigen::Affine3d H_world_target = PoseUtils::Pose3dToAffine3d(
101 mapper.GetTargetPoseById(target_pose_fbs->id())->pose);
102 Eigen::Affine3d H_world_robot = H_world_target * H_robot_target.inverse();
103 Eigen::Affine3d H_world_camera =
104 H_world_target * H_camera_target.inverse();
105 LOG(INFO) << node_name << ", " << target_pose_fbs->id()
106 << ", t = " << pi_distributed_time
107 << ", pose_error = " << target_pose_fbs->pose_error()
108 << ", robot_pos (x,y,z) + "
109 << H_world_robot.translation().transpose();
110 vis_robot_.DrawRobotOutline(
111 H_world_robot, node_name + "-" +
112 std::to_string(target_pose_fbs->id()) + " " +
113 std::to_string(target_pose_fbs->pose_error() /
114 FLAGS_max_pose_error));
115 vis_robot_.DrawFrameAxes(H_world_camera, node_name);
116 vis_robot_.DrawFrameAxes(H_world_target,
117 std::to_string(target_pose_fbs->id()));
118 }
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800119 }
120}
121
milind-u5ddd5152023-03-04 15:19:17 -0800122// Get images from pi and pass apriltag positions to HandleAprilTags()
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800123void HandlePiCaptures(
milind-uf3ab8ba2023-02-04 17:56:16 -0800124 aos::EventLoop *detection_event_loop, aos::EventLoop *mapping_event_loop,
125 aos::logger::LogReader *reader,
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800126 std::vector<DataAdapter::TimestampedDetection>
127 *timestamped_target_detections,
milind-u09fb1252023-01-28 19:21:41 -0800128 std::vector<std::unique_ptr<AprilRoboticsDetector>> *detectors) {
milind-uf3ab8ba2023-02-04 17:56:16 -0800129 static constexpr std::string_view kImageChannel = "/camera";
130 auto detector_ptr = std::make_unique<AprilRoboticsDetector>(
131 detection_event_loop, kImageChannel);
milind-uf2a4e322023-02-01 19:33:10 -0800132 // Get the camera extrinsics
James Kuszmaul258e4ee2023-02-23 14:22:30 -0800133 cv::Mat extrinsics_cv = detector_ptr->extrinsics().value();
milind-uf2a4e322023-02-01 19:33:10 -0800134 Eigen::Matrix4d extrinsics_matrix;
135 cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
136 const auto extrinsics = Eigen::Affine3d(extrinsics_matrix);
137
138 detectors->emplace_back(std::move(detector_ptr));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800139
Jim Ostrowski49be8232023-03-23 01:00:14 -0700140 ceres::examples::VectorOfConstraints target_constraints;
141 frc971::vision::TargetMapper target_loc_mapper(FLAGS_json_path,
142 target_constraints);
143
milind-uf3ab8ba2023-02-04 17:56:16 -0800144 mapping_event_loop->MakeWatcher("/camera", [=](const TargetMap &map) {
milind-u09fb1252023-01-28 19:21:41 -0800145 aos::distributed_clock::time_point pi_distributed_time =
146 reader->event_loop_factory()
milind-uf3ab8ba2023-02-04 17:56:16 -0800147 ->GetNodeEventLoopFactory(mapping_event_loop->node())
milind-u09fb1252023-01-28 19:21:41 -0800148 ->ToDistributedClock(aos::monotonic_clock::time_point(
149 aos::monotonic_clock::duration(map.monotonic_timestamp_ns())));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800150
Jim Ostrowski49be8232023-03-23 01:00:14 -0700151 std::string node_name = detection_event_loop->node()->name()->str();
milind-u5ddd5152023-03-04 15:19:17 -0800152 HandleAprilTags(map, pi_distributed_time, timestamped_target_detections,
Jim Ostrowski49be8232023-03-23 01:00:14 -0700153 extrinsics, node_name, target_loc_mapper);
154 if (FLAGS_visualize) {
155 cv::imshow("View", vis_robot_.image_);
156 cv::waitKey();
157 cv::Mat image_mat =
158 cv::Mat::zeros(cv::Size(kImageWidth, kImageWidth), CV_8UC3);
159 vis_robot_.SetImage(image_mat);
160 }
milind-u09fb1252023-01-28 19:21:41 -0800161 });
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800162}
163
164void MappingMain(int argc, char *argv[]) {
165 std::vector<std::string> unsorted_logfiles =
166 aos::logger::FindLogs(argc, argv);
167
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800168 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
169
milind-u4a5ef8a2023-03-05 14:10:23 -0800170 std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config =
171 (FLAGS_config.empty()
172 ? std::nullopt
173 : std::make_optional(aos::configuration::ReadConfig(FLAGS_config)));
Jim Ostrowskiaec5dd22023-02-27 22:17:53 -0800174
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800175 // open logfiles
milind-u4a5ef8a2023-03-05 14:10:23 -0800176 aos::logger::LogReader reader(
177 aos::logger::SortParts(unsorted_logfiles),
178 config.has_value() ? &config->message() : nullptr);
milind-uf3ab8ba2023-02-04 17:56:16 -0800179 // Send new april tag poses. This allows us to take a log of images, then play
180 // with the april detection code and see those changes take effect in mapping
181 constexpr size_t kNumPis = 4;
182 for (size_t i = 1; i <= kNumPis; i++) {
183 reader.RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i),
184 "frc971.vision.TargetMap");
milind-uc5a494f2023-02-24 15:39:22 -0800185 reader.RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i),
186 "foxglove.ImageAnnotations");
187 reader.RemapLoggedChannel(absl::StrFormat("/pi%u/constants", i),
188 "y2023.Constants");
milind-uf3ab8ba2023-02-04 17:56:16 -0800189 }
190
milind-uc5a494f2023-02-24 15:39:22 -0800191 reader.RemapLoggedChannel("/imu/constants", "y2023.Constants");
192
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800193 reader.Register();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800194
milind-uc5a494f2023-02-24 15:39:22 -0800195 SendSimulationConstants(reader.event_loop_factory(), FLAGS_team_number,
196 FLAGS_constants_path);
197
milind-u09fb1252023-01-28 19:21:41 -0800198 std::vector<std::unique_ptr<AprilRoboticsDetector>> detectors;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800199
200 const aos::Node *pi1 =
201 aos::configuration::GetNode(reader.configuration(), "pi1");
milind-uf3ab8ba2023-02-04 17:56:16 -0800202 std::unique_ptr<aos::EventLoop> pi1_detection_event_loop =
203 reader.event_loop_factory()->MakeEventLoop("pi1_detection", pi1);
204 std::unique_ptr<aos::EventLoop> pi1_mapping_event_loop =
205 reader.event_loop_factory()->MakeEventLoop("pi1_mapping", pi1);
206 HandlePiCaptures(pi1_detection_event_loop.get(), pi1_mapping_event_loop.get(),
207 &reader, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800208
209 const aos::Node *pi2 =
210 aos::configuration::GetNode(reader.configuration(), "pi2");
milind-uf3ab8ba2023-02-04 17:56:16 -0800211 std::unique_ptr<aos::EventLoop> pi2_detection_event_loop =
212 reader.event_loop_factory()->MakeEventLoop("pi2_detection", pi2);
213 std::unique_ptr<aos::EventLoop> pi2_mapping_event_loop =
214 reader.event_loop_factory()->MakeEventLoop("pi2_mapping", pi2);
215 HandlePiCaptures(pi2_detection_event_loop.get(), pi2_mapping_event_loop.get(),
216 &reader, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800217
218 const aos::Node *pi3 =
219 aos::configuration::GetNode(reader.configuration(), "pi3");
milind-uf3ab8ba2023-02-04 17:56:16 -0800220 std::unique_ptr<aos::EventLoop> pi3_detection_event_loop =
221 reader.event_loop_factory()->MakeEventLoop("pi3_detection", pi3);
222 std::unique_ptr<aos::EventLoop> pi3_mapping_event_loop =
223 reader.event_loop_factory()->MakeEventLoop("pi3_mapping", pi3);
224 HandlePiCaptures(pi3_detection_event_loop.get(), pi3_mapping_event_loop.get(),
225 &reader, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800226
227 const aos::Node *pi4 =
228 aos::configuration::GetNode(reader.configuration(), "pi4");
milind-uf3ab8ba2023-02-04 17:56:16 -0800229 std::unique_ptr<aos::EventLoop> pi4_detection_event_loop =
230 reader.event_loop_factory()->MakeEventLoop("pi4_detection", pi4);
231 std::unique_ptr<aos::EventLoop> pi4_mapping_event_loop =
232 reader.event_loop_factory()->MakeEventLoop("pi4_mapping", pi4);
233 HandlePiCaptures(pi4_detection_event_loop.get(), pi4_mapping_event_loop.get(),
234 &reader, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800235
Jim Ostrowski68965cd2023-03-01 20:32:51 -0800236 std::unique_ptr<aos::EventLoop> mcap_event_loop;
237 std::unique_ptr<aos::McapLogger> relogger;
238 if (!FLAGS_mcap_output_path.empty()) {
239 LOG(INFO) << "Writing out mcap file to " << FLAGS_mcap_output_path;
Jim Ostrowski68965cd2023-03-01 20:32:51 -0800240 const aos::Node *node =
241 aos::configuration::GetNode(reader.configuration(), FLAGS_pi);
242 reader.event_loop_factory()->GetNodeEventLoopFactory(node)->OnStartup(
243 [&relogger, &mcap_event_loop, &reader, node]() {
244 mcap_event_loop =
245 reader.event_loop_factory()->MakeEventLoop("mcap", node);
246 relogger = std::make_unique<aos::McapLogger>(
247 mcap_event_loop.get(), FLAGS_mcap_output_path,
248 aos::McapLogger::Serialization::kFlatbuffer,
249 aos::McapLogger::CanonicalChannelNames::kShortened,
250 aos::McapLogger::Compression::kLz4);
251 });
252 }
253
Jim Ostrowski49be8232023-03-23 01:00:14 -0700254 if (FLAGS_visualize) {
255 cv::Mat image_mat =
256 cv::Mat::zeros(cv::Size(kImageWidth, kImageWidth), CV_8UC3);
257 vis_robot_.SetImage(image_mat);
258 const double kFocalLength = 500.0;
259 vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength);
260 }
261
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800262 reader.event_loop_factory()->Run();
263
264 auto target_constraints =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800265 DataAdapter::MatchTargetDetections(timestamped_target_detections);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800266
267 frc971::vision::TargetMapper mapper(FLAGS_json_path, target_constraints);
milind-uc5a494f2023-02-24 15:39:22 -0800268 mapper.Solve(FLAGS_field_name, FLAGS_output_dir);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800269
milind-u09fb1252023-01-28 19:21:41 -0800270 // Clean up all the pointers
271 for (auto &detector_ptr : detectors) {
272 detector_ptr.reset();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800273 }
274}
275
276} // namespace vision
milind-u16e3a082023-01-21 13:53:43 -0800277} // namespace y2023
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800278
279int main(int argc, char **argv) {
280 aos::InitGoogle(&argc, &argv);
milind-u16e3a082023-01-21 13:53:43 -0800281 y2023::vision::MappingMain(argc, argv);
Milind Upadhyay915d6002022-12-26 20:37:43 -0800282}