blob: 112696efc6ccc2480fb7d022fc0a86e3ce0b1240 [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"
14#include "y2022/control_loops/superstructure/superstructure_status_generated.h"
15#include "y2022/vision/camera_reader.h"
16
17DEFINE_string(json_path, "target_map.json",
18 "Specify path for json with initial pose guesses.");
Milind Upadhyay915d6002022-12-26 20:37:43 -080019DEFINE_int32(team_number, 971,
20 "Use the calibration for a node with this team number");
21
22DEFINE_bool(
23 use_robot_position, false,
24 "If true, use localizer output messages to get the robot position, and "
25 "superstructure status messages to get the turret angle, at the "
26 "times of target detections. Currently does not work reliably on the box "
27 "of pis.");
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080028
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080029DECLARE_string(image_channel);
30
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080031namespace y2022 {
32namespace vision {
33using frc971::vision::DataAdapter;
34using frc971::vision::PoseUtils;
35using frc971::vision::TargetMapper;
36namespace superstructure = ::y2022::control_loops::superstructure;
37
38// Find transformation from camera to robot reference frame
39Eigen::Affine3d CameraTransform(Eigen::Affine3d fixed_extrinsics,
40 Eigen::Affine3d turret_extrinsics,
41 double turret_position) {
42 // Calculate the pose of the camera relative to the robot origin.
43 Eigen::Affine3d H_robot_camrob =
44 fixed_extrinsics *
45 Eigen::Affine3d(frc971::control_loops::TransformationMatrixForYaw<double>(
46 turret_position)) *
47 turret_extrinsics;
48
49 return H_robot_camrob;
50}
51
52// Change reference frame from camera to robot
53Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camcv_target,
54 Eigen::Affine3d fixed_extrinsics,
55 Eigen::Affine3d turret_extrinsics,
56 double turret_position) {
57 // With X, Y, Z being robot axes and x, y, z being camera axes,
58 // x = -Y, y = -Z, z = X
59 const Eigen::Affine3d H_camcv_camrob =
60 Eigen::Affine3d((Eigen::Matrix4d() << 0.0, -1.0, 0.0, 0.0, 0.0, 0.0, -1.0,
61 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0)
62 .finished());
63
64 const Eigen::Affine3d H_robot_camrob =
65 CameraTransform(fixed_extrinsics, turret_extrinsics, turret_position);
66 const Eigen::Affine3d H_robot_target =
67 H_robot_camrob * H_camcv_camrob.inverse() * H_camcv_target;
68 return H_robot_target;
69}
70
71// Add detected apriltag poses relative to the robot to
72// timestamped_target_detections
Milind Upadhyay915d6002022-12-26 20:37:43 -080073void HandleAprilTag(aos::distributed_clock::time_point pi_distributed_time,
74 std::vector<cv::Vec4i> april_ids,
75 std::vector<Eigen::Vector3d> rvecs_eigen,
76 std::vector<Eigen::Vector3d> tvecs_eigen,
77 std::vector<DataAdapter::TimestampedDetection>
78 *timestamped_target_detections,
79 std::optional<aos::Fetcher<superstructure::Status>>
80 *superstructure_status_fetcher,
81 Eigen::Affine3d fixed_extrinsics,
82 Eigen::Affine3d turret_extrinsics) {
83 double turret_position = 0.0;
84
85 if (superstructure_status_fetcher->has_value()) {
86 CHECK(superstructure_status_fetcher->value().Fetch());
87 turret_position =
88 superstructure_status_fetcher->value().get()->turret()->position();
89 }
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080090
91 for (size_t tag = 0; tag < april_ids.size(); tag++) {
92 Eigen::Translation3d T_camera_target = Eigen::Translation3d(
93 tvecs_eigen[tag][0], tvecs_eigen[tag][1], tvecs_eigen[tag][2]);
94 Eigen::AngleAxisd r_angle = Eigen::AngleAxisd(
95 rvecs_eigen[tag].norm(), rvecs_eigen[tag] / rvecs_eigen[tag].norm());
96 CHECK(rvecs_eigen[tag].norm() != 0) << "rvecs norm = 0; divide by 0";
97 Eigen::Affine3d H_camcv_target = T_camera_target * r_angle;
98
99 Eigen::Affine3d H_robot_target = CameraToRobotDetection(
100 H_camcv_target, fixed_extrinsics, turret_extrinsics, turret_position);
101
102 timestamped_target_detections->emplace_back(
103 DataAdapter::TimestampedDetection{.time = pi_distributed_time,
104 .H_robot_target = H_robot_target,
105 .id = april_ids[tag][0]});
106 }
107}
108
109Eigen::Affine3d CameraFixedExtrinsics(
110 const calibration::CameraCalibration *camera_calibration) {
111 cv::Mat extrinsics(
112 4, 4, CV_32F,
113 const_cast<void *>(static_cast<const void *>(
114 camera_calibration->fixed_extrinsics()->data()->data())));
115 extrinsics.convertTo(extrinsics, CV_64F);
116 CHECK_EQ(extrinsics.total(),
117 camera_calibration->fixed_extrinsics()->data()->size());
118 Eigen::Matrix4d extrinsics_eigen;
119 cv::cv2eigen(extrinsics, extrinsics_eigen);
120 return Eigen::Affine3d(extrinsics_eigen);
121}
122
123Eigen::Affine3d CameraTurretExtrinsics(
124 const calibration::CameraCalibration *camera_calibration) {
125 cv::Mat extrinsics(
126 4, 4, CV_32F,
127 const_cast<void *>(static_cast<const void *>(
128 camera_calibration->turret_extrinsics()->data()->data())));
129 extrinsics.convertTo(extrinsics, CV_64F);
130 CHECK_EQ(extrinsics.total(),
131 camera_calibration->turret_extrinsics()->data()->size());
132 Eigen::Matrix4d extrinsics_eigen;
133 cv::cv2eigen(extrinsics, extrinsics_eigen);
134 return Eigen::Affine3d(extrinsics_eigen);
135}
136
137// Get images from pi and pass apriltag positions to HandleAprilTag()
138void HandlePiCaptures(
139 int pi_number, aos::EventLoop *pi_event_loop,
140 aos::logger::LogReader *reader,
Milind Upadhyay915d6002022-12-26 20:37:43 -0800141 std::optional<aos::Fetcher<superstructure::Status>>
142 *superstructure_status_fetcher,
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800143 std::vector<DataAdapter::TimestampedDetection>
144 *timestamped_target_detections,
145 std::vector<std::unique_ptr<CharucoExtractor>> *charuco_extractors,
146 std::vector<std::unique_ptr<ImageCallback>> *image_callbacks) {
147 const aos::FlatbufferSpan<calibration::CalibrationData> calibration_data(
148 CalibrationData());
149 const calibration::CameraCalibration *calibration =
150 CameraReader::FindCameraCalibration(&calibration_data.message(),
151 "pi" + std::to_string(pi_number),
152 FLAGS_team_number);
153 const auto turret_extrinsics = CameraTurretExtrinsics(calibration);
154 const auto fixed_extrinsics = CameraFixedExtrinsics(calibration);
155
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800156 // TODO(milind): change to /camera once we log at full frequency
157 static constexpr std::string_view kImageChannel = "/camera/decimated";
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800158 charuco_extractors->emplace_back(std::make_unique<CharucoExtractor>(
159 pi_event_loop,
160 "pi-" + std::to_string(FLAGS_team_number) + "-" +
161 std::to_string(pi_number),
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800162 TargetType::kAprilTag, kImageChannel,
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800163 [=](cv::Mat /*rgb_image*/, aos::monotonic_clock::time_point eof,
164 std::vector<cv::Vec4i> april_ids,
165 std::vector<std::vector<cv::Point2f>> /*april_corners*/, bool valid,
166 std::vector<Eigen::Vector3d> rvecs_eigen,
167 std::vector<Eigen::Vector3d> tvecs_eigen) {
168 aos::distributed_clock::time_point pi_distributed_time =
169 reader->event_loop_factory()
170 ->GetNodeEventLoopFactory(pi_event_loop->node())
171 ->ToDistributedClock(eof);
172
173 if (valid) {
174 HandleAprilTag(pi_distributed_time, april_ids, rvecs_eigen,
175 tvecs_eigen, timestamped_target_detections,
176 superstructure_status_fetcher, fixed_extrinsics,
177 turret_extrinsics);
178 }
179 }));
180
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800181 image_callbacks->emplace_back(std::make_unique<ImageCallback>(
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800182 pi_event_loop, kImageChannel,
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800183 [&, charuco_extractor =
184 charuco_extractors->at(charuco_extractors->size() - 1).get()](
185 cv::Mat rgb_image, const aos::monotonic_clock::time_point eof) {
186 charuco_extractor->HandleImage(rgb_image, eof);
187 }));
188}
189
190void MappingMain(int argc, char *argv[]) {
191 std::vector<std::string> unsorted_logfiles =
192 aos::logger::FindLogs(argc, argv);
193
194 std::vector<DataAdapter::TimestampedPose> timestamped_robot_poses;
195 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
196
197 // open logfiles
198 aos::logger::LogReader reader(aos::logger::SortParts(unsorted_logfiles));
199 reader.Register();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800200
Milind Upadhyay915d6002022-12-26 20:37:43 -0800201 std::optional<aos::Fetcher<superstructure::Status>>
202 superstructure_status_fetcher;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800203
Milind Upadhyay915d6002022-12-26 20:37:43 -0800204 if (FLAGS_use_robot_position) {
205 const aos::Node *imu_node =
206 aos::configuration::GetNode(reader.configuration(), "imu");
207 std::unique_ptr<aos::EventLoop> imu_event_loop =
208 reader.event_loop_factory()->MakeEventLoop("imu", imu_node);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800209
Milind Upadhyay915d6002022-12-26 20:37:43 -0800210 imu_event_loop->MakeWatcher(
211 "/localizer", [&](const frc971::controls::LocalizerOutput &localizer) {
212 aos::monotonic_clock::time_point imu_monotonic_time =
213 aos::monotonic_clock::time_point(aos::monotonic_clock::duration(
214 localizer.monotonic_timestamp_ns()));
215 aos::distributed_clock::time_point imu_distributed_time =
216 reader.event_loop_factory()
217 ->GetNodeEventLoopFactory(imu_node)
218 ->ToDistributedClock(imu_monotonic_time);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800219
Milind Upadhyay915d6002022-12-26 20:37:43 -0800220 timestamped_robot_poses.emplace_back(DataAdapter::TimestampedPose{
221 .time = imu_distributed_time,
222 .pose =
223 ceres::examples::Pose2d{.x = localizer.x(),
224 .y = localizer.y(),
225 .yaw_radians = localizer.theta()}});
226 });
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800227
Milind Upadhyay915d6002022-12-26 20:37:43 -0800228 const aos::Node *roborio_node =
229 aos::configuration::GetNode(reader.configuration(), "roborio");
230 std::unique_ptr<aos::EventLoop> roborio_event_loop =
231 reader.event_loop_factory()->MakeEventLoop("roborio", roborio_node);
232
233 superstructure_status_fetcher =
234 roborio_event_loop->MakeFetcher<superstructure::Status>(
235 "/superstructure");
236 }
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800237
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800238 std::vector<std::unique_ptr<CharucoExtractor>> charuco_extractors;
239 std::vector<std::unique_ptr<ImageCallback>> image_callbacks;
240
241 const aos::Node *pi1 =
242 aos::configuration::GetNode(reader.configuration(), "pi1");
243 std::unique_ptr<aos::EventLoop> pi1_event_loop =
244 reader.event_loop_factory()->MakeEventLoop("pi1", pi1);
245 HandlePiCaptures(
246 1, pi1_event_loop.get(), &reader, &superstructure_status_fetcher,
247 &timestamped_target_detections, &charuco_extractors, &image_callbacks);
248
249 const aos::Node *pi2 =
250 aos::configuration::GetNode(reader.configuration(), "pi2");
251 std::unique_ptr<aos::EventLoop> pi2_event_loop =
252 reader.event_loop_factory()->MakeEventLoop("pi2", pi2);
253 HandlePiCaptures(
254 2, pi2_event_loop.get(), &reader, &superstructure_status_fetcher,
255 &timestamped_target_detections, &charuco_extractors, &image_callbacks);
256
257 const aos::Node *pi3 =
258 aos::configuration::GetNode(reader.configuration(), "pi3");
259 std::unique_ptr<aos::EventLoop> pi3_event_loop =
260 reader.event_loop_factory()->MakeEventLoop("pi3", pi3);
261 HandlePiCaptures(
262 3, pi3_event_loop.get(), &reader, &superstructure_status_fetcher,
263 &timestamped_target_detections, &charuco_extractors, &image_callbacks);
264
265 const aos::Node *pi4 =
266 aos::configuration::GetNode(reader.configuration(), "pi4");
267 std::unique_ptr<aos::EventLoop> pi4_event_loop =
268 reader.event_loop_factory()->MakeEventLoop("pi4", pi4);
269 HandlePiCaptures(
270 4, pi4_event_loop.get(), &reader, &superstructure_status_fetcher,
271 &timestamped_target_detections, &charuco_extractors, &image_callbacks);
272
273 reader.event_loop_factory()->Run();
274
275 auto target_constraints =
Milind Upadhyay915d6002022-12-26 20:37:43 -0800276 (FLAGS_use_robot_position
277 ? DataAdapter::MatchTargetDetections(timestamped_robot_poses,
278 timestamped_target_detections)
279 .first
280 : DataAdapter::MatchTargetDetections(timestamped_target_detections));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800281
282 frc971::vision::TargetMapper mapper(FLAGS_json_path, target_constraints);
Yash Chainani03669632022-12-17 19:37:34 -0800283 mapper.Solve("rapid_react");
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800284
285 // Pointers need to be deleted to destruct all fetchers
286 for (auto &charuco_extractor_ptr : charuco_extractors) {
287 charuco_extractor_ptr.reset();
288 }
289
290 for (auto &image_callback_ptr : image_callbacks) {
291 image_callback_ptr.reset();
292 }
293}
294
295} // namespace vision
296} // namespace y2022
297
298int main(int argc, char **argv) {
299 aos::InitGoogle(&argc, &argv);
300 y2022::vision::MappingMain(argc, argv);
Milind Upadhyay915d6002022-12-26 20:37:43 -0800301}