blob: e9ef6627252e547d9af46f1cb9bccb065eeca3f2 [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-ude9045f2023-03-25 18:17:12 -070038DEFINE_double(
39 max_pose_error_ratio, 0.4,
40 "Throw out target poses with a higher pose error ratio than this");
milind-ua30a4a12023-03-24 20:49:41 -070041DEFINE_uint64(wait_key, 0,
42 "Time in ms to wait between images, if no click (0 to wait "
43 "indefinitely until click).");
milind-ude9045f2023-03-25 18:17:12 -070044DEFINE_uint64(skip_to, 1,
45 "Start at combined image of this number (1 is the first image)");
milind-ua30a4a12023-03-24 20:49:41 -070046DEFINE_bool(solve, true, "Whether to solve for the field's target map.");
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080047
milind-u16e3a082023-01-21 13:53:43 -080048namespace y2023 {
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080049namespace vision {
50using frc971::vision::DataAdapter;
milind-u16e3a082023-01-21 13:53:43 -080051using frc971::vision::ImageCallback;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080052using frc971::vision::PoseUtils;
milind-u09fb1252023-01-28 19:21:41 -080053using frc971::vision::TargetMap;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080054using frc971::vision::TargetMapper;
milind-ua30a4a12023-03-24 20:49:41 -070055using frc971::vision::VisualizeRobot;
milind-u16e3a082023-01-21 13:53:43 -080056namespace calibration = frc971::vision::calibration;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080057
58// Change reference frame from camera to robot
milind-uee67abd2023-02-23 18:26:55 -080059Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080060 Eigen::Affine3d extrinsics) {
milind-uee67abd2023-02-23 18:26:55 -080061 const Eigen::Affine3d H_robot_camera = extrinsics;
62 const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080063 return H_robot_target;
64}
65
Jim Ostrowski49be8232023-03-23 01:00:14 -070066const int kImageWidth = 1000;
milind-ua30a4a12023-03-24 20:49:41 -070067// Map from pi node name to color for drawing
68const std::map<std::string, cv::Scalar> kPiColors = {
69 {"pi1", cv::Scalar(255, 0, 255)},
70 {"pi2", cv::Scalar(255, 255, 0)},
71 {"pi3", cv::Scalar(0, 255, 255)},
72 {"pi4", cv::Scalar(255, 165, 0)},
73};
Jim Ostrowski49be8232023-03-23 01:00:14 -070074
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080075// Add detected apriltag poses relative to the robot to
76// timestamped_target_detections
milind-u5ddd5152023-03-04 15:19:17 -080077void HandleAprilTags(const TargetMap &map,
78 aos::distributed_clock::time_point pi_distributed_time,
79 std::vector<DataAdapter::TimestampedDetection>
80 *timestamped_target_detections,
Jim Ostrowski49be8232023-03-23 01:00:14 -070081 Eigen::Affine3d extrinsics, std::string node_name,
milind-ua30a4a12023-03-24 20:49:41 -070082 frc971::vision::TargetMapper target_loc_mapper,
83 std::set<std::string> *drawn_nodes,
84 VisualizeRobot *vis_robot, size_t *display_count) {
85 bool drew = false;
86 std::stringstream label;
87 label << node_name << " - ";
88
milind-u3f5f83c2023-01-29 15:23:51 -080089 for (const auto *target_pose_fbs : *map.target_poses()) {
milind-u5ddd5152023-03-04 15:19:17 -080090 // Skip detections with high pose errors
91 if (target_pose_fbs->pose_error() > FLAGS_max_pose_error) {
milind-ude9045f2023-03-25 18:17:12 -070092 VLOG(1) << " Skipping tag " << target_pose_fbs->id()
93 << " due to pose error of " << target_pose_fbs->pose_error();
94 continue;
95 }
96 // Skip detections with high pose error ratios
97 if (target_pose_fbs->pose_error_ratio() > FLAGS_max_pose_error_ratio) {
98 VLOG(1) << " Skipping tag " << target_pose_fbs->id()
99 << " due to pose error ratio of "
100 << target_pose_fbs->pose_error_ratio();
milind-u5ddd5152023-03-04 15:19:17 -0800101 continue;
102 }
103
milind-u3f5f83c2023-01-29 15:23:51 -0800104 const TargetMapper::TargetPose target_pose =
105 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800106
milind-uee67abd2023-02-23 18:26:55 -0800107 Eigen::Affine3d H_camera_target =
milind-u3f5f83c2023-01-29 15:23:51 -0800108 Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800109 Eigen::Affine3d H_robot_target =
milind-uee67abd2023-02-23 18:26:55 -0800110 CameraToRobotDetection(H_camera_target, extrinsics);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800111
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800112 ceres::examples::Pose3d target_pose_camera =
milind-uee67abd2023-02-23 18:26:55 -0800113 PoseUtils::Affine3dToPose3d(H_camera_target);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800114 double distance_from_camera = target_pose_camera.p.norm();
milind-ud62f80a2023-03-04 16:37:09 -0800115 double distortion_factor = target_pose_fbs->distortion_factor();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800116
milind-u09fb1252023-01-28 19:21:41 -0800117 CHECK(map.has_monotonic_timestamp_ns())
118 << "Need detection timestamps for mapping";
119
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800120 timestamped_target_detections->emplace_back(
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800121 DataAdapter::TimestampedDetection{
122 .time = pi_distributed_time,
123 .H_robot_target = H_robot_target,
124 .distance_from_camera = distance_from_camera,
milind-ud62f80a2023-03-04 16:37:09 -0800125 .distortion_factor = distortion_factor,
milind-u3f5f83c2023-01-29 15:23:51 -0800126 .id = static_cast<TargetMapper::TargetId>(target_pose.id)});
Jim Ostrowski49be8232023-03-23 01:00:14 -0700127
128 if (FLAGS_visualize) {
milind-ua30a4a12023-03-24 20:49:41 -0700129 // If we've already drawn in the current image,
130 // display it before clearing and adding the new poses
131 if (drawn_nodes->count(node_name) != 0) {
132 (*display_count)++;
133 cv::putText(vis_robot->image_,
134 "Poses #" + std::to_string(*display_count),
135 cv::Point(600, 10), cv::FONT_HERSHEY_PLAIN, 1.0,
136 cv::Scalar(255, 255, 255));
137
milind-ude9045f2023-03-25 18:17:12 -0700138 if (*display_count >= FLAGS_skip_to) {
139 cv::imshow("View", vis_robot->image_);
140 cv::waitKey(FLAGS_wait_key);
141 } else {
142 VLOG(1) << "At poses #" << std::to_string(*display_count);
143 }
milind-ua30a4a12023-03-24 20:49:41 -0700144 vis_robot->ClearImage();
145 drawn_nodes->clear();
146 }
147
Jim Ostrowski49be8232023-03-23 01:00:14 -0700148 Eigen::Affine3d H_world_target = PoseUtils::Pose3dToAffine3d(
milind-ua30a4a12023-03-24 20:49:41 -0700149 target_loc_mapper.GetTargetPoseById(target_pose_fbs->id())->pose);
Jim Ostrowski49be8232023-03-23 01:00:14 -0700150 Eigen::Affine3d H_world_robot = H_world_target * H_robot_target.inverse();
milind-ude9045f2023-03-25 18:17:12 -0700151 VLOG(2) << node_name << ", " << target_pose_fbs->id()
152 << ", t = " << pi_distributed_time
153 << ", pose_error = " << target_pose_fbs->pose_error()
154 << ", pose_error_ratio = " << target_pose_fbs->pose_error_ratio()
155 << ", robot_pos (x,y,z) + "
156 << H_world_robot.translation().transpose();
milind-ua30a4a12023-03-24 20:49:41 -0700157
158 label << "id " << target_pose_fbs->id() << ": err "
milind-ude9045f2023-03-25 18:17:12 -0700159 << (target_pose_fbs->pose_error() / FLAGS_max_pose_error)
160 << " ratio " << target_pose_fbs->pose_error_ratio() << " ";
milind-ua30a4a12023-03-24 20:49:41 -0700161
162 vis_robot->DrawRobotOutline(H_world_robot,
163 std::to_string(target_pose_fbs->id()),
164 kPiColors.at(node_name));
165
166 vis_robot->DrawFrameAxes(H_world_target,
167 std::to_string(target_pose_fbs->id()),
168 kPiColors.at(node_name));
169 drew = true;
Jim Ostrowski49be8232023-03-23 01:00:14 -0700170 }
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800171 }
milind-ua30a4a12023-03-24 20:49:41 -0700172 if (drew) {
173 size_t pi_number =
174 static_cast<size_t>(node_name[node_name.size() - 1] - '0');
175 cv::putText(vis_robot->image_, label.str(),
176 cv::Point(10, 10 + 20 * pi_number), cv::FONT_HERSHEY_PLAIN, 1.0,
177 kPiColors.at(node_name));
178
179 drawn_nodes->emplace(node_name);
180 }
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800181}
182
milind-u5ddd5152023-03-04 15:19:17 -0800183// Get images from pi and pass apriltag positions to HandleAprilTags()
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800184void HandlePiCaptures(
milind-uf3ab8ba2023-02-04 17:56:16 -0800185 aos::EventLoop *detection_event_loop, aos::EventLoop *mapping_event_loop,
186 aos::logger::LogReader *reader,
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800187 std::vector<DataAdapter::TimestampedDetection>
188 *timestamped_target_detections,
milind-ua30a4a12023-03-24 20:49:41 -0700189 std::vector<std::unique_ptr<AprilRoboticsDetector>> *detectors,
190 std::set<std::string> *drawn_nodes, VisualizeRobot *vis_robot,
191 size_t *display_count) {
milind-uf3ab8ba2023-02-04 17:56:16 -0800192 static constexpr std::string_view kImageChannel = "/camera";
milind-ua30a4a12023-03-24 20:49:41 -0700193 // For the robots, we need to flip the image since the cameras are rolled by
194 // 180 degrees
195 bool flip_image = (FLAGS_team_number != 7971);
milind-uf3ab8ba2023-02-04 17:56:16 -0800196 auto detector_ptr = std::make_unique<AprilRoboticsDetector>(
milind-ua30a4a12023-03-24 20:49:41 -0700197 detection_event_loop, kImageChannel, flip_image);
milind-uf2a4e322023-02-01 19:33:10 -0800198 // Get the camera extrinsics
James Kuszmaul258e4ee2023-02-23 14:22:30 -0800199 cv::Mat extrinsics_cv = detector_ptr->extrinsics().value();
milind-uf2a4e322023-02-01 19:33:10 -0800200 Eigen::Matrix4d extrinsics_matrix;
201 cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
202 const auto extrinsics = Eigen::Affine3d(extrinsics_matrix);
203
204 detectors->emplace_back(std::move(detector_ptr));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800205
Jim Ostrowski49be8232023-03-23 01:00:14 -0700206 ceres::examples::VectorOfConstraints target_constraints;
207 frc971::vision::TargetMapper target_loc_mapper(FLAGS_json_path,
208 target_constraints);
209
milind-uf3ab8ba2023-02-04 17:56:16 -0800210 mapping_event_loop->MakeWatcher("/camera", [=](const TargetMap &map) {
milind-u09fb1252023-01-28 19:21:41 -0800211 aos::distributed_clock::time_point pi_distributed_time =
212 reader->event_loop_factory()
milind-uf3ab8ba2023-02-04 17:56:16 -0800213 ->GetNodeEventLoopFactory(mapping_event_loop->node())
milind-u09fb1252023-01-28 19:21:41 -0800214 ->ToDistributedClock(aos::monotonic_clock::time_point(
215 aos::monotonic_clock::duration(map.monotonic_timestamp_ns())));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800216
Jim Ostrowski49be8232023-03-23 01:00:14 -0700217 std::string node_name = detection_event_loop->node()->name()->str();
milind-u5ddd5152023-03-04 15:19:17 -0800218 HandleAprilTags(map, pi_distributed_time, timestamped_target_detections,
milind-ua30a4a12023-03-24 20:49:41 -0700219 extrinsics, node_name, target_loc_mapper, drawn_nodes,
220 vis_robot, display_count);
milind-u09fb1252023-01-28 19:21:41 -0800221 });
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800222}
223
224void MappingMain(int argc, char *argv[]) {
225 std::vector<std::string> unsorted_logfiles =
226 aos::logger::FindLogs(argc, argv);
227
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800228 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
229
milind-u4a5ef8a2023-03-05 14:10:23 -0800230 std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config =
231 (FLAGS_config.empty()
232 ? std::nullopt
233 : std::make_optional(aos::configuration::ReadConfig(FLAGS_config)));
Jim Ostrowskiaec5dd22023-02-27 22:17:53 -0800234
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800235 // open logfiles
milind-u4a5ef8a2023-03-05 14:10:23 -0800236 aos::logger::LogReader reader(
237 aos::logger::SortParts(unsorted_logfiles),
238 config.has_value() ? &config->message() : nullptr);
milind-ua30a4a12023-03-24 20:49:41 -0700239 // Send new april tag poses. This allows us to take a log of images, then
240 // play with the april detection code and see those changes take effect in
241 // mapping
milind-uf3ab8ba2023-02-04 17:56:16 -0800242 constexpr size_t kNumPis = 4;
243 for (size_t i = 1; i <= kNumPis; i++) {
244 reader.RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i),
245 "frc971.vision.TargetMap");
milind-uc5a494f2023-02-24 15:39:22 -0800246 reader.RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i),
247 "foxglove.ImageAnnotations");
248 reader.RemapLoggedChannel(absl::StrFormat("/pi%u/constants", i),
249 "y2023.Constants");
milind-uf3ab8ba2023-02-04 17:56:16 -0800250 }
251
milind-uc5a494f2023-02-24 15:39:22 -0800252 reader.RemapLoggedChannel("/imu/constants", "y2023.Constants");
253
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800254 reader.Register();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800255
milind-uc5a494f2023-02-24 15:39:22 -0800256 SendSimulationConstants(reader.event_loop_factory(), FLAGS_team_number,
257 FLAGS_constants_path);
258
milind-u09fb1252023-01-28 19:21:41 -0800259 std::vector<std::unique_ptr<AprilRoboticsDetector>> detectors;
milind-ua30a4a12023-03-24 20:49:41 -0700260 VisualizeRobot vis_robot;
261 std::set<std::string> drawn_nodes;
262 size_t display_count = 0;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800263
264 const aos::Node *pi1 =
265 aos::configuration::GetNode(reader.configuration(), "pi1");
milind-uf3ab8ba2023-02-04 17:56:16 -0800266 std::unique_ptr<aos::EventLoop> pi1_detection_event_loop =
267 reader.event_loop_factory()->MakeEventLoop("pi1_detection", pi1);
268 std::unique_ptr<aos::EventLoop> pi1_mapping_event_loop =
269 reader.event_loop_factory()->MakeEventLoop("pi1_mapping", pi1);
270 HandlePiCaptures(pi1_detection_event_loop.get(), pi1_mapping_event_loop.get(),
milind-ua30a4a12023-03-24 20:49:41 -0700271 &reader, &timestamped_target_detections, &detectors,
272 &drawn_nodes, &vis_robot, &display_count);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800273
274 const aos::Node *pi2 =
275 aos::configuration::GetNode(reader.configuration(), "pi2");
milind-uf3ab8ba2023-02-04 17:56:16 -0800276 std::unique_ptr<aos::EventLoop> pi2_detection_event_loop =
277 reader.event_loop_factory()->MakeEventLoop("pi2_detection", pi2);
278 std::unique_ptr<aos::EventLoop> pi2_mapping_event_loop =
279 reader.event_loop_factory()->MakeEventLoop("pi2_mapping", pi2);
280 HandlePiCaptures(pi2_detection_event_loop.get(), pi2_mapping_event_loop.get(),
milind-ua30a4a12023-03-24 20:49:41 -0700281 &reader, &timestamped_target_detections, &detectors,
282 &drawn_nodes, &vis_robot, &display_count);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800283
284 const aos::Node *pi3 =
285 aos::configuration::GetNode(reader.configuration(), "pi3");
milind-uf3ab8ba2023-02-04 17:56:16 -0800286 std::unique_ptr<aos::EventLoop> pi3_detection_event_loop =
287 reader.event_loop_factory()->MakeEventLoop("pi3_detection", pi3);
288 std::unique_ptr<aos::EventLoop> pi3_mapping_event_loop =
289 reader.event_loop_factory()->MakeEventLoop("pi3_mapping", pi3);
290 HandlePiCaptures(pi3_detection_event_loop.get(), pi3_mapping_event_loop.get(),
milind-ua30a4a12023-03-24 20:49:41 -0700291 &reader, &timestamped_target_detections, &detectors,
292 &drawn_nodes, &vis_robot, &display_count);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800293
294 const aos::Node *pi4 =
295 aos::configuration::GetNode(reader.configuration(), "pi4");
milind-uf3ab8ba2023-02-04 17:56:16 -0800296 std::unique_ptr<aos::EventLoop> pi4_detection_event_loop =
297 reader.event_loop_factory()->MakeEventLoop("pi4_detection", pi4);
298 std::unique_ptr<aos::EventLoop> pi4_mapping_event_loop =
299 reader.event_loop_factory()->MakeEventLoop("pi4_mapping", pi4);
300 HandlePiCaptures(pi4_detection_event_loop.get(), pi4_mapping_event_loop.get(),
milind-ua30a4a12023-03-24 20:49:41 -0700301 &reader, &timestamped_target_detections, &detectors,
302 &drawn_nodes, &vis_robot, &display_count);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800303
Jim Ostrowski68965cd2023-03-01 20:32:51 -0800304 std::unique_ptr<aos::EventLoop> mcap_event_loop;
305 std::unique_ptr<aos::McapLogger> relogger;
306 if (!FLAGS_mcap_output_path.empty()) {
307 LOG(INFO) << "Writing out mcap file to " << FLAGS_mcap_output_path;
Jim Ostrowski68965cd2023-03-01 20:32:51 -0800308 const aos::Node *node =
309 aos::configuration::GetNode(reader.configuration(), FLAGS_pi);
310 reader.event_loop_factory()->GetNodeEventLoopFactory(node)->OnStartup(
311 [&relogger, &mcap_event_loop, &reader, node]() {
312 mcap_event_loop =
313 reader.event_loop_factory()->MakeEventLoop("mcap", node);
314 relogger = std::make_unique<aos::McapLogger>(
315 mcap_event_loop.get(), FLAGS_mcap_output_path,
316 aos::McapLogger::Serialization::kFlatbuffer,
317 aos::McapLogger::CanonicalChannelNames::kShortened,
318 aos::McapLogger::Compression::kLz4);
319 });
320 }
321
Jim Ostrowski49be8232023-03-23 01:00:14 -0700322 if (FLAGS_visualize) {
milind-ua30a4a12023-03-24 20:49:41 -0700323 vis_robot.ClearImage();
Jim Ostrowski49be8232023-03-23 01:00:14 -0700324 const double kFocalLength = 500.0;
milind-ua30a4a12023-03-24 20:49:41 -0700325 vis_robot.SetDefaultViewpoint(kImageWidth, kFocalLength);
Jim Ostrowski49be8232023-03-23 01:00:14 -0700326 }
327
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800328 reader.event_loop_factory()->Run();
329
milind-ua30a4a12023-03-24 20:49:41 -0700330 if (FLAGS_solve) {
331 auto target_constraints =
332 DataAdapter::MatchTargetDetections(timestamped_target_detections);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800333
milind-ua30a4a12023-03-24 20:49:41 -0700334 frc971::vision::TargetMapper mapper(FLAGS_json_path, target_constraints);
335 mapper.Solve(FLAGS_field_name, FLAGS_output_dir);
336 }
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800337
milind-u09fb1252023-01-28 19:21:41 -0800338 // Clean up all the pointers
339 for (auto &detector_ptr : detectors) {
340 detector_ptr.reset();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800341 }
342}
343
344} // namespace vision
milind-u16e3a082023-01-21 13:53:43 -0800345} // namespace y2023
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800346
347int main(int argc, char **argv) {
348 aos::InitGoogle(&argc, &argv);
milind-u16e3a082023-01-21 13:53:43 -0800349 y2023::vision::MappingMain(argc, argv);
Milind Upadhyay915d6002022-12-26 20:37:43 -0800350}