blob: ea9af28ae693657b9f52ea4a02cb6039c6ceb3d0 [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"
James Kuszmaul969e4ab2023-01-28 16:09:19 -080014#include "external/com_github_foxglove_schemas/ImageAnnotations_schema.h"
15#include "external/com_github_foxglove_schemas/CompressedImage_schema.h"
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080016
milind-u8c72d532021-12-11 15:02:42 -080017DEFINE_bool(display_undistorted, false,
18 "If true, display the undistorted image.");
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080019DEFINE_string(save_path, "", "Where to store annotated images");
20DEFINE_bool(save_valid_only, false,
21 "If true, only save images with valid pose estimates");
milind-u8c72d532021-12-11 15:02:42 -080022
23namespace frc971 {
24namespace vision {
25using aos::distributed_clock;
26using aos::monotonic_clock;
27namespace chrono = std::chrono;
28
Austin Schuh5b379072021-12-26 16:01:04 -080029constexpr double kG = 9.807;
30
milind-u8c72d532021-12-11 15:02:42 -080031void CalibrationData::AddCameraPose(
32 distributed_clock::time_point distributed_now, Eigen::Vector3d rvec,
33 Eigen::Vector3d tvec) {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080034 // Always start with IMU (or turret) reading...
35 // Note, we may not have a turret, so need to handle that case
36 // If we later get a turret point, then we handle removal of camera points in
37 // AddTurret
38 if ((!imu_points_.empty() && imu_points_[0].first < distributed_now) &&
39 (turret_points_.empty() || turret_points_[0].first < distributed_now)) {
Austin Schuh5b379072021-12-26 16:01:04 -080040 rot_trans_points_.emplace_back(distributed_now, std::make_pair(rvec, tvec));
41 }
milind-u8c72d532021-12-11 15:02:42 -080042}
43
44void CalibrationData::AddImu(distributed_clock::time_point distributed_now,
45 Eigen::Vector3d gyro, Eigen::Vector3d accel) {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080046 double zero_threshold = 1e-12;
47 // We seem to be getting 0 readings on IMU, so ignore for now
48 // TODO<Jim>: I think this has been resolved in HandleIMU, but want to leave
49 // this here just in case there are other ways this could happen
50 if ((fabs(accel(0)) < zero_threshold) && (fabs(accel(1)) < zero_threshold) &&
51 (fabs(accel(2)) < zero_threshold)) {
52 LOG(FATAL) << "Ignoring zero value from IMU accelerometer: " << accel
53 << " (gyro is " << gyro << ")";
54 } else {
55 imu_points_.emplace_back(distributed_now, std::make_pair(gyro, accel));
56 }
milind-u8c72d532021-12-11 15:02:42 -080057}
58
Austin Schuh2895f4c2022-02-26 16:38:46 -080059void CalibrationData::AddTurret(
60 aos::distributed_clock::time_point distributed_now, Eigen::Vector2d state) {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080061 // We want the turret to be known too when solving. But, we don't know if
62 // we are going to have a turret until we get the first reading. In that
63 // case, blow away any camera readings from before.
64 // NOTE: Since the IMU motion is independent of the turret position, we don't
65 // need to remove the IMU readings before the turret
66 if (turret_points_.empty()) {
67 while (!rot_trans_points_.empty() &&
68 rot_trans_points_[0].first < distributed_now) {
69 LOG(INFO) << "Erasing, distributed " << distributed_now;
70 rot_trans_points_.erase(rot_trans_points_.begin());
71 }
Austin Schuh2895f4c2022-02-26 16:38:46 -080072 }
73 turret_points_.emplace_back(distributed_now, state);
74}
75
Austin Schuhdcb6b362022-02-25 18:06:21 -080076void CalibrationData::ReviewData(CalibrationDataObserver *observer) const {
milind-u8c72d532021-12-11 15:02:42 -080077 size_t next_camera_point = 0;
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080078 size_t next_imu_point = 0;
79 size_t next_turret_point = 0;
80
81 // Just go until one of the data streams runs out. We lose a few points, but
82 // it makes the logic much easier
83 while (
84 next_camera_point != rot_trans_points_.size() &&
85 next_imu_point != imu_points_.size() &&
86 (turret_points_.empty() || next_turret_point != turret_points_.size())) {
87 // If camera_point is next, update it
88 if ((rot_trans_points_[next_camera_point].first <=
89 imu_points_[next_imu_point].first) &&
90 (turret_points_.empty() ||
91 (rot_trans_points_[next_camera_point].first <=
92 turret_points_[next_turret_point].first))) {
93 // Camera!
94 observer->UpdateCamera(rot_trans_points_[next_camera_point].first,
95 rot_trans_points_[next_camera_point].second);
96 ++next_camera_point;
97 } else {
98 // If it's not the camera, check if IMU is next
99 if (turret_points_.empty() || (imu_points_[next_imu_point].first <=
100 turret_points_[next_turret_point].first)) {
101 // IMU!
102 observer->UpdateIMU(imu_points_[next_imu_point].first,
103 imu_points_[next_imu_point].second);
104 ++next_imu_point;
milind-u8c72d532021-12-11 15:02:42 -0800105 } else {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800106 // If it's not IMU or camera, and turret_points is not empty, it must be
107 // the turret!
108 observer->UpdateTurret(turret_points_[next_turret_point].first,
109 turret_points_[next_turret_point].second);
110 ++next_turret_point;
milind-u8c72d532021-12-11 15:02:42 -0800111 }
112 }
113 }
114}
115
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800116CalibrationFoxgloveVisualizer::CalibrationFoxgloveVisualizer(
117 aos::EventLoop *event_loop)
118 : event_loop_(event_loop),
119 image_converter_(event_loop_, "/camera", "/visualization",
120 ImageCompression::kJpeg),
121 annotations_sender_(
122 event_loop_->MakeSender<foxglove::ImageAnnotations>("/visualization")) {}
123
124aos::FlatbufferDetachedBuffer<aos::Configuration>
125CalibrationFoxgloveVisualizer::AddVisualizationChannels(
126 const aos::Configuration *config, const aos::Node *node) {
127 constexpr std::string_view channel_name = "/visualization";
128 aos::ChannelT channel_overrides;
129 channel_overrides.max_size = 10000000;
130 aos::FlatbufferDetachedBuffer<aos::Configuration> result =
131 aos::configuration::AddChannelToConfiguration(
132 config, channel_name,
133 aos::FlatbufferSpan<reflection::Schema>(
134 foxglove::ImageAnnotationsSchema()),
135 node, channel_overrides);
136 return aos::configuration::AddChannelToConfiguration(
137 &result.message(), channel_name,
138 aos::FlatbufferSpan<reflection::Schema>(
139 foxglove::CompressedImageSchema()),
140 node, channel_overrides);
141}
142
milind-u8c72d532021-12-11 15:02:42 -0800143Calibration::Calibration(aos::SimulatedEventLoopFactory *event_loop_factory,
144 aos::EventLoop *image_event_loop,
145 aos::EventLoop *imu_event_loop, std::string_view pi,
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800146 TargetType target_type, std::string_view image_channel,
milind-u8c72d532021-12-11 15:02:42 -0800147 CalibrationData *data)
148 : image_event_loop_(image_event_loop),
149 image_factory_(event_loop_factory->GetNodeEventLoopFactory(
150 image_event_loop_->node())),
151 imu_event_loop_(imu_event_loop),
152 imu_factory_(
153 event_loop_factory->GetNodeEventLoopFactory(imu_event_loop_->node())),
154 charuco_extractor_(
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800155 image_event_loop_, pi, target_type, image_channel,
milind-u8c72d532021-12-11 15:02:42 -0800156 [this](cv::Mat rgb_image, monotonic_clock::time_point eof,
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800157 std::vector<cv::Vec4i> charuco_ids,
158 std::vector<std::vector<cv::Point2f>> charuco_corners,
159 bool valid, std::vector<Eigen::Vector3d> rvecs_eigen,
160 std::vector<Eigen::Vector3d> tvecs_eigen) {
milind-u8c72d532021-12-11 15:02:42 -0800161 HandleCharuco(rgb_image, eof, charuco_ids, charuco_corners, valid,
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800162 rvecs_eigen, tvecs_eigen);
163 }),
164 image_callback_(
165 image_event_loop_,
166 absl::StrCat("/pi",
167 std::to_string(aos::network::ParsePiNumber(pi).value()),
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800168 image_channel),
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800169 [this](cv::Mat rgb_image, const monotonic_clock::time_point eof) {
170 charuco_extractor_.HandleImage(rgb_image, eof);
milind-u8c72d532021-12-11 15:02:42 -0800171 }),
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800172 data_(data),
173 visualizer_event_loop_(image_factory_->MakeEventLoop("visualization")),
174 visualizer_(visualizer_event_loop_.get()) {
milind-u8c72d532021-12-11 15:02:42 -0800175 imu_factory_->OnShutdown([]() { cv::destroyAllWindows(); });
176
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800177 // Check for IMUValuesBatch topic on both /localizer and /drivetrain channels,
178 // since both are valid/possible
179 std::string imu_channel;
180 if (imu_event_loop->HasChannel<frc971::IMUValuesBatch>("/localizer")) {
181 imu_channel = "/localizer";
182 } else if (imu_event_loop->HasChannel<frc971::IMUValuesBatch>(
183 "/drivetrain")) {
184 imu_channel = "/drivetrain";
185 } else {
186 LOG(FATAL) << "Couldn't find channel with IMU data for either localizer or "
187 "drivtrain";
188 }
189
190 VLOG(2) << "Listening for " << frc971::IMUValuesBatch::GetFullyQualifiedName()
191 << " on channel: " << imu_channel;
192
milind-u8c72d532021-12-11 15:02:42 -0800193 imu_event_loop_->MakeWatcher(
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800194 imu_channel, [this](const frc971::IMUValuesBatch &imu) {
milind-u8c72d532021-12-11 15:02:42 -0800195 if (!imu.has_readings()) {
196 return;
197 }
198 for (const frc971::IMUValues *value : *imu.readings()) {
199 HandleIMU(value);
200 }
201 });
202}
203
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800204void Calibration::HandleCharuco(
205 cv::Mat rgb_image, const monotonic_clock::time_point eof,
206 std::vector<cv::Vec4i> /*charuco_ids*/,
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800207 std::vector<std::vector<cv::Point2f>> charuco_corners, bool valid,
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800208 std::vector<Eigen::Vector3d> rvecs_eigen,
209 std::vector<Eigen::Vector3d> tvecs_eigen) {
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800210 visualizer_.HandleCharuco(eof, charuco_corners);
milind-u8c72d532021-12-11 15:02:42 -0800211 if (valid) {
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800212 CHECK(rvecs_eigen.size() > 0) << "Require at least one target detected";
213 // We only use one (the first) target detected for calibration
214 data_->AddCameraPose(image_factory_->ToDistributedClock(eof),
215 rvecs_eigen[0], tvecs_eigen[0]);
milind-u8c72d532021-12-11 15:02:42 -0800216
milind-u8c72d532021-12-11 15:02:42 -0800217 Eigen::IOFormat HeavyFmt(Eigen::FullPrecision, 0, ", ", ",\n", "[", "]",
218 "[", "]");
219
220 const double age_double =
221 std::chrono::duration_cast<std::chrono::duration<double>>(
222 image_event_loop_->monotonic_now() - eof)
223 .count();
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800224 VLOG(1) << std::fixed << std::setprecision(6) << "Age: " << age_double
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800225 << ", Pose is R:" << rvecs_eigen[0].transpose().format(HeavyFmt)
226 << "\nT:" << tvecs_eigen[0].transpose().format(HeavyFmt);
milind-u8c72d532021-12-11 15:02:42 -0800227 }
228
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800229 if (FLAGS_visualize) {
230 if (FLAGS_display_undistorted) {
231 const cv::Size image_size(rgb_image.cols, rgb_image.rows);
232 cv::Mat undistorted_rgb_image(image_size, CV_8UC3);
233 cv::undistort(rgb_image, undistorted_rgb_image,
234 charuco_extractor_.camera_matrix(),
235 charuco_extractor_.dist_coeffs());
milind-u8c72d532021-12-11 15:02:42 -0800236
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800237 cv::imshow("Display undist", undistorted_rgb_image);
238 }
milind-u8c72d532021-12-11 15:02:42 -0800239
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800240 cv::imshow("Display", rgb_image);
241 cv::waitKey(1);
milind-u8c72d532021-12-11 15:02:42 -0800242 }
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800243
244 if (FLAGS_save_path != "") {
245 if (!FLAGS_save_valid_only || valid) {
246 static int img_count = 0;
247 std::string image_name = absl::StrFormat("/img_%06d.png", img_count);
248 std::string path = FLAGS_save_path + image_name;
249 VLOG(2) << "Saving image to " << path;
250 cv::imwrite(path, rgb_image);
251 img_count++;
252 }
253 }
milind-u8c72d532021-12-11 15:02:42 -0800254}
255
256void Calibration::HandleIMU(const frc971::IMUValues *imu) {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800257 // Need to check for valid values, since we sometimes don't get them
258 if (!imu->has_gyro_x() || !imu->has_gyro_y() || !imu->has_gyro_z() ||
259 !imu->has_accelerometer_x() || !imu->has_accelerometer_y() ||
260 !imu->has_accelerometer_z()) {
261 return;
262 }
263
264 VLOG(2) << "IMU " << imu;
milind-u8c72d532021-12-11 15:02:42 -0800265 imu->UnPackTo(&last_value_);
266 Eigen::Vector3d gyro(last_value_.gyro_x, last_value_.gyro_y,
267 last_value_.gyro_z);
268 Eigen::Vector3d accel(last_value_.accelerometer_x,
269 last_value_.accelerometer_y,
270 last_value_.accelerometer_z);
271
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800272 // TODO: ToDistributedClock may be too noisy.
milind-u8c72d532021-12-11 15:02:42 -0800273 data_->AddImu(imu_factory_->ToDistributedClock(monotonic_clock::time_point(
274 chrono::nanoseconds(imu->monotonic_timestamp_ns()))),
Austin Schuh5b379072021-12-26 16:01:04 -0800275 gyro, accel * kG);
milind-u8c72d532021-12-11 15:02:42 -0800276}
277
278} // namespace vision
279} // namespace frc971