blob: d4c8c50bb68b4dd84d095cdf9a505de82aa09df9 [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-u16e3a082023-01-21 13:53:43 -080015#include "y2023/vision/calibration_data.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080016
17DEFINE_string(json_path, "target_map.json",
18 "Specify path for json with initial pose guesses.");
Milind Upadhyayc5beba12022-12-17 17:41:20 -080019DEFINE_int32(team_number, 7971,
Milind Upadhyay915d6002022-12-26 20:37:43 -080020 "Use the calibration for a node with this team number");
21
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080022DECLARE_string(image_channel);
23
milind-u16e3a082023-01-21 13:53:43 -080024namespace y2023 {
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080025namespace vision {
milind-u16e3a082023-01-21 13:53:43 -080026using frc971::vision::CharucoExtractor;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080027using frc971::vision::DataAdapter;
milind-u16e3a082023-01-21 13:53:43 -080028using frc971::vision::ImageCallback;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080029using frc971::vision::PoseUtils;
30using frc971::vision::TargetMapper;
milind-u16e3a082023-01-21 13:53:43 -080031namespace calibration = frc971::vision::calibration;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080032
33// Change reference frame from camera to robot
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080034Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camrob_target,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080035 Eigen::Affine3d extrinsics) {
36 const Eigen::Affine3d H_robot_camrob = extrinsics;
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080037 const Eigen::Affine3d H_robot_target = H_robot_camrob * H_camrob_target;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080038 return H_robot_target;
39}
40
41// Add detected apriltag poses relative to the robot to
42// timestamped_target_detections
Milind Upadhyay915d6002022-12-26 20:37:43 -080043void HandleAprilTag(aos::distributed_clock::time_point pi_distributed_time,
44 std::vector<cv::Vec4i> april_ids,
45 std::vector<Eigen::Vector3d> rvecs_eigen,
46 std::vector<Eigen::Vector3d> tvecs_eigen,
47 std::vector<DataAdapter::TimestampedDetection>
48 *timestamped_target_detections,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080049 Eigen::Affine3d extrinsics) {
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080050 for (size_t tag = 0; tag < april_ids.size(); tag++) {
51 Eigen::Translation3d T_camera_target = Eigen::Translation3d(
52 tvecs_eigen[tag][0], tvecs_eigen[tag][1], tvecs_eigen[tag][2]);
53 Eigen::AngleAxisd r_angle = Eigen::AngleAxisd(
54 rvecs_eigen[tag].norm(), rvecs_eigen[tag] / rvecs_eigen[tag].norm());
55 CHECK(rvecs_eigen[tag].norm() != 0) << "rvecs norm = 0; divide by 0";
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080056
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080057 Eigen::Affine3d H_camcv_target = T_camera_target * r_angle;
58 // With X, Y, Z being robot axes and x, y, z being camera axes,
59 // x = -Y, y = -Z, z = X
60 static const Eigen::Affine3d H_camcv_camrob =
61 Eigen::Affine3d((Eigen::Matrix4d() << 0.0, -1.0, 0.0, 0.0, 0.0, 0.0,
62 -1.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0)
63 .finished());
64 Eigen::Affine3d H_camrob_target = H_camcv_camrob.inverse() * H_camcv_target;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080065 Eigen::Affine3d H_robot_target =
66 CameraToRobotDetection(H_camrob_target, extrinsics);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080067
Milind Upadhyayc5beba12022-12-17 17:41:20 -080068 ceres::examples::Pose3d target_pose_camera =
69 PoseUtils::Affine3dToPose3d(H_camrob_target);
70 double distance_from_camera = target_pose_camera.p.norm();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080071
72 timestamped_target_detections->emplace_back(
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080073 DataAdapter::TimestampedDetection{
74 .time = pi_distributed_time,
75 .H_robot_target = H_robot_target,
76 .distance_from_camera = distance_from_camera,
77 .id = april_ids[tag][0]});
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080078 }
79}
80
milind-u16e3a082023-01-21 13:53:43 -080081const calibration::CameraCalibration *FindCameraCalibration(
82 const calibration::CalibrationData *calibration_data,
83 std::string_view node_name) {
84 for (const calibration::CameraCalibration *candidate :
85 *calibration_data->camera_calibrations()) {
86 if (candidate->node_name()->string_view() != node_name) {
87 continue;
88 }
89 if (candidate->team_number() != FLAGS_team_number) {
90 continue;
91 }
92 return candidate;
93 }
94 LOG(FATAL) << ": Failed to find camera calibration for " << node_name
95 << " on " << FLAGS_team_number;
96}
97
Milind Upadhyayc5beba12022-12-17 17:41:20 -080098Eigen::Affine3d CameraExtrinsics(
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080099 const calibration::CameraCalibration *camera_calibration) {
milind-u16e3a082023-01-21 13:53:43 -0800100 const frc971::vision::calibration::TransformationMatrix *transform =
101 camera_calibration->has_turret_extrinsics()
102 ? camera_calibration->turret_extrinsics()
103 : camera_calibration->fixed_extrinsics();
104
105 cv::Mat result(
106 4, 4, CV_32F,
107 const_cast<void *>(static_cast<const void *>(transform->data()->data())));
108 result.convertTo(result, CV_64F);
109 CHECK_EQ(result.total(), transform->data()->size());
110
111 Eigen::Matrix4d result_eigen;
112 cv::cv2eigen(result, result_eigen);
113 return Eigen::Affine3d(result_eigen);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800114}
115
116// Get images from pi and pass apriltag positions to HandleAprilTag()
117void HandlePiCaptures(
118 int pi_number, aos::EventLoop *pi_event_loop,
119 aos::logger::LogReader *reader,
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800120 std::vector<DataAdapter::TimestampedDetection>
121 *timestamped_target_detections,
122 std::vector<std::unique_ptr<CharucoExtractor>> *charuco_extractors,
123 std::vector<std::unique_ptr<ImageCallback>> *image_callbacks) {
124 const aos::FlatbufferSpan<calibration::CalibrationData> calibration_data(
125 CalibrationData());
milind-u16e3a082023-01-21 13:53:43 -0800126 const calibration::CameraCalibration *calibration = FindCameraCalibration(
127 &calibration_data.message(), "pi" + std::to_string(pi_number));
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800128 const auto extrinsics = CameraExtrinsics(calibration);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800129
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800130 // TODO(milind): change to /camera once we log at full frequency
131 static constexpr std::string_view kImageChannel = "/camera/decimated";
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800132 charuco_extractors->emplace_back(std::make_unique<CharucoExtractor>(
133 pi_event_loop,
134 "pi-" + std::to_string(FLAGS_team_number) + "-" +
135 std::to_string(pi_number),
milind-u16e3a082023-01-21 13:53:43 -0800136 frc971::vision::TargetType::kAprilTag, kImageChannel,
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800137 [=](cv::Mat /*rgb_image*/, aos::monotonic_clock::time_point eof,
138 std::vector<cv::Vec4i> april_ids,
139 std::vector<std::vector<cv::Point2f>> /*april_corners*/, bool valid,
140 std::vector<Eigen::Vector3d> rvecs_eigen,
141 std::vector<Eigen::Vector3d> tvecs_eigen) {
142 aos::distributed_clock::time_point pi_distributed_time =
143 reader->event_loop_factory()
144 ->GetNodeEventLoopFactory(pi_event_loop->node())
145 ->ToDistributedClock(eof);
146
147 if (valid) {
148 HandleAprilTag(pi_distributed_time, april_ids, rvecs_eigen,
149 tvecs_eigen, timestamped_target_detections,
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800150 extrinsics);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800151 }
152 }));
153
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800154 image_callbacks->emplace_back(std::make_unique<ImageCallback>(
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800155 pi_event_loop, kImageChannel,
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800156 [&, charuco_extractor =
157 charuco_extractors->at(charuco_extractors->size() - 1).get()](
158 cv::Mat rgb_image, const aos::monotonic_clock::time_point eof) {
159 charuco_extractor->HandleImage(rgb_image, eof);
160 }));
161}
162
163void MappingMain(int argc, char *argv[]) {
164 std::vector<std::string> unsorted_logfiles =
165 aos::logger::FindLogs(argc, argv);
166
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800167 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
168
169 // open logfiles
170 aos::logger::LogReader reader(aos::logger::SortParts(unsorted_logfiles));
171 reader.Register();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800172
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800173 std::vector<std::unique_ptr<CharucoExtractor>> charuco_extractors;
174 std::vector<std::unique_ptr<ImageCallback>> image_callbacks;
175
176 const aos::Node *pi1 =
177 aos::configuration::GetNode(reader.configuration(), "pi1");
178 std::unique_ptr<aos::EventLoop> pi1_event_loop =
179 reader.event_loop_factory()->MakeEventLoop("pi1", pi1);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800180 HandlePiCaptures(1, pi1_event_loop.get(), &reader,
181 &timestamped_target_detections, &charuco_extractors,
182 &image_callbacks);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800183
184 const aos::Node *pi2 =
185 aos::configuration::GetNode(reader.configuration(), "pi2");
186 std::unique_ptr<aos::EventLoop> pi2_event_loop =
187 reader.event_loop_factory()->MakeEventLoop("pi2", pi2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800188 HandlePiCaptures(2, pi2_event_loop.get(), &reader,
189 &timestamped_target_detections, &charuco_extractors,
190 &image_callbacks);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800191
192 const aos::Node *pi3 =
193 aos::configuration::GetNode(reader.configuration(), "pi3");
194 std::unique_ptr<aos::EventLoop> pi3_event_loop =
195 reader.event_loop_factory()->MakeEventLoop("pi3", pi3);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800196 HandlePiCaptures(3, pi3_event_loop.get(), &reader,
197 &timestamped_target_detections, &charuco_extractors,
198 &image_callbacks);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800199
200 const aos::Node *pi4 =
201 aos::configuration::GetNode(reader.configuration(), "pi4");
202 std::unique_ptr<aos::EventLoop> pi4_event_loop =
203 reader.event_loop_factory()->MakeEventLoop("pi4", pi4);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800204 HandlePiCaptures(4, pi4_event_loop.get(), &reader,
205 &timestamped_target_detections, &charuco_extractors,
206 &image_callbacks);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800207
208 reader.event_loop_factory()->Run();
209
210 auto target_constraints =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800211 DataAdapter::MatchTargetDetections(timestamped_target_detections);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800212
213 frc971::vision::TargetMapper mapper(FLAGS_json_path, target_constraints);
Yash Chainani03669632022-12-17 19:37:34 -0800214 mapper.Solve("rapid_react");
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800215
216 // Pointers need to be deleted to destruct all fetchers
217 for (auto &charuco_extractor_ptr : charuco_extractors) {
218 charuco_extractor_ptr.reset();
219 }
220
221 for (auto &image_callback_ptr : image_callbacks) {
222 image_callback_ptr.reset();
223 }
224}
225
226} // namespace vision
milind-u16e3a082023-01-21 13:53:43 -0800227} // namespace y2023
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800228
229int main(int argc, char **argv) {
230 aos::InitGoogle(&argc, &argv);
milind-u16e3a082023-01-21 13:53:43 -0800231 y2023::vision::MappingMain(argc, argv);
Milind Upadhyay915d6002022-12-26 20:37:43 -0800232}