blob: 529e330e877dfb14350d8c6971dde7bcad840af0 [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"
5#include "frc971/vision/charuco_lib.h"
6#include "frc971/vision/target_mapper.h"
7#include "opencv2/aruco.hpp"
8#include "opencv2/calib3d.hpp"
9#include "opencv2/core/eigen.hpp"
10#include "opencv2/features2d.hpp"
11#include "opencv2/highgui.hpp"
12#include "opencv2/highgui/highgui.hpp"
13#include "opencv2/imgproc.hpp"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080014#include "y2022/vision/camera_reader.h"
15
16DEFINE_string(json_path, "target_map.json",
17 "Specify path for json with initial pose guesses.");
Milind Upadhyayc5beba12022-12-17 17:41:20 -080018DEFINE_int32(team_number, 7971,
Milind Upadhyay915d6002022-12-26 20:37:43 -080019 "Use the calibration for a node with this team number");
20
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080021DECLARE_string(image_channel);
22
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080023namespace y2022 {
24namespace vision {
25using frc971::vision::DataAdapter;
26using frc971::vision::PoseUtils;
27using frc971::vision::TargetMapper;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080028
29// Change reference frame from camera to robot
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080030Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camrob_target,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080031 Eigen::Affine3d extrinsics) {
32 const Eigen::Affine3d H_robot_camrob = extrinsics;
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080033 const Eigen::Affine3d H_robot_target = H_robot_camrob * H_camrob_target;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080034 return H_robot_target;
35}
36
37// Add detected apriltag poses relative to the robot to
38// timestamped_target_detections
Milind Upadhyay915d6002022-12-26 20:37:43 -080039void HandleAprilTag(aos::distributed_clock::time_point pi_distributed_time,
40 std::vector<cv::Vec4i> april_ids,
41 std::vector<Eigen::Vector3d> rvecs_eigen,
42 std::vector<Eigen::Vector3d> tvecs_eigen,
43 std::vector<DataAdapter::TimestampedDetection>
44 *timestamped_target_detections,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080045 Eigen::Affine3d extrinsics) {
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080046 for (size_t tag = 0; tag < april_ids.size(); tag++) {
47 Eigen::Translation3d T_camera_target = Eigen::Translation3d(
48 tvecs_eigen[tag][0], tvecs_eigen[tag][1], tvecs_eigen[tag][2]);
49 Eigen::AngleAxisd r_angle = Eigen::AngleAxisd(
50 rvecs_eigen[tag].norm(), rvecs_eigen[tag] / rvecs_eigen[tag].norm());
51 CHECK(rvecs_eigen[tag].norm() != 0) << "rvecs norm = 0; divide by 0";
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080052
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080053 Eigen::Affine3d H_camcv_target = T_camera_target * r_angle;
54 // With X, Y, Z being robot axes and x, y, z being camera axes,
55 // x = -Y, y = -Z, z = X
56 static const Eigen::Affine3d H_camcv_camrob =
57 Eigen::Affine3d((Eigen::Matrix4d() << 0.0, -1.0, 0.0, 0.0, 0.0, 0.0,
58 -1.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0)
59 .finished());
60 Eigen::Affine3d H_camrob_target = H_camcv_camrob.inverse() * H_camcv_target;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080061 Eigen::Affine3d H_robot_target =
62 CameraToRobotDetection(H_camrob_target, extrinsics);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080063
Milind Upadhyayc5beba12022-12-17 17:41:20 -080064 ceres::examples::Pose3d target_pose_camera =
65 PoseUtils::Affine3dToPose3d(H_camrob_target);
66 double distance_from_camera = target_pose_camera.p.norm();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080067
68 timestamped_target_detections->emplace_back(
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080069 DataAdapter::TimestampedDetection{
70 .time = pi_distributed_time,
71 .H_robot_target = H_robot_target,
72 .distance_from_camera = distance_from_camera,
73 .id = april_ids[tag][0]});
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080074 }
75}
76
Milind Upadhyayc5beba12022-12-17 17:41:20 -080077Eigen::Affine3d CameraExtrinsics(
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080078 const calibration::CameraCalibration *camera_calibration) {
Milind Upadhyayc5beba12022-12-17 17:41:20 -080079 cv::Mat extrinsics = CameraReader::CameraExtrinsics(camera_calibration);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080080 Eigen::Matrix4d extrinsics_eigen;
81 cv::cv2eigen(extrinsics, extrinsics_eigen);
82 return Eigen::Affine3d(extrinsics_eigen);
83}
84
85// Get images from pi and pass apriltag positions to HandleAprilTag()
86void HandlePiCaptures(
87 int pi_number, aos::EventLoop *pi_event_loop,
88 aos::logger::LogReader *reader,
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080089 std::vector<DataAdapter::TimestampedDetection>
90 *timestamped_target_detections,
91 std::vector<std::unique_ptr<CharucoExtractor>> *charuco_extractors,
92 std::vector<std::unique_ptr<ImageCallback>> *image_callbacks) {
93 const aos::FlatbufferSpan<calibration::CalibrationData> calibration_data(
94 CalibrationData());
95 const calibration::CameraCalibration *calibration =
96 CameraReader::FindCameraCalibration(&calibration_data.message(),
97 "pi" + std::to_string(pi_number),
98 FLAGS_team_number);
Milind Upadhyayc5beba12022-12-17 17:41:20 -080099 const auto extrinsics = CameraExtrinsics(calibration);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800100
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800101 // TODO(milind): change to /camera once we log at full frequency
102 static constexpr std::string_view kImageChannel = "/camera/decimated";
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800103 charuco_extractors->emplace_back(std::make_unique<CharucoExtractor>(
104 pi_event_loop,
105 "pi-" + std::to_string(FLAGS_team_number) + "-" +
106 std::to_string(pi_number),
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800107 TargetType::kAprilTag, kImageChannel,
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800108 [=](cv::Mat /*rgb_image*/, aos::monotonic_clock::time_point eof,
109 std::vector<cv::Vec4i> april_ids,
110 std::vector<std::vector<cv::Point2f>> /*april_corners*/, bool valid,
111 std::vector<Eigen::Vector3d> rvecs_eigen,
112 std::vector<Eigen::Vector3d> tvecs_eigen) {
113 aos::distributed_clock::time_point pi_distributed_time =
114 reader->event_loop_factory()
115 ->GetNodeEventLoopFactory(pi_event_loop->node())
116 ->ToDistributedClock(eof);
117
118 if (valid) {
119 HandleAprilTag(pi_distributed_time, april_ids, rvecs_eigen,
120 tvecs_eigen, timestamped_target_detections,
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800121 extrinsics);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800122 }
123 }));
124
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800125 image_callbacks->emplace_back(std::make_unique<ImageCallback>(
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800126 pi_event_loop, kImageChannel,
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800127 [&, charuco_extractor =
128 charuco_extractors->at(charuco_extractors->size() - 1).get()](
129 cv::Mat rgb_image, const aos::monotonic_clock::time_point eof) {
130 charuco_extractor->HandleImage(rgb_image, eof);
131 }));
132}
133
134void MappingMain(int argc, char *argv[]) {
135 std::vector<std::string> unsorted_logfiles =
136 aos::logger::FindLogs(argc, argv);
137
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800138 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
139
140 // open logfiles
141 aos::logger::LogReader reader(aos::logger::SortParts(unsorted_logfiles));
142 reader.Register();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800143
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800144 std::vector<std::unique_ptr<CharucoExtractor>> charuco_extractors;
145 std::vector<std::unique_ptr<ImageCallback>> image_callbacks;
146
147 const aos::Node *pi1 =
148 aos::configuration::GetNode(reader.configuration(), "pi1");
149 std::unique_ptr<aos::EventLoop> pi1_event_loop =
150 reader.event_loop_factory()->MakeEventLoop("pi1", pi1);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800151 HandlePiCaptures(1, pi1_event_loop.get(), &reader,
152 &timestamped_target_detections, &charuco_extractors,
153 &image_callbacks);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800154
155 const aos::Node *pi2 =
156 aos::configuration::GetNode(reader.configuration(), "pi2");
157 std::unique_ptr<aos::EventLoop> pi2_event_loop =
158 reader.event_loop_factory()->MakeEventLoop("pi2", pi2);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800159 HandlePiCaptures(2, pi2_event_loop.get(), &reader,
160 &timestamped_target_detections, &charuco_extractors,
161 &image_callbacks);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800162
163 const aos::Node *pi3 =
164 aos::configuration::GetNode(reader.configuration(), "pi3");
165 std::unique_ptr<aos::EventLoop> pi3_event_loop =
166 reader.event_loop_factory()->MakeEventLoop("pi3", pi3);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800167 HandlePiCaptures(3, pi3_event_loop.get(), &reader,
168 &timestamped_target_detections, &charuco_extractors,
169 &image_callbacks);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800170
171 const aos::Node *pi4 =
172 aos::configuration::GetNode(reader.configuration(), "pi4");
173 std::unique_ptr<aos::EventLoop> pi4_event_loop =
174 reader.event_loop_factory()->MakeEventLoop("pi4", pi4);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800175 HandlePiCaptures(4, pi4_event_loop.get(), &reader,
176 &timestamped_target_detections, &charuco_extractors,
177 &image_callbacks);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800178
179 reader.event_loop_factory()->Run();
180
181 auto target_constraints =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800182 DataAdapter::MatchTargetDetections(timestamped_target_detections);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800183
184 frc971::vision::TargetMapper mapper(FLAGS_json_path, target_constraints);
Yash Chainani03669632022-12-17 19:37:34 -0800185 mapper.Solve("rapid_react");
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800186
187 // Pointers need to be deleted to destruct all fetchers
188 for (auto &charuco_extractor_ptr : charuco_extractors) {
189 charuco_extractor_ptr.reset();
190 }
191
192 for (auto &image_callback_ptr : image_callbacks) {
193 image_callback_ptr.reset();
194 }
195}
196
197} // namespace vision
198} // namespace y2022
199
200int main(int argc, char **argv) {
201 aos::InitGoogle(&argc, &argv);
202 y2022::vision::MappingMain(argc, argv);
Milind Upadhyay915d6002022-12-26 20:37:43 -0800203}