blob: b41d7d5dad12801676e3d0771b6b4206919f2f8c [file] [log] [blame]
Yash Chainanid5c7f0d2022-11-19 17:05:57 -08001#include "aos/events/logging/log_reader.h"
2#include "aos/events/simulated_event_loop.h"
3#include "aos/init.h"
4#include "frc971/control_loops/pose.h"
milind-u16e3a082023-01-21 13:53:43 -08005#include "frc971/vision/calibration_generated.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -08006#include "frc971/vision/charuco_lib.h"
7#include "frc971/vision/target_mapper.h"
8#include "opencv2/aruco.hpp"
9#include "opencv2/calib3d.hpp"
10#include "opencv2/core/eigen.hpp"
11#include "opencv2/features2d.hpp"
12#include "opencv2/highgui.hpp"
13#include "opencv2/highgui/highgui.hpp"
14#include "opencv2/imgproc.hpp"
milind-u09fb1252023-01-28 19:21:41 -080015#include "y2023/vision/aprilrobotics.h"
James Kuszmauld67f6d22023-02-05 17:37:25 -080016#include "y2023/vision/vision_util.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080017
18DEFINE_string(json_path, "target_map.json",
19 "Specify path for json with initial pose guesses.");
milind-u09fb1252023-01-28 19:21:41 -080020DECLARE_int32(team_number);
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080021
milind-u16e3a082023-01-21 13:53:43 -080022namespace y2023 {
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080023namespace vision {
24using frc971::vision::DataAdapter;
milind-u16e3a082023-01-21 13:53:43 -080025using frc971::vision::ImageCallback;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080026using frc971::vision::PoseUtils;
milind-u09fb1252023-01-28 19:21:41 -080027using frc971::vision::TargetMap;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080028using frc971::vision::TargetMapper;
milind-u16e3a082023-01-21 13:53:43 -080029namespace calibration = frc971::vision::calibration;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080030
31// Change reference frame from camera to robot
milind-uee67abd2023-02-23 18:26:55 -080032Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080033 Eigen::Affine3d extrinsics) {
milind-uee67abd2023-02-23 18:26:55 -080034 const Eigen::Affine3d H_robot_camera = extrinsics;
35 const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080036 return H_robot_target;
37}
38
39// Add detected apriltag poses relative to the robot to
40// timestamped_target_detections
milind-u09fb1252023-01-28 19:21:41 -080041void HandleAprilTag(const TargetMap &map,
42 aos::distributed_clock::time_point pi_distributed_time,
Milind Upadhyay915d6002022-12-26 20:37:43 -080043 std::vector<DataAdapter::TimestampedDetection>
44 *timestamped_target_detections,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080045 Eigen::Affine3d extrinsics) {
milind-u3f5f83c2023-01-29 15:23:51 -080046 for (const auto *target_pose_fbs : *map.target_poses()) {
47 const TargetMapper::TargetPose target_pose =
48 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080049
milind-uee67abd2023-02-23 18:26:55 -080050 Eigen::Affine3d H_camera_target =
milind-u3f5f83c2023-01-29 15:23:51 -080051 Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080052 Eigen::Affine3d H_robot_target =
milind-uee67abd2023-02-23 18:26:55 -080053 CameraToRobotDetection(H_camera_target, extrinsics);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080054
Milind Upadhyayc5beba12022-12-17 17:41:20 -080055 ceres::examples::Pose3d target_pose_camera =
milind-uee67abd2023-02-23 18:26:55 -080056 PoseUtils::Affine3dToPose3d(H_camera_target);
Milind Upadhyayc5beba12022-12-17 17:41:20 -080057 double distance_from_camera = target_pose_camera.p.norm();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080058
milind-u09fb1252023-01-28 19:21:41 -080059 CHECK(map.has_monotonic_timestamp_ns())
60 << "Need detection timestamps for mapping";
61
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080062 timestamped_target_detections->emplace_back(
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080063 DataAdapter::TimestampedDetection{
64 .time = pi_distributed_time,
65 .H_robot_target = H_robot_target,
66 .distance_from_camera = distance_from_camera,
milind-u3f5f83c2023-01-29 15:23:51 -080067 .id = static_cast<TargetMapper::TargetId>(target_pose.id)});
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080068 }
69}
70
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080071// Get images from pi and pass apriltag positions to HandleAprilTag()
72void HandlePiCaptures(
milind-uf3ab8ba2023-02-04 17:56:16 -080073 aos::EventLoop *detection_event_loop, aos::EventLoop *mapping_event_loop,
74 aos::logger::LogReader *reader,
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080075 std::vector<DataAdapter::TimestampedDetection>
76 *timestamped_target_detections,
milind-u09fb1252023-01-28 19:21:41 -080077 std::vector<std::unique_ptr<AprilRoboticsDetector>> *detectors) {
milind-uf3ab8ba2023-02-04 17:56:16 -080078 static constexpr std::string_view kImageChannel = "/camera";
79 auto detector_ptr = std::make_unique<AprilRoboticsDetector>(
80 detection_event_loop, kImageChannel);
milind-uf2a4e322023-02-01 19:33:10 -080081 // Get the camera extrinsics
James Kuszmaul258e4ee2023-02-23 14:22:30 -080082 cv::Mat extrinsics_cv = detector_ptr->extrinsics().value();
milind-uf2a4e322023-02-01 19:33:10 -080083 Eigen::Matrix4d extrinsics_matrix;
84 cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
85 const auto extrinsics = Eigen::Affine3d(extrinsics_matrix);
86
87 detectors->emplace_back(std::move(detector_ptr));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080088
milind-uf3ab8ba2023-02-04 17:56:16 -080089 mapping_event_loop->MakeWatcher("/camera", [=](const TargetMap &map) {
milind-u09fb1252023-01-28 19:21:41 -080090 aos::distributed_clock::time_point pi_distributed_time =
91 reader->event_loop_factory()
milind-uf3ab8ba2023-02-04 17:56:16 -080092 ->GetNodeEventLoopFactory(mapping_event_loop->node())
milind-u09fb1252023-01-28 19:21:41 -080093 ->ToDistributedClock(aos::monotonic_clock::time_point(
94 aos::monotonic_clock::duration(map.monotonic_timestamp_ns())));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080095
milind-u09fb1252023-01-28 19:21:41 -080096 HandleAprilTag(map, pi_distributed_time, timestamped_target_detections,
97 extrinsics);
98 });
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080099}
100
101void MappingMain(int argc, char *argv[]) {
102 std::vector<std::string> unsorted_logfiles =
103 aos::logger::FindLogs(argc, argv);
104
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800105 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
106
107 // open logfiles
108 aos::logger::LogReader reader(aos::logger::SortParts(unsorted_logfiles));
milind-uf3ab8ba2023-02-04 17:56:16 -0800109 // Send new april tag poses. This allows us to take a log of images, then play
110 // with the april detection code and see those changes take effect in mapping
111 constexpr size_t kNumPis = 4;
112 for (size_t i = 1; i <= kNumPis; i++) {
113 reader.RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i),
114 "frc971.vision.TargetMap");
115 }
116
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800117 reader.Register();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800118
milind-u09fb1252023-01-28 19:21:41 -0800119 std::vector<std::unique_ptr<AprilRoboticsDetector>> detectors;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800120
121 const aos::Node *pi1 =
122 aos::configuration::GetNode(reader.configuration(), "pi1");
milind-uf3ab8ba2023-02-04 17:56:16 -0800123 std::unique_ptr<aos::EventLoop> pi1_detection_event_loop =
124 reader.event_loop_factory()->MakeEventLoop("pi1_detection", pi1);
125 std::unique_ptr<aos::EventLoop> pi1_mapping_event_loop =
126 reader.event_loop_factory()->MakeEventLoop("pi1_mapping", pi1);
127 HandlePiCaptures(pi1_detection_event_loop.get(), pi1_mapping_event_loop.get(),
128 &reader, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800129
130 const aos::Node *pi2 =
131 aos::configuration::GetNode(reader.configuration(), "pi2");
milind-uf3ab8ba2023-02-04 17:56:16 -0800132 std::unique_ptr<aos::EventLoop> pi2_detection_event_loop =
133 reader.event_loop_factory()->MakeEventLoop("pi2_detection", pi2);
134 std::unique_ptr<aos::EventLoop> pi2_mapping_event_loop =
135 reader.event_loop_factory()->MakeEventLoop("pi2_mapping", pi2);
136 HandlePiCaptures(pi2_detection_event_loop.get(), pi2_mapping_event_loop.get(),
137 &reader, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800138
139 const aos::Node *pi3 =
140 aos::configuration::GetNode(reader.configuration(), "pi3");
milind-uf3ab8ba2023-02-04 17:56:16 -0800141 std::unique_ptr<aos::EventLoop> pi3_detection_event_loop =
142 reader.event_loop_factory()->MakeEventLoop("pi3_detection", pi3);
143 std::unique_ptr<aos::EventLoop> pi3_mapping_event_loop =
144 reader.event_loop_factory()->MakeEventLoop("pi3_mapping", pi3);
145 HandlePiCaptures(pi3_detection_event_loop.get(), pi3_mapping_event_loop.get(),
146 &reader, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800147
148 const aos::Node *pi4 =
149 aos::configuration::GetNode(reader.configuration(), "pi4");
milind-uf3ab8ba2023-02-04 17:56:16 -0800150 std::unique_ptr<aos::EventLoop> pi4_detection_event_loop =
151 reader.event_loop_factory()->MakeEventLoop("pi4_detection", pi4);
152 std::unique_ptr<aos::EventLoop> pi4_mapping_event_loop =
153 reader.event_loop_factory()->MakeEventLoop("pi4_mapping", pi4);
154 HandlePiCaptures(pi4_detection_event_loop.get(), pi4_mapping_event_loop.get(),
155 &reader, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800156
157 reader.event_loop_factory()->Run();
158
159 auto target_constraints =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800160 DataAdapter::MatchTargetDetections(timestamped_target_detections);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800161
162 frc971::vision::TargetMapper mapper(FLAGS_json_path, target_constraints);
milind-u09fb1252023-01-28 19:21:41 -0800163 mapper.Solve("charged_up");
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800164
milind-u09fb1252023-01-28 19:21:41 -0800165 // Clean up all the pointers
166 for (auto &detector_ptr : detectors) {
167 detector_ptr.reset();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800168 }
169}
170
171} // namespace vision
milind-u16e3a082023-01-21 13:53:43 -0800172} // namespace y2023
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800173
174int main(int argc, char **argv) {
175 aos::InitGoogle(&argc, &argv);
milind-u16e3a082023-01-21 13:53:43 -0800176 y2023::vision::MappingMain(argc, argv);
Milind Upadhyay915d6002022-12-26 20:37:43 -0800177}