blob: 3b0bcc6dc95fae8cf1901ba927a586d94455b9ea [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>
Jim Ostrowskib3cab972022-12-03 15:47:00 -08005
milind-u8c72d532021-12-11 15:02:42 -08006#include "Eigen/Dense"
Philipp Schrader790cb542023-07-05 21:06:52 -07007#include "external/com_github_foxglove_schemas/CompressedImage_schema.h"
8#include "external/com_github_foxglove_schemas/ImageAnnotations_schema.h"
9#include <opencv2/highgui/highgui.hpp>
10
milind-u8c72d532021-12-11 15:02:42 -080011#include "aos/events/simulated_event_loop.h"
Jim Ostrowskib3cab972022-12-03 15:47:00 -080012#include "aos/network/team_number.h"
milind-u8c72d532021-12-11 15:02:42 -080013#include "aos/time/time.h"
14#include "frc971/control_loops/quaternion_utils.h"
Austin Schuhdcb6b362022-02-25 18:06:21 -080015#include "frc971/vision/charuco_lib.h"
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080016#include "frc971/wpilib/imu_batch_generated.h"
17
milind-u8c72d532021-12-11 15:02:42 -080018DEFINE_bool(display_undistorted, false,
19 "If true, display the undistorted image.");
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080020DEFINE_string(save_path, "", "Where to store annotated images");
21DEFINE_bool(save_valid_only, false,
22 "If true, only save images with valid pose estimates");
milind-u8c72d532021-12-11 15:02:42 -080023
24namespace frc971 {
25namespace vision {
26using aos::distributed_clock;
27using aos::monotonic_clock;
28namespace chrono = std::chrono;
29
Austin Schuh5b379072021-12-26 16:01:04 -080030constexpr double kG = 9.807;
31
milind-u8c72d532021-12-11 15:02:42 -080032void CalibrationData::AddCameraPose(
33 distributed_clock::time_point distributed_now, Eigen::Vector3d rvec,
34 Eigen::Vector3d tvec) {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080035 // Always start with IMU (or turret) reading...
36 // Note, we may not have a turret, so need to handle that case
37 // If we later get a turret point, then we handle removal of camera points in
38 // AddTurret
39 if ((!imu_points_.empty() && imu_points_[0].first < distributed_now) &&
40 (turret_points_.empty() || turret_points_[0].first < distributed_now)) {
Austin Schuh5b379072021-12-26 16:01:04 -080041 rot_trans_points_.emplace_back(distributed_now, std::make_pair(rvec, tvec));
42 }
milind-u8c72d532021-12-11 15:02:42 -080043}
44
45void CalibrationData::AddImu(distributed_clock::time_point distributed_now,
46 Eigen::Vector3d gyro, Eigen::Vector3d accel) {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080047 double zero_threshold = 1e-12;
48 // We seem to be getting 0 readings on IMU, so ignore for now
49 // TODO<Jim>: I think this has been resolved in HandleIMU, but want to leave
50 // this here just in case there are other ways this could happen
51 if ((fabs(accel(0)) < zero_threshold) && (fabs(accel(1)) < zero_threshold) &&
52 (fabs(accel(2)) < zero_threshold)) {
53 LOG(FATAL) << "Ignoring zero value from IMU accelerometer: " << accel
54 << " (gyro is " << gyro << ")";
55 } else {
56 imu_points_.emplace_back(distributed_now, std::make_pair(gyro, accel));
57 }
milind-u8c72d532021-12-11 15:02:42 -080058}
59
Austin Schuh2895f4c2022-02-26 16:38:46 -080060void CalibrationData::AddTurret(
61 aos::distributed_clock::time_point distributed_now, Eigen::Vector2d state) {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080062 // We want the turret to be known too when solving. But, we don't know if
63 // we are going to have a turret until we get the first reading. In that
64 // case, blow away any camera readings from before.
65 // NOTE: Since the IMU motion is independent of the turret position, we don't
66 // need to remove the IMU readings before the turret
67 if (turret_points_.empty()) {
68 while (!rot_trans_points_.empty() &&
69 rot_trans_points_[0].first < distributed_now) {
70 LOG(INFO) << "Erasing, distributed " << distributed_now;
71 rot_trans_points_.erase(rot_trans_points_.begin());
72 }
Austin Schuh2895f4c2022-02-26 16:38:46 -080073 }
74 turret_points_.emplace_back(distributed_now, state);
75}
76
Austin Schuhdcb6b362022-02-25 18:06:21 -080077void CalibrationData::ReviewData(CalibrationDataObserver *observer) const {
milind-u8c72d532021-12-11 15:02:42 -080078 size_t next_camera_point = 0;
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080079 size_t next_imu_point = 0;
80 size_t next_turret_point = 0;
81
82 // Just go until one of the data streams runs out. We lose a few points, but
83 // it makes the logic much easier
84 while (
85 next_camera_point != rot_trans_points_.size() &&
86 next_imu_point != imu_points_.size() &&
87 (turret_points_.empty() || next_turret_point != turret_points_.size())) {
88 // If camera_point is next, update it
89 if ((rot_trans_points_[next_camera_point].first <=
90 imu_points_[next_imu_point].first) &&
91 (turret_points_.empty() ||
92 (rot_trans_points_[next_camera_point].first <=
93 turret_points_[next_turret_point].first))) {
94 // Camera!
95 observer->UpdateCamera(rot_trans_points_[next_camera_point].first,
96 rot_trans_points_[next_camera_point].second);
97 ++next_camera_point;
98 } else {
99 // If it's not the camera, check if IMU is next
100 if (turret_points_.empty() || (imu_points_[next_imu_point].first <=
101 turret_points_[next_turret_point].first)) {
102 // IMU!
103 observer->UpdateIMU(imu_points_[next_imu_point].first,
104 imu_points_[next_imu_point].second);
105 ++next_imu_point;
milind-u8c72d532021-12-11 15:02:42 -0800106 } else {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800107 // If it's not IMU or camera, and turret_points is not empty, it must be
108 // the turret!
109 observer->UpdateTurret(turret_points_[next_turret_point].first,
110 turret_points_[next_turret_point].second);
111 ++next_turret_point;
milind-u8c72d532021-12-11 15:02:42 -0800112 }
113 }
114 }
115}
116
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800117CalibrationFoxgloveVisualizer::CalibrationFoxgloveVisualizer(
118 aos::EventLoop *event_loop)
119 : event_loop_(event_loop),
Jim Ostrowski86203682023-02-22 19:43:10 -0800120 image_converter_(event_loop_, "/camera", "/camera",
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800121 ImageCompression::kJpeg),
122 annotations_sender_(
Jim Ostrowski86203682023-02-22 19:43:10 -0800123 event_loop_->MakeSender<foxglove::ImageAnnotations>("/camera")) {}
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800124
125aos::FlatbufferDetachedBuffer<aos::Configuration>
126CalibrationFoxgloveVisualizer::AddVisualizationChannels(
127 const aos::Configuration *config, const aos::Node *node) {
128 constexpr std::string_view channel_name = "/visualization";
129 aos::ChannelT channel_overrides;
130 channel_overrides.max_size = 10000000;
131 aos::FlatbufferDetachedBuffer<aos::Configuration> result =
132 aos::configuration::AddChannelToConfiguration(
133 config, channel_name,
134 aos::FlatbufferSpan<reflection::Schema>(
135 foxglove::ImageAnnotationsSchema()),
136 node, channel_overrides);
137 return aos::configuration::AddChannelToConfiguration(
138 &result.message(), channel_name,
139 aos::FlatbufferSpan<reflection::Schema>(
140 foxglove::CompressedImageSchema()),
141 node, channel_overrides);
142}
143
James Kuszmaul7e958812023-02-11 15:34:31 -0800144Calibration::Calibration(
145 aos::SimulatedEventLoopFactory *event_loop_factory,
146 aos::EventLoop *image_event_loop, aos::EventLoop *imu_event_loop,
147 std::string_view pi,
148 const calibration::CameraCalibration *intrinsics_calibration,
149 TargetType target_type, std::string_view image_channel,
150 CalibrationData *data)
milind-u8c72d532021-12-11 15:02:42 -0800151 : image_event_loop_(image_event_loop),
152 image_factory_(event_loop_factory->GetNodeEventLoopFactory(
153 image_event_loop_->node())),
154 imu_event_loop_(imu_event_loop),
155 imu_factory_(
156 event_loop_factory->GetNodeEventLoopFactory(imu_event_loop_->node())),
157 charuco_extractor_(
James Kuszmaul7e958812023-02-11 15:34:31 -0800158 image_event_loop_, intrinsics_calibration, target_type, image_channel,
milind-u8c72d532021-12-11 15:02:42 -0800159 [this](cv::Mat rgb_image, monotonic_clock::time_point eof,
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800160 std::vector<cv::Vec4i> charuco_ids,
161 std::vector<std::vector<cv::Point2f>> charuco_corners,
162 bool valid, std::vector<Eigen::Vector3d> rvecs_eigen,
163 std::vector<Eigen::Vector3d> tvecs_eigen) {
milind-u8c72d532021-12-11 15:02:42 -0800164 HandleCharuco(rgb_image, eof, charuco_ids, charuco_corners, valid,
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800165 rvecs_eigen, tvecs_eigen);
166 }),
167 image_callback_(
168 image_event_loop_,
169 absl::StrCat("/pi",
170 std::to_string(aos::network::ParsePiNumber(pi).value()),
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800171 image_channel),
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800172 [this](cv::Mat rgb_image, const monotonic_clock::time_point eof) {
173 charuco_extractor_.HandleImage(rgb_image, eof);
milind-u8c72d532021-12-11 15:02:42 -0800174 }),
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800175 data_(data),
176 visualizer_event_loop_(image_factory_->MakeEventLoop("visualization")),
177 visualizer_(visualizer_event_loop_.get()) {
milind-u8c72d532021-12-11 15:02:42 -0800178 imu_factory_->OnShutdown([]() { cv::destroyAllWindows(); });
179
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800180 // Check for IMUValuesBatch topic on both /localizer and /drivetrain channels,
181 // since both are valid/possible
182 std::string imu_channel;
183 if (imu_event_loop->HasChannel<frc971::IMUValuesBatch>("/localizer")) {
184 imu_channel = "/localizer";
185 } else if (imu_event_loop->HasChannel<frc971::IMUValuesBatch>(
186 "/drivetrain")) {
187 imu_channel = "/drivetrain";
188 } else {
189 LOG(FATAL) << "Couldn't find channel with IMU data for either localizer or "
190 "drivtrain";
191 }
192
193 VLOG(2) << "Listening for " << frc971::IMUValuesBatch::GetFullyQualifiedName()
194 << " on channel: " << imu_channel;
195
milind-u8c72d532021-12-11 15:02:42 -0800196 imu_event_loop_->MakeWatcher(
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800197 imu_channel, [this](const frc971::IMUValuesBatch &imu) {
milind-u8c72d532021-12-11 15:02:42 -0800198 if (!imu.has_readings()) {
199 return;
200 }
201 for (const frc971::IMUValues *value : *imu.readings()) {
202 HandleIMU(value);
203 }
204 });
205}
206
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800207void Calibration::HandleCharuco(
208 cv::Mat rgb_image, const monotonic_clock::time_point eof,
209 std::vector<cv::Vec4i> /*charuco_ids*/,
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800210 std::vector<std::vector<cv::Point2f>> charuco_corners, bool valid,
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800211 std::vector<Eigen::Vector3d> rvecs_eigen,
212 std::vector<Eigen::Vector3d> tvecs_eigen) {
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800213 visualizer_.HandleCharuco(eof, charuco_corners);
milind-u8c72d532021-12-11 15:02:42 -0800214 if (valid) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800215 CHECK(rvecs_eigen.size() > 0) << "Require at least one target detected";
216 // We only use one (the first) target detected for calibration
217 data_->AddCameraPose(image_factory_->ToDistributedClock(eof),
218 rvecs_eigen[0], tvecs_eigen[0]);
milind-u8c72d532021-12-11 15:02:42 -0800219
milind-u8c72d532021-12-11 15:02:42 -0800220 Eigen::IOFormat HeavyFmt(Eigen::FullPrecision, 0, ", ", ",\n", "[", "]",
221 "[", "]");
222
223 const double age_double =
224 std::chrono::duration_cast<std::chrono::duration<double>>(
225 image_event_loop_->monotonic_now() - eof)
226 .count();
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800227 VLOG(1) << std::fixed << std::setprecision(6) << "Age: " << age_double
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800228 << ", Pose is R:" << rvecs_eigen[0].transpose().format(HeavyFmt)
229 << "\nT:" << tvecs_eigen[0].transpose().format(HeavyFmt);
milind-u8c72d532021-12-11 15:02:42 -0800230 }
231
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800232 if (FLAGS_visualize) {
233 if (FLAGS_display_undistorted) {
234 const cv::Size image_size(rgb_image.cols, rgb_image.rows);
235 cv::Mat undistorted_rgb_image(image_size, CV_8UC3);
236 cv::undistort(rgb_image, undistorted_rgb_image,
237 charuco_extractor_.camera_matrix(),
238 charuco_extractor_.dist_coeffs());
milind-u8c72d532021-12-11 15:02:42 -0800239
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800240 cv::imshow("Display undist", undistorted_rgb_image);
241 }
milind-u8c72d532021-12-11 15:02:42 -0800242
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800243 cv::imshow("Display", rgb_image);
244 cv::waitKey(1);
milind-u8c72d532021-12-11 15:02:42 -0800245 }
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800246
247 if (FLAGS_save_path != "") {
248 if (!FLAGS_save_valid_only || valid) {
249 static int img_count = 0;
250 std::string image_name = absl::StrFormat("/img_%06d.png", img_count);
251 std::string path = FLAGS_save_path + image_name;
252 VLOG(2) << "Saving image to " << path;
253 cv::imwrite(path, rgb_image);
254 img_count++;
255 }
256 }
milind-u8c72d532021-12-11 15:02:42 -0800257}
258
259void Calibration::HandleIMU(const frc971::IMUValues *imu) {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800260 // Need to check for valid values, since we sometimes don't get them
261 if (!imu->has_gyro_x() || !imu->has_gyro_y() || !imu->has_gyro_z() ||
262 !imu->has_accelerometer_x() || !imu->has_accelerometer_y() ||
263 !imu->has_accelerometer_z()) {
264 return;
265 }
266
267 VLOG(2) << "IMU " << imu;
milind-u8c72d532021-12-11 15:02:42 -0800268 imu->UnPackTo(&last_value_);
269 Eigen::Vector3d gyro(last_value_.gyro_x, last_value_.gyro_y,
270 last_value_.gyro_z);
271 Eigen::Vector3d accel(last_value_.accelerometer_x,
272 last_value_.accelerometer_y,
273 last_value_.accelerometer_z);
274
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800275 // TODO: ToDistributedClock may be too noisy.
milind-u8c72d532021-12-11 15:02:42 -0800276 data_->AddImu(imu_factory_->ToDistributedClock(monotonic_clock::time_point(
277 chrono::nanoseconds(imu->monotonic_timestamp_ns()))),
Austin Schuh5b379072021-12-26 16:01:04 -0800278 gyro, accel * kG);
milind-u8c72d532021-12-11 15:02:42 -0800279}
280
281} // namespace vision
282} // namespace frc971