Jim Ostrowski | aec5dd2 | 2023-02-27 22:17:53 -0800 | [diff] [blame] | 1 | #include "aos/configuration.h" |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 2 | #include "aos/events/logging/log_reader.h" |
| 3 | #include "aos/events/simulated_event_loop.h" |
| 4 | #include "aos/init.h" |
Jim Ostrowski | 68965cd | 2023-03-01 20:32:51 -0800 | [diff] [blame] | 5 | #include "aos/util/mcap_logger.h" |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 6 | #include "frc971/control_loops/pose.h" |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 7 | #include "frc971/vision/calibration_generated.h" |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 8 | #include "frc971/vision/charuco_lib.h" |
| 9 | #include "frc971/vision/target_mapper.h" |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 10 | #include "frc971/vision/visualize_robot.h" |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 11 | #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-u | c5a494f | 2023-02-24 15:39:22 -0800 | [diff] [blame] | 18 | #include "y2023/constants/simulated_constants_sender.h" |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 19 | #include "y2023/vision/aprilrobotics.h" |
James Kuszmaul | d67f6d2 | 2023-02-05 17:37:25 -0800 | [diff] [blame] | 20 | #include "y2023/vision/vision_util.h" |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 21 | |
milind-u | c5a494f | 2023-02-24 15:39:22 -0800 | [diff] [blame] | 22 | DEFINE_string(json_path, "y2023/vision/maps/target_map.json", |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 23 | "Specify path for json with initial pose guesses."); |
milind-u | 4a5ef8a | 2023-03-05 14:10:23 -0800 | [diff] [blame] | 24 | DEFINE_string(config, "", |
| 25 | "If set, override the log's config file with this one."); |
milind-u | c5a494f | 2023-02-24 15:39:22 -0800 | [diff] [blame] | 26 | DEFINE_string(constants_path, "y2023/constants/constants.json", |
| 27 | "Path to the constant file"); |
| 28 | DEFINE_string(output_dir, "y2023/vision/maps", |
| 29 | "Directory to write solved target map to"); |
| 30 | DEFINE_string(field_name, "charged_up", |
| 31 | "Field name, for the output json filename and flatbuffer field"); |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 32 | DEFINE_int32(team_number, 0, |
| 33 | "Required: Use the calibration for a node with this team number"); |
Jim Ostrowski | 68965cd | 2023-03-01 20:32:51 -0800 | [diff] [blame] | 34 | DEFINE_string(mcap_output_path, "/tmp/log.mcap", "Log to output."); |
| 35 | DEFINE_string(pi, "pi1", "Pi name to generate mcap log for; defaults to pi1."); |
milind-u | 5ddd515 | 2023-03-04 15:19:17 -0800 | [diff] [blame] | 36 | DEFINE_double(max_pose_error, 1e-6, |
| 37 | "Throw out target poses with a higher pose error than this"); |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 38 | |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 39 | namespace y2023 { |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 40 | namespace vision { |
| 41 | using frc971::vision::DataAdapter; |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 42 | using frc971::vision::ImageCallback; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 43 | using frc971::vision::PoseUtils; |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 44 | using frc971::vision::TargetMap; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 45 | using frc971::vision::TargetMapper; |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 46 | namespace calibration = frc971::vision::calibration; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 47 | |
| 48 | // Change reference frame from camera to robot |
milind-u | ee67abd | 2023-02-23 18:26:55 -0800 | [diff] [blame] | 49 | Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target, |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 50 | Eigen::Affine3d extrinsics) { |
milind-u | ee67abd | 2023-02-23 18:26:55 -0800 | [diff] [blame] | 51 | const Eigen::Affine3d H_robot_camera = extrinsics; |
| 52 | const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 53 | return H_robot_target; |
| 54 | } |
| 55 | |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 56 | frc971::vision::VisualizeRobot vis_robot_; |
| 57 | const int kImageWidth = 1000; |
| 58 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 59 | // Add detected apriltag poses relative to the robot to |
| 60 | // timestamped_target_detections |
milind-u | 5ddd515 | 2023-03-04 15:19:17 -0800 | [diff] [blame] | 61 | void HandleAprilTags(const TargetMap &map, |
| 62 | aos::distributed_clock::time_point pi_distributed_time, |
| 63 | std::vector<DataAdapter::TimestampedDetection> |
| 64 | *timestamped_target_detections, |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 65 | Eigen::Affine3d extrinsics, std::string node_name, |
| 66 | frc971::vision::TargetMapper mapper) { |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 67 | for (const auto *target_pose_fbs : *map.target_poses()) { |
milind-u | 5ddd515 | 2023-03-04 15:19:17 -0800 | [diff] [blame] | 68 | // Skip detections with high pose errors |
| 69 | if (target_pose_fbs->pose_error() > FLAGS_max_pose_error) { |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 70 | LOG(INFO) << " Skipping tag " << target_pose_fbs->id() |
| 71 | << " due to pose error of " << target_pose_fbs->pose_error(); |
milind-u | 5ddd515 | 2023-03-04 15:19:17 -0800 | [diff] [blame] | 72 | continue; |
| 73 | } |
| 74 | |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 75 | const TargetMapper::TargetPose target_pose = |
| 76 | PoseUtils::TargetPoseFromFbs(*target_pose_fbs); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 77 | |
milind-u | ee67abd | 2023-02-23 18:26:55 -0800 | [diff] [blame] | 78 | Eigen::Affine3d H_camera_target = |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 79 | Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 80 | Eigen::Affine3d H_robot_target = |
milind-u | ee67abd | 2023-02-23 18:26:55 -0800 | [diff] [blame] | 81 | CameraToRobotDetection(H_camera_target, extrinsics); |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 82 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 83 | ceres::examples::Pose3d target_pose_camera = |
milind-u | ee67abd | 2023-02-23 18:26:55 -0800 | [diff] [blame] | 84 | PoseUtils::Affine3dToPose3d(H_camera_target); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 85 | double distance_from_camera = target_pose_camera.p.norm(); |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 86 | double distortion_factor = target_pose_fbs->distortion_factor(); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 87 | |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 88 | CHECK(map.has_monotonic_timestamp_ns()) |
| 89 | << "Need detection timestamps for mapping"; |
| 90 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 91 | timestamped_target_detections->emplace_back( |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 92 | DataAdapter::TimestampedDetection{ |
| 93 | .time = pi_distributed_time, |
| 94 | .H_robot_target = H_robot_target, |
| 95 | .distance_from_camera = distance_from_camera, |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 96 | .distortion_factor = distortion_factor, |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 97 | .id = static_cast<TargetMapper::TargetId>(target_pose.id)}); |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 98 | |
| 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 Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 119 | } |
| 120 | } |
| 121 | |
milind-u | 5ddd515 | 2023-03-04 15:19:17 -0800 | [diff] [blame] | 122 | // Get images from pi and pass apriltag positions to HandleAprilTags() |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 123 | void HandlePiCaptures( |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 124 | aos::EventLoop *detection_event_loop, aos::EventLoop *mapping_event_loop, |
| 125 | aos::logger::LogReader *reader, |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 126 | std::vector<DataAdapter::TimestampedDetection> |
| 127 | *timestamped_target_detections, |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 128 | std::vector<std::unique_ptr<AprilRoboticsDetector>> *detectors) { |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 129 | static constexpr std::string_view kImageChannel = "/camera"; |
| 130 | auto detector_ptr = std::make_unique<AprilRoboticsDetector>( |
| 131 | detection_event_loop, kImageChannel); |
milind-u | f2a4e32 | 2023-02-01 19:33:10 -0800 | [diff] [blame] | 132 | // Get the camera extrinsics |
James Kuszmaul | 258e4ee | 2023-02-23 14:22:30 -0800 | [diff] [blame] | 133 | cv::Mat extrinsics_cv = detector_ptr->extrinsics().value(); |
milind-u | f2a4e32 | 2023-02-01 19:33:10 -0800 | [diff] [blame] | 134 | 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 Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 139 | |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 140 | ceres::examples::VectorOfConstraints target_constraints; |
| 141 | frc971::vision::TargetMapper target_loc_mapper(FLAGS_json_path, |
| 142 | target_constraints); |
| 143 | |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 144 | mapping_event_loop->MakeWatcher("/camera", [=](const TargetMap &map) { |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 145 | aos::distributed_clock::time_point pi_distributed_time = |
| 146 | reader->event_loop_factory() |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 147 | ->GetNodeEventLoopFactory(mapping_event_loop->node()) |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 148 | ->ToDistributedClock(aos::monotonic_clock::time_point( |
| 149 | aos::monotonic_clock::duration(map.monotonic_timestamp_ns()))); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 150 | |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 151 | std::string node_name = detection_event_loop->node()->name()->str(); |
milind-u | 5ddd515 | 2023-03-04 15:19:17 -0800 | [diff] [blame] | 152 | HandleAprilTags(map, pi_distributed_time, timestamped_target_detections, |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 153 | 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-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 161 | }); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 162 | } |
| 163 | |
| 164 | void MappingMain(int argc, char *argv[]) { |
| 165 | std::vector<std::string> unsorted_logfiles = |
| 166 | aos::logger::FindLogs(argc, argv); |
| 167 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 168 | std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections; |
| 169 | |
milind-u | 4a5ef8a | 2023-03-05 14:10:23 -0800 | [diff] [blame] | 170 | std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config = |
| 171 | (FLAGS_config.empty() |
| 172 | ? std::nullopt |
| 173 | : std::make_optional(aos::configuration::ReadConfig(FLAGS_config))); |
Jim Ostrowski | aec5dd2 | 2023-02-27 22:17:53 -0800 | [diff] [blame] | 174 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 175 | // open logfiles |
milind-u | 4a5ef8a | 2023-03-05 14:10:23 -0800 | [diff] [blame] | 176 | aos::logger::LogReader reader( |
| 177 | aos::logger::SortParts(unsorted_logfiles), |
| 178 | config.has_value() ? &config->message() : nullptr); |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 179 | // 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-u | c5a494f | 2023-02-24 15:39:22 -0800 | [diff] [blame] | 185 | reader.RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i), |
| 186 | "foxglove.ImageAnnotations"); |
| 187 | reader.RemapLoggedChannel(absl::StrFormat("/pi%u/constants", i), |
| 188 | "y2023.Constants"); |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 189 | } |
| 190 | |
milind-u | c5a494f | 2023-02-24 15:39:22 -0800 | [diff] [blame] | 191 | reader.RemapLoggedChannel("/imu/constants", "y2023.Constants"); |
| 192 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 193 | reader.Register(); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 194 | |
milind-u | c5a494f | 2023-02-24 15:39:22 -0800 | [diff] [blame] | 195 | SendSimulationConstants(reader.event_loop_factory(), FLAGS_team_number, |
| 196 | FLAGS_constants_path); |
| 197 | |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 198 | std::vector<std::unique_ptr<AprilRoboticsDetector>> detectors; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 199 | |
| 200 | const aos::Node *pi1 = |
| 201 | aos::configuration::GetNode(reader.configuration(), "pi1"); |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 202 | 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, ×tamped_target_detections, &detectors); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 208 | |
| 209 | const aos::Node *pi2 = |
| 210 | aos::configuration::GetNode(reader.configuration(), "pi2"); |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 211 | 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, ×tamped_target_detections, &detectors); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 217 | |
| 218 | const aos::Node *pi3 = |
| 219 | aos::configuration::GetNode(reader.configuration(), "pi3"); |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 220 | 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, ×tamped_target_detections, &detectors); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 226 | |
| 227 | const aos::Node *pi4 = |
| 228 | aos::configuration::GetNode(reader.configuration(), "pi4"); |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 229 | 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, ×tamped_target_detections, &detectors); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 235 | |
Jim Ostrowski | 68965cd | 2023-03-01 20:32:51 -0800 | [diff] [blame] | 236 | 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 Ostrowski | 68965cd | 2023-03-01 20:32:51 -0800 | [diff] [blame] | 240 | 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 Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 254 | 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 Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 262 | reader.event_loop_factory()->Run(); |
| 263 | |
| 264 | auto target_constraints = |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 265 | DataAdapter::MatchTargetDetections(timestamped_target_detections); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 266 | |
| 267 | frc971::vision::TargetMapper mapper(FLAGS_json_path, target_constraints); |
milind-u | c5a494f | 2023-02-24 15:39:22 -0800 | [diff] [blame] | 268 | mapper.Solve(FLAGS_field_name, FLAGS_output_dir); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 269 | |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 270 | // Clean up all the pointers |
| 271 | for (auto &detector_ptr : detectors) { |
| 272 | detector_ptr.reset(); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 273 | } |
| 274 | } |
| 275 | |
| 276 | } // namespace vision |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 277 | } // namespace y2023 |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 278 | |
| 279 | int main(int argc, char **argv) { |
| 280 | aos::InitGoogle(&argc, &argv); |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 281 | y2023::vision::MappingMain(argc, argv); |
Milind Upadhyay | 915d600 | 2022-12-26 20:37:43 -0800 | [diff] [blame] | 282 | } |