blob: 6d32dbd20caba79ea8f6b8365efa64efbef832f1 [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"
milind-u16e3a082023-01-21 13:53:43 -080016#include "y2023/vision/calibration_data.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 {
milind-u16e3a082023-01-21 13:53:43 -080024using frc971::vision::CharucoExtractor;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080025using frc971::vision::DataAdapter;
milind-u16e3a082023-01-21 13:53:43 -080026using frc971::vision::ImageCallback;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080027using frc971::vision::PoseUtils;
milind-u09fb1252023-01-28 19:21:41 -080028using frc971::vision::TargetMap;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080029using frc971::vision::TargetMapper;
milind-u16e3a082023-01-21 13:53:43 -080030namespace calibration = frc971::vision::calibration;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080031
32// Change reference frame from camera to robot
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080033Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camrob_target,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080034 Eigen::Affine3d extrinsics) {
35 const Eigen::Affine3d H_robot_camrob = extrinsics;
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080036 const Eigen::Affine3d H_robot_target = H_robot_camrob * H_camrob_target;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080037 return H_robot_target;
38}
39
40// Add detected apriltag poses relative to the robot to
41// timestamped_target_detections
milind-u09fb1252023-01-28 19:21:41 -080042void HandleAprilTag(const TargetMap &map,
43 aos::distributed_clock::time_point pi_distributed_time,
Milind Upadhyay915d6002022-12-26 20:37:43 -080044 std::vector<DataAdapter::TimestampedDetection>
45 *timestamped_target_detections,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080046 Eigen::Affine3d extrinsics) {
milind-u3f5f83c2023-01-29 15:23:51 -080047 for (const auto *target_pose_fbs : *map.target_poses()) {
48 const TargetMapper::TargetPose target_pose =
49 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080050
milind-u3f5f83c2023-01-29 15:23:51 -080051 Eigen::Affine3d H_camcv_target =
52 Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q;
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080053 // With X, Y, Z being robot axes and x, y, z being camera axes,
54 // x = -Y, y = -Z, z = X
55 static const Eigen::Affine3d H_camcv_camrob =
56 Eigen::Affine3d((Eigen::Matrix4d() << 0.0, -1.0, 0.0, 0.0, 0.0, 0.0,
57 -1.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0)
58 .finished());
59 Eigen::Affine3d H_camrob_target = H_camcv_camrob.inverse() * H_camcv_target;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080060 Eigen::Affine3d H_robot_target =
61 CameraToRobotDetection(H_camrob_target, extrinsics);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080062
Milind Upadhyayc5beba12022-12-17 17:41:20 -080063 ceres::examples::Pose3d target_pose_camera =
64 PoseUtils::Affine3dToPose3d(H_camrob_target);
65 double distance_from_camera = target_pose_camera.p.norm();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080066
milind-u09fb1252023-01-28 19:21:41 -080067 CHECK(map.has_monotonic_timestamp_ns())
68 << "Need detection timestamps for mapping";
69
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080070 timestamped_target_detections->emplace_back(
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080071 DataAdapter::TimestampedDetection{
72 .time = pi_distributed_time,
73 .H_robot_target = H_robot_target,
74 .distance_from_camera = distance_from_camera,
milind-u3f5f83c2023-01-29 15:23:51 -080075 .id = static_cast<TargetMapper::TargetId>(target_pose.id)});
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080076 }
77}
78
milind-u16e3a082023-01-21 13:53:43 -080079const calibration::CameraCalibration *FindCameraCalibration(
80 const calibration::CalibrationData *calibration_data,
81 std::string_view node_name) {
82 for (const calibration::CameraCalibration *candidate :
83 *calibration_data->camera_calibrations()) {
84 if (candidate->node_name()->string_view() != node_name) {
85 continue;
86 }
87 if (candidate->team_number() != FLAGS_team_number) {
88 continue;
89 }
90 return candidate;
91 }
92 LOG(FATAL) << ": Failed to find camera calibration for " << node_name
93 << " on " << FLAGS_team_number;
94}
95
Milind Upadhyayc5beba12022-12-17 17:41:20 -080096Eigen::Affine3d CameraExtrinsics(
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080097 const calibration::CameraCalibration *camera_calibration) {
milind-u16e3a082023-01-21 13:53:43 -080098 const frc971::vision::calibration::TransformationMatrix *transform =
99 camera_calibration->has_turret_extrinsics()
100 ? camera_calibration->turret_extrinsics()
101 : camera_calibration->fixed_extrinsics();
102
103 cv::Mat result(
104 4, 4, CV_32F,
105 const_cast<void *>(static_cast<const void *>(transform->data()->data())));
106 result.convertTo(result, CV_64F);
107 CHECK_EQ(result.total(), transform->data()->size());
108
109 Eigen::Matrix4d result_eigen;
110 cv::cv2eigen(result, result_eigen);
111 return Eigen::Affine3d(result_eigen);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800112}
113
114// Get images from pi and pass apriltag positions to HandleAprilTag()
115void HandlePiCaptures(
milind-u09fb1252023-01-28 19:21:41 -0800116 aos::EventLoop *pi_event_loop, aos::logger::LogReader *reader,
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800117 std::vector<DataAdapter::TimestampedDetection>
118 *timestamped_target_detections,
milind-u09fb1252023-01-28 19:21:41 -0800119 std::vector<std::unique_ptr<AprilRoboticsDetector>> *detectors) {
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800120 const aos::FlatbufferSpan<calibration::CalibrationData> calibration_data(
121 CalibrationData());
milind-u09fb1252023-01-28 19:21:41 -0800122
123 const auto node_name = pi_event_loop->node()->name()->string_view();
124 const calibration::CameraCalibration *calibration =
125 FindCameraCalibration(&calibration_data.message(), node_name);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800126 const auto extrinsics = CameraExtrinsics(calibration);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800127
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800128 // TODO(milind): change to /camera once we log at full frequency
129 static constexpr std::string_view kImageChannel = "/camera/decimated";
milind-u09fb1252023-01-28 19:21:41 -0800130 detectors->emplace_back(
131 std::make_unique<AprilRoboticsDetector>(pi_event_loop, kImageChannel));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800132
milind-u09fb1252023-01-28 19:21:41 -0800133 pi_event_loop->MakeWatcher("/camera", [=](const TargetMap &map) {
134 aos::distributed_clock::time_point pi_distributed_time =
135 reader->event_loop_factory()
136 ->GetNodeEventLoopFactory(pi_event_loop->node())
137 ->ToDistributedClock(aos::monotonic_clock::time_point(
138 aos::monotonic_clock::duration(map.monotonic_timestamp_ns())));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800139
milind-u09fb1252023-01-28 19:21:41 -0800140 HandleAprilTag(map, pi_distributed_time, timestamped_target_detections,
141 extrinsics);
142 });
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800143}
144
145void MappingMain(int argc, char *argv[]) {
146 std::vector<std::string> unsorted_logfiles =
147 aos::logger::FindLogs(argc, argv);
148
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800149 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
150
151 // open logfiles
152 aos::logger::LogReader reader(aos::logger::SortParts(unsorted_logfiles));
153 reader.Register();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800154
milind-u09fb1252023-01-28 19:21:41 -0800155 std::vector<std::unique_ptr<AprilRoboticsDetector>> detectors;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800156
157 const aos::Node *pi1 =
158 aos::configuration::GetNode(reader.configuration(), "pi1");
159 std::unique_ptr<aos::EventLoop> pi1_event_loop =
160 reader.event_loop_factory()->MakeEventLoop("pi1", pi1);
milind-u09fb1252023-01-28 19:21:41 -0800161 HandlePiCaptures(pi1_event_loop.get(), &reader,
162 &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800163
164 const aos::Node *pi2 =
165 aos::configuration::GetNode(reader.configuration(), "pi2");
166 std::unique_ptr<aos::EventLoop> pi2_event_loop =
167 reader.event_loop_factory()->MakeEventLoop("pi2", pi2);
milind-u09fb1252023-01-28 19:21:41 -0800168 HandlePiCaptures(pi2_event_loop.get(), &reader,
169 &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800170
171 const aos::Node *pi3 =
172 aos::configuration::GetNode(reader.configuration(), "pi3");
173 std::unique_ptr<aos::EventLoop> pi3_event_loop =
174 reader.event_loop_factory()->MakeEventLoop("pi3", pi3);
milind-u09fb1252023-01-28 19:21:41 -0800175 HandlePiCaptures(pi3_event_loop.get(), &reader,
176 &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800177
178 const aos::Node *pi4 =
179 aos::configuration::GetNode(reader.configuration(), "pi4");
180 std::unique_ptr<aos::EventLoop> pi4_event_loop =
181 reader.event_loop_factory()->MakeEventLoop("pi4", pi4);
milind-u09fb1252023-01-28 19:21:41 -0800182 HandlePiCaptures(pi4_event_loop.get(), &reader,
183 &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800184
185 reader.event_loop_factory()->Run();
186
187 auto target_constraints =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800188 DataAdapter::MatchTargetDetections(timestamped_target_detections);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800189
190 frc971::vision::TargetMapper mapper(FLAGS_json_path, target_constraints);
milind-u09fb1252023-01-28 19:21:41 -0800191 mapper.Solve("charged_up");
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800192
milind-u09fb1252023-01-28 19:21:41 -0800193 // Clean up all the pointers
194 for (auto &detector_ptr : detectors) {
195 detector_ptr.reset();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800196 }
197}
198
199} // namespace vision
milind-u16e3a082023-01-21 13:53:43 -0800200} // namespace y2023
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800201
202int main(int argc, char **argv) {
203 aos::InitGoogle(&argc, &argv);
milind-u16e3a082023-01-21 13:53:43 -0800204 y2023::vision::MappingMain(argc, argv);
Milind Upadhyay915d6002022-12-26 20:37:43 -0800205}