blob: 921c17217d26909d4fbb2e53f5196aac1209b57e [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 Upadhyayebf93ee2023-01-05 14:12:58 -080032Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camrob_target,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080033 Eigen::Affine3d extrinsics) {
34 const Eigen::Affine3d H_robot_camrob = extrinsics;
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080035 const Eigen::Affine3d H_robot_target = H_robot_camrob * H_camrob_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-u3f5f83c2023-01-29 15:23:51 -080050 Eigen::Affine3d H_camcv_target =
51 Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q;
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080052 // With X, Y, Z being robot axes and x, y, z being camera axes,
53 // x = -Y, y = -Z, z = X
54 static const Eigen::Affine3d H_camcv_camrob =
55 Eigen::Affine3d((Eigen::Matrix4d() << 0.0, -1.0, 0.0, 0.0, 0.0, 0.0,
56 -1.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0)
57 .finished());
58 Eigen::Affine3d H_camrob_target = H_camcv_camrob.inverse() * H_camcv_target;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080059 Eigen::Affine3d H_robot_target =
60 CameraToRobotDetection(H_camrob_target, extrinsics);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080061
Milind Upadhyayc5beba12022-12-17 17:41:20 -080062 ceres::examples::Pose3d target_pose_camera =
63 PoseUtils::Affine3dToPose3d(H_camrob_target);
64 double distance_from_camera = target_pose_camera.p.norm();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080065
milind-u09fb1252023-01-28 19:21:41 -080066 CHECK(map.has_monotonic_timestamp_ns())
67 << "Need detection timestamps for mapping";
68
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080069 timestamped_target_detections->emplace_back(
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080070 DataAdapter::TimestampedDetection{
71 .time = pi_distributed_time,
72 .H_robot_target = H_robot_target,
73 .distance_from_camera = distance_from_camera,
milind-u3f5f83c2023-01-29 15:23:51 -080074 .id = static_cast<TargetMapper::TargetId>(target_pose.id)});
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080075 }
76}
77
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080078// Get images from pi and pass apriltag positions to HandleAprilTag()
79void HandlePiCaptures(
milind-uf3ab8ba2023-02-04 17:56:16 -080080 aos::EventLoop *detection_event_loop, aos::EventLoop *mapping_event_loop,
81 aos::logger::LogReader *reader,
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080082 std::vector<DataAdapter::TimestampedDetection>
83 *timestamped_target_detections,
milind-u09fb1252023-01-28 19:21:41 -080084 std::vector<std::unique_ptr<AprilRoboticsDetector>> *detectors) {
milind-uf3ab8ba2023-02-04 17:56:16 -080085 static constexpr std::string_view kImageChannel = "/camera";
86 auto detector_ptr = std::make_unique<AprilRoboticsDetector>(
87 detection_event_loop, kImageChannel);
milind-uf2a4e322023-02-01 19:33:10 -080088 // Get the camera extrinsics
89 cv::Mat extrinsics_cv = detector_ptr->extrinsics();
90 Eigen::Matrix4d extrinsics_matrix;
91 cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
92 const auto extrinsics = Eigen::Affine3d(extrinsics_matrix);
93
94 detectors->emplace_back(std::move(detector_ptr));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080095
milind-uf3ab8ba2023-02-04 17:56:16 -080096 mapping_event_loop->MakeWatcher("/camera", [=](const TargetMap &map) {
milind-u09fb1252023-01-28 19:21:41 -080097 aos::distributed_clock::time_point pi_distributed_time =
98 reader->event_loop_factory()
milind-uf3ab8ba2023-02-04 17:56:16 -080099 ->GetNodeEventLoopFactory(mapping_event_loop->node())
milind-u09fb1252023-01-28 19:21:41 -0800100 ->ToDistributedClock(aos::monotonic_clock::time_point(
101 aos::monotonic_clock::duration(map.monotonic_timestamp_ns())));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800102
milind-u09fb1252023-01-28 19:21:41 -0800103 HandleAprilTag(map, pi_distributed_time, timestamped_target_detections,
104 extrinsics);
105 });
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800106}
107
108void MappingMain(int argc, char *argv[]) {
109 std::vector<std::string> unsorted_logfiles =
110 aos::logger::FindLogs(argc, argv);
111
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800112 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
113
114 // open logfiles
115 aos::logger::LogReader reader(aos::logger::SortParts(unsorted_logfiles));
milind-uf3ab8ba2023-02-04 17:56:16 -0800116 // Send new april tag poses. This allows us to take a log of images, then play
117 // with the april detection code and see those changes take effect in mapping
118 constexpr size_t kNumPis = 4;
119 for (size_t i = 1; i <= kNumPis; i++) {
120 reader.RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i),
121 "frc971.vision.TargetMap");
122 }
123
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800124 reader.Register();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800125
milind-u09fb1252023-01-28 19:21:41 -0800126 std::vector<std::unique_ptr<AprilRoboticsDetector>> detectors;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800127
128 const aos::Node *pi1 =
129 aos::configuration::GetNode(reader.configuration(), "pi1");
milind-uf3ab8ba2023-02-04 17:56:16 -0800130 std::unique_ptr<aos::EventLoop> pi1_detection_event_loop =
131 reader.event_loop_factory()->MakeEventLoop("pi1_detection", pi1);
132 std::unique_ptr<aos::EventLoop> pi1_mapping_event_loop =
133 reader.event_loop_factory()->MakeEventLoop("pi1_mapping", pi1);
134 HandlePiCaptures(pi1_detection_event_loop.get(), pi1_mapping_event_loop.get(),
135 &reader, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800136
137 const aos::Node *pi2 =
138 aos::configuration::GetNode(reader.configuration(), "pi2");
milind-uf3ab8ba2023-02-04 17:56:16 -0800139 std::unique_ptr<aos::EventLoop> pi2_detection_event_loop =
140 reader.event_loop_factory()->MakeEventLoop("pi2_detection", pi2);
141 std::unique_ptr<aos::EventLoop> pi2_mapping_event_loop =
142 reader.event_loop_factory()->MakeEventLoop("pi2_mapping", pi2);
143 HandlePiCaptures(pi2_detection_event_loop.get(), pi2_mapping_event_loop.get(),
144 &reader, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800145
146 const aos::Node *pi3 =
147 aos::configuration::GetNode(reader.configuration(), "pi3");
milind-uf3ab8ba2023-02-04 17:56:16 -0800148 std::unique_ptr<aos::EventLoop> pi3_detection_event_loop =
149 reader.event_loop_factory()->MakeEventLoop("pi3_detection", pi3);
150 std::unique_ptr<aos::EventLoop> pi3_mapping_event_loop =
151 reader.event_loop_factory()->MakeEventLoop("pi3_mapping", pi3);
152 HandlePiCaptures(pi3_detection_event_loop.get(), pi3_mapping_event_loop.get(),
153 &reader, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800154
155 const aos::Node *pi4 =
156 aos::configuration::GetNode(reader.configuration(), "pi4");
milind-uf3ab8ba2023-02-04 17:56:16 -0800157 std::unique_ptr<aos::EventLoop> pi4_detection_event_loop =
158 reader.event_loop_factory()->MakeEventLoop("pi4_detection", pi4);
159 std::unique_ptr<aos::EventLoop> pi4_mapping_event_loop =
160 reader.event_loop_factory()->MakeEventLoop("pi4_mapping", pi4);
161 HandlePiCaptures(pi4_detection_event_loop.get(), pi4_mapping_event_loop.get(),
162 &reader, &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800163
164 reader.event_loop_factory()->Run();
165
166 auto target_constraints =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800167 DataAdapter::MatchTargetDetections(timestamped_target_detections);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800168
169 frc971::vision::TargetMapper mapper(FLAGS_json_path, target_constraints);
milind-u09fb1252023-01-28 19:21:41 -0800170 mapper.Solve("charged_up");
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800171
milind-u09fb1252023-01-28 19:21:41 -0800172 // Clean up all the pointers
173 for (auto &detector_ptr : detectors) {
174 detector_ptr.reset();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800175 }
176}
177
178} // namespace vision
milind-u16e3a082023-01-21 13:53:43 -0800179} // namespace y2023
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800180
181int main(int argc, char **argv) {
182 aos::InitGoogle(&argc, &argv);
milind-u16e3a082023-01-21 13:53:43 -0800183 y2023::vision::MappingMain(argc, argv);
Milind Upadhyay915d6002022-12-26 20:37:43 -0800184}