blob: f1ab4fce7501fde0490c6faf05e45da19609108e [file] [log] [blame]
Austin Schuhdcb6b362022-02-25 18:06:21 -08001#include "frc971/vision/calibration_accumulator.h"
milind-u8c72d532021-12-11 15:02:42 -08002
Jim Ostrowskib3cab972022-12-03 15:47:00 -08003#include <algorithm>
4#include <limits>
5#include <opencv2/highgui/highgui.hpp>
6
milind-u8c72d532021-12-11 15:02:42 -08007#include "Eigen/Dense"
8#include "aos/events/simulated_event_loop.h"
Jim Ostrowskib3cab972022-12-03 15:47:00 -08009#include "aos/network/team_number.h"
milind-u8c72d532021-12-11 15:02:42 -080010#include "aos/time/time.h"
11#include "frc971/control_loops/quaternion_utils.h"
Austin Schuhdcb6b362022-02-25 18:06:21 -080012#include "frc971/vision/charuco_lib.h"
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080013#include "frc971/wpilib/imu_batch_generated.h"
14
milind-u8c72d532021-12-11 15:02:42 -080015DEFINE_bool(display_undistorted, false,
16 "If true, display the undistorted image.");
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080017DEFINE_string(save_path, "", "Where to store annotated images");
18DEFINE_bool(save_valid_only, false,
19 "If true, only save images with valid pose estimates");
milind-u8c72d532021-12-11 15:02:42 -080020
21namespace frc971 {
22namespace vision {
23using aos::distributed_clock;
24using aos::monotonic_clock;
25namespace chrono = std::chrono;
26
Austin Schuh5b379072021-12-26 16:01:04 -080027constexpr double kG = 9.807;
28
milind-u8c72d532021-12-11 15:02:42 -080029void CalibrationData::AddCameraPose(
30 distributed_clock::time_point distributed_now, Eigen::Vector3d rvec,
31 Eigen::Vector3d tvec) {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080032 // Always start with IMU (or turret) reading...
33 // Note, we may not have a turret, so need to handle that case
34 // If we later get a turret point, then we handle removal of camera points in
35 // AddTurret
36 if ((!imu_points_.empty() && imu_points_[0].first < distributed_now) &&
37 (turret_points_.empty() || turret_points_[0].first < distributed_now)) {
Austin Schuh5b379072021-12-26 16:01:04 -080038 rot_trans_points_.emplace_back(distributed_now, std::make_pair(rvec, tvec));
39 }
milind-u8c72d532021-12-11 15:02:42 -080040}
41
42void CalibrationData::AddImu(distributed_clock::time_point distributed_now,
43 Eigen::Vector3d gyro, Eigen::Vector3d accel) {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080044 double zero_threshold = 1e-12;
45 // We seem to be getting 0 readings on IMU, so ignore for now
46 // TODO<Jim>: I think this has been resolved in HandleIMU, but want to leave
47 // this here just in case there are other ways this could happen
48 if ((fabs(accel(0)) < zero_threshold) && (fabs(accel(1)) < zero_threshold) &&
49 (fabs(accel(2)) < zero_threshold)) {
50 LOG(FATAL) << "Ignoring zero value from IMU accelerometer: " << accel
51 << " (gyro is " << gyro << ")";
52 } else {
53 imu_points_.emplace_back(distributed_now, std::make_pair(gyro, accel));
54 }
milind-u8c72d532021-12-11 15:02:42 -080055}
56
Austin Schuh2895f4c2022-02-26 16:38:46 -080057void CalibrationData::AddTurret(
58 aos::distributed_clock::time_point distributed_now, Eigen::Vector2d state) {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080059 // We want the turret to be known too when solving. But, we don't know if
60 // we are going to have a turret until we get the first reading. In that
61 // case, blow away any camera readings from before.
62 // NOTE: Since the IMU motion is independent of the turret position, we don't
63 // need to remove the IMU readings before the turret
64 if (turret_points_.empty()) {
65 while (!rot_trans_points_.empty() &&
66 rot_trans_points_[0].first < distributed_now) {
67 LOG(INFO) << "Erasing, distributed " << distributed_now;
68 rot_trans_points_.erase(rot_trans_points_.begin());
69 }
Austin Schuh2895f4c2022-02-26 16:38:46 -080070 }
71 turret_points_.emplace_back(distributed_now, state);
72}
73
Austin Schuhdcb6b362022-02-25 18:06:21 -080074void CalibrationData::ReviewData(CalibrationDataObserver *observer) const {
milind-u8c72d532021-12-11 15:02:42 -080075 size_t next_camera_point = 0;
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080076 size_t next_imu_point = 0;
77 size_t next_turret_point = 0;
78
79 // Just go until one of the data streams runs out. We lose a few points, but
80 // it makes the logic much easier
81 while (
82 next_camera_point != rot_trans_points_.size() &&
83 next_imu_point != imu_points_.size() &&
84 (turret_points_.empty() || next_turret_point != turret_points_.size())) {
85 // If camera_point is next, update it
86 if ((rot_trans_points_[next_camera_point].first <=
87 imu_points_[next_imu_point].first) &&
88 (turret_points_.empty() ||
89 (rot_trans_points_[next_camera_point].first <=
90 turret_points_[next_turret_point].first))) {
91 // Camera!
92 observer->UpdateCamera(rot_trans_points_[next_camera_point].first,
93 rot_trans_points_[next_camera_point].second);
94 ++next_camera_point;
95 } else {
96 // If it's not the camera, check if IMU is next
97 if (turret_points_.empty() || (imu_points_[next_imu_point].first <=
98 turret_points_[next_turret_point].first)) {
99 // IMU!
100 observer->UpdateIMU(imu_points_[next_imu_point].first,
101 imu_points_[next_imu_point].second);
102 ++next_imu_point;
milind-u8c72d532021-12-11 15:02:42 -0800103 } else {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800104 // If it's not IMU or camera, and turret_points is not empty, it must be
105 // the turret!
106 observer->UpdateTurret(turret_points_[next_turret_point].first,
107 turret_points_[next_turret_point].second);
108 ++next_turret_point;
milind-u8c72d532021-12-11 15:02:42 -0800109 }
110 }
111 }
112}
113
114Calibration::Calibration(aos::SimulatedEventLoopFactory *event_loop_factory,
115 aos::EventLoop *image_event_loop,
116 aos::EventLoop *imu_event_loop, std::string_view pi,
117 CalibrationData *data)
118 : image_event_loop_(image_event_loop),
119 image_factory_(event_loop_factory->GetNodeEventLoopFactory(
120 image_event_loop_->node())),
121 imu_event_loop_(imu_event_loop),
122 imu_factory_(
123 event_loop_factory->GetNodeEventLoopFactory(imu_event_loop_->node())),
124 charuco_extractor_(
125 image_event_loop_, pi,
126 [this](cv::Mat rgb_image, monotonic_clock::time_point eof,
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800127 std::vector<cv::Vec4i> charuco_ids,
128 std::vector<std::vector<cv::Point2f>> charuco_corners,
129 bool valid, std::vector<Eigen::Vector3d> rvecs_eigen,
130 std::vector<Eigen::Vector3d> tvecs_eigen) {
milind-u8c72d532021-12-11 15:02:42 -0800131 HandleCharuco(rgb_image, eof, charuco_ids, charuco_corners, valid,
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800132 rvecs_eigen, tvecs_eigen);
133 }),
134 image_callback_(
135 image_event_loop_,
136 absl::StrCat("/pi",
137 std::to_string(aos::network::ParsePiNumber(pi).value()),
138 "/camera"),
139 [this](cv::Mat rgb_image, const monotonic_clock::time_point eof) {
140 charuco_extractor_.HandleImage(rgb_image, eof);
milind-u8c72d532021-12-11 15:02:42 -0800141 }),
142 data_(data) {
143 imu_factory_->OnShutdown([]() { cv::destroyAllWindows(); });
144
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800145 // Check for IMUValuesBatch topic on both /localizer and /drivetrain channels,
146 // since both are valid/possible
147 std::string imu_channel;
148 if (imu_event_loop->HasChannel<frc971::IMUValuesBatch>("/localizer")) {
149 imu_channel = "/localizer";
150 } else if (imu_event_loop->HasChannel<frc971::IMUValuesBatch>(
151 "/drivetrain")) {
152 imu_channel = "/drivetrain";
153 } else {
154 LOG(FATAL) << "Couldn't find channel with IMU data for either localizer or "
155 "drivtrain";
156 }
157
158 VLOG(2) << "Listening for " << frc971::IMUValuesBatch::GetFullyQualifiedName()
159 << " on channel: " << imu_channel;
160
milind-u8c72d532021-12-11 15:02:42 -0800161 imu_event_loop_->MakeWatcher(
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800162 imu_channel, [this](const frc971::IMUValuesBatch &imu) {
milind-u8c72d532021-12-11 15:02:42 -0800163 if (!imu.has_readings()) {
164 return;
165 }
166 for (const frc971::IMUValues *value : *imu.readings()) {
167 HandleIMU(value);
168 }
169 });
170}
171
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800172void Calibration::HandleCharuco(
173 cv::Mat rgb_image, const monotonic_clock::time_point eof,
174 std::vector<cv::Vec4i> /*charuco_ids*/,
175 std::vector<std::vector<cv::Point2f>> /*charuco_corners*/, bool valid,
176 std::vector<Eigen::Vector3d> rvecs_eigen,
177 std::vector<Eigen::Vector3d> tvecs_eigen) {
milind-u8c72d532021-12-11 15:02:42 -0800178 if (valid) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800179 CHECK(rvecs_eigen.size() > 0) << "Require at least one target detected";
180 // We only use one (the first) target detected for calibration
181 data_->AddCameraPose(image_factory_->ToDistributedClock(eof),
182 rvecs_eigen[0], tvecs_eigen[0]);
milind-u8c72d532021-12-11 15:02:42 -0800183
milind-u8c72d532021-12-11 15:02:42 -0800184 Eigen::IOFormat HeavyFmt(Eigen::FullPrecision, 0, ", ", ",\n", "[", "]",
185 "[", "]");
186
187 const double age_double =
188 std::chrono::duration_cast<std::chrono::duration<double>>(
189 image_event_loop_->monotonic_now() - eof)
190 .count();
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800191 VLOG(1) << std::fixed << std::setprecision(6) << "Age: " << age_double
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800192 << ", Pose is R:" << rvecs_eigen[0].transpose().format(HeavyFmt)
193 << "\nT:" << tvecs_eigen[0].transpose().format(HeavyFmt);
milind-u8c72d532021-12-11 15:02:42 -0800194 }
195
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800196 if (FLAGS_visualize) {
197 if (FLAGS_display_undistorted) {
198 const cv::Size image_size(rgb_image.cols, rgb_image.rows);
199 cv::Mat undistorted_rgb_image(image_size, CV_8UC3);
200 cv::undistort(rgb_image, undistorted_rgb_image,
201 charuco_extractor_.camera_matrix(),
202 charuco_extractor_.dist_coeffs());
milind-u8c72d532021-12-11 15:02:42 -0800203
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800204 cv::imshow("Display undist", undistorted_rgb_image);
205 }
milind-u8c72d532021-12-11 15:02:42 -0800206
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800207 cv::imshow("Display", rgb_image);
208 cv::waitKey(1);
milind-u8c72d532021-12-11 15:02:42 -0800209 }
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800210
211 if (FLAGS_save_path != "") {
212 if (!FLAGS_save_valid_only || valid) {
213 static int img_count = 0;
214 std::string image_name = absl::StrFormat("/img_%06d.png", img_count);
215 std::string path = FLAGS_save_path + image_name;
216 VLOG(2) << "Saving image to " << path;
217 cv::imwrite(path, rgb_image);
218 img_count++;
219 }
220 }
milind-u8c72d532021-12-11 15:02:42 -0800221}
222
223void Calibration::HandleIMU(const frc971::IMUValues *imu) {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800224 // Need to check for valid values, since we sometimes don't get them
225 if (!imu->has_gyro_x() || !imu->has_gyro_y() || !imu->has_gyro_z() ||
226 !imu->has_accelerometer_x() || !imu->has_accelerometer_y() ||
227 !imu->has_accelerometer_z()) {
228 return;
229 }
230
231 VLOG(2) << "IMU " << imu;
milind-u8c72d532021-12-11 15:02:42 -0800232 imu->UnPackTo(&last_value_);
233 Eigen::Vector3d gyro(last_value_.gyro_x, last_value_.gyro_y,
234 last_value_.gyro_z);
235 Eigen::Vector3d accel(last_value_.accelerometer_x,
236 last_value_.accelerometer_y,
237 last_value_.accelerometer_z);
238
239 data_->AddImu(imu_factory_->ToDistributedClock(monotonic_clock::time_point(
240 chrono::nanoseconds(imu->monotonic_timestamp_ns()))),
Austin Schuh5b379072021-12-26 16:01:04 -0800241 gyro, accel * kG);
milind-u8c72d532021-12-11 15:02:42 -0800242}
243
244} // namespace vision
245} // namespace frc971