Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 1 | #include "frc971/vision/calibration_accumulator.h" |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 2 | |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 3 | #include <algorithm> |
| 4 | #include <limits> |
| 5 | #include <opencv2/highgui/highgui.hpp> |
| 6 | |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 7 | #include "Eigen/Dense" |
| 8 | #include "aos/events/simulated_event_loop.h" |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 9 | #include "aos/network/team_number.h" |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 10 | #include "aos/time/time.h" |
| 11 | #include "frc971/control_loops/quaternion_utils.h" |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 12 | #include "frc971/vision/charuco_lib.h" |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 13 | #include "frc971/wpilib/imu_batch_generated.h" |
| 14 | |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 15 | DEFINE_bool(display_undistorted, false, |
| 16 | "If true, display the undistorted image."); |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 17 | DEFINE_string(save_path, "", "Where to store annotated images"); |
| 18 | DEFINE_bool(save_valid_only, false, |
| 19 | "If true, only save images with valid pose estimates"); |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 20 | |
| 21 | namespace frc971 { |
| 22 | namespace vision { |
| 23 | using aos::distributed_clock; |
| 24 | using aos::monotonic_clock; |
| 25 | namespace chrono = std::chrono; |
| 26 | |
Austin Schuh | 5b37907 | 2021-12-26 16:01:04 -0800 | [diff] [blame] | 27 | constexpr double kG = 9.807; |
| 28 | |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 29 | void CalibrationData::AddCameraPose( |
| 30 | distributed_clock::time_point distributed_now, Eigen::Vector3d rvec, |
| 31 | Eigen::Vector3d tvec) { |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 32 | // 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 Schuh | 5b37907 | 2021-12-26 16:01:04 -0800 | [diff] [blame] | 38 | rot_trans_points_.emplace_back(distributed_now, std::make_pair(rvec, tvec)); |
| 39 | } |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 40 | } |
| 41 | |
| 42 | void CalibrationData::AddImu(distributed_clock::time_point distributed_now, |
| 43 | Eigen::Vector3d gyro, Eigen::Vector3d accel) { |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 44 | 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-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 55 | } |
| 56 | |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 57 | void CalibrationData::AddTurret( |
| 58 | aos::distributed_clock::time_point distributed_now, Eigen::Vector2d state) { |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 59 | // 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 Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 70 | } |
| 71 | turret_points_.emplace_back(distributed_now, state); |
| 72 | } |
| 73 | |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 74 | void CalibrationData::ReviewData(CalibrationDataObserver *observer) const { |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 75 | size_t next_camera_point = 0; |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 76 | 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-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 103 | } else { |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 104 | // 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-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 109 | } |
| 110 | } |
| 111 | } |
| 112 | } |
| 113 | |
| 114 | Calibration::Calibration(aos::SimulatedEventLoopFactory *event_loop_factory, |
| 115 | aos::EventLoop *image_event_loop, |
| 116 | aos::EventLoop *imu_event_loop, std::string_view pi, |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 117 | TargetType target_type, std::string_view image_channel, |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 118 | CalibrationData *data) |
| 119 | : image_event_loop_(image_event_loop), |
| 120 | image_factory_(event_loop_factory->GetNodeEventLoopFactory( |
| 121 | image_event_loop_->node())), |
| 122 | imu_event_loop_(imu_event_loop), |
| 123 | imu_factory_( |
| 124 | event_loop_factory->GetNodeEventLoopFactory(imu_event_loop_->node())), |
| 125 | charuco_extractor_( |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 126 | image_event_loop_, pi, target_type, image_channel, |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 127 | [this](cv::Mat rgb_image, monotonic_clock::time_point eof, |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 128 | std::vector<cv::Vec4i> charuco_ids, |
| 129 | std::vector<std::vector<cv::Point2f>> charuco_corners, |
| 130 | bool valid, std::vector<Eigen::Vector3d> rvecs_eigen, |
| 131 | std::vector<Eigen::Vector3d> tvecs_eigen) { |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 132 | HandleCharuco(rgb_image, eof, charuco_ids, charuco_corners, valid, |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 133 | rvecs_eigen, tvecs_eigen); |
| 134 | }), |
| 135 | image_callback_( |
| 136 | image_event_loop_, |
| 137 | absl::StrCat("/pi", |
| 138 | std::to_string(aos::network::ParsePiNumber(pi).value()), |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 139 | image_channel), |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 140 | [this](cv::Mat rgb_image, const monotonic_clock::time_point eof) { |
| 141 | charuco_extractor_.HandleImage(rgb_image, eof); |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 142 | }), |
| 143 | data_(data) { |
| 144 | imu_factory_->OnShutdown([]() { cv::destroyAllWindows(); }); |
| 145 | |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 146 | // Check for IMUValuesBatch topic on both /localizer and /drivetrain channels, |
| 147 | // since both are valid/possible |
| 148 | std::string imu_channel; |
| 149 | if (imu_event_loop->HasChannel<frc971::IMUValuesBatch>("/localizer")) { |
| 150 | imu_channel = "/localizer"; |
| 151 | } else if (imu_event_loop->HasChannel<frc971::IMUValuesBatch>( |
| 152 | "/drivetrain")) { |
| 153 | imu_channel = "/drivetrain"; |
| 154 | } else { |
| 155 | LOG(FATAL) << "Couldn't find channel with IMU data for either localizer or " |
| 156 | "drivtrain"; |
| 157 | } |
| 158 | |
| 159 | VLOG(2) << "Listening for " << frc971::IMUValuesBatch::GetFullyQualifiedName() |
| 160 | << " on channel: " << imu_channel; |
| 161 | |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 162 | imu_event_loop_->MakeWatcher( |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 163 | imu_channel, [this](const frc971::IMUValuesBatch &imu) { |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 164 | if (!imu.has_readings()) { |
| 165 | return; |
| 166 | } |
| 167 | for (const frc971::IMUValues *value : *imu.readings()) { |
| 168 | HandleIMU(value); |
| 169 | } |
| 170 | }); |
| 171 | } |
| 172 | |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 173 | void Calibration::HandleCharuco( |
| 174 | cv::Mat rgb_image, const monotonic_clock::time_point eof, |
| 175 | std::vector<cv::Vec4i> /*charuco_ids*/, |
| 176 | std::vector<std::vector<cv::Point2f>> /*charuco_corners*/, bool valid, |
| 177 | std::vector<Eigen::Vector3d> rvecs_eigen, |
| 178 | std::vector<Eigen::Vector3d> tvecs_eigen) { |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 179 | if (valid) { |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 180 | CHECK(rvecs_eigen.size() > 0) << "Require at least one target detected"; |
| 181 | // We only use one (the first) target detected for calibration |
| 182 | data_->AddCameraPose(image_factory_->ToDistributedClock(eof), |
| 183 | rvecs_eigen[0], tvecs_eigen[0]); |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 184 | |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 185 | Eigen::IOFormat HeavyFmt(Eigen::FullPrecision, 0, ", ", ",\n", "[", "]", |
| 186 | "[", "]"); |
| 187 | |
| 188 | const double age_double = |
| 189 | std::chrono::duration_cast<std::chrono::duration<double>>( |
| 190 | image_event_loop_->monotonic_now() - eof) |
| 191 | .count(); |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 192 | VLOG(1) << std::fixed << std::setprecision(6) << "Age: " << age_double |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 193 | << ", Pose is R:" << rvecs_eigen[0].transpose().format(HeavyFmt) |
| 194 | << "\nT:" << tvecs_eigen[0].transpose().format(HeavyFmt); |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 195 | } |
| 196 | |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 197 | if (FLAGS_visualize) { |
| 198 | if (FLAGS_display_undistorted) { |
| 199 | const cv::Size image_size(rgb_image.cols, rgb_image.rows); |
| 200 | cv::Mat undistorted_rgb_image(image_size, CV_8UC3); |
| 201 | cv::undistort(rgb_image, undistorted_rgb_image, |
| 202 | charuco_extractor_.camera_matrix(), |
| 203 | charuco_extractor_.dist_coeffs()); |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 204 | |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 205 | cv::imshow("Display undist", undistorted_rgb_image); |
| 206 | } |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 207 | |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 208 | cv::imshow("Display", rgb_image); |
| 209 | cv::waitKey(1); |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 210 | } |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 211 | |
| 212 | if (FLAGS_save_path != "") { |
| 213 | if (!FLAGS_save_valid_only || valid) { |
| 214 | static int img_count = 0; |
| 215 | std::string image_name = absl::StrFormat("/img_%06d.png", img_count); |
| 216 | std::string path = FLAGS_save_path + image_name; |
| 217 | VLOG(2) << "Saving image to " << path; |
| 218 | cv::imwrite(path, rgb_image); |
| 219 | img_count++; |
| 220 | } |
| 221 | } |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 222 | } |
| 223 | |
| 224 | void Calibration::HandleIMU(const frc971::IMUValues *imu) { |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 225 | // Need to check for valid values, since we sometimes don't get them |
| 226 | if (!imu->has_gyro_x() || !imu->has_gyro_y() || !imu->has_gyro_z() || |
| 227 | !imu->has_accelerometer_x() || !imu->has_accelerometer_y() || |
| 228 | !imu->has_accelerometer_z()) { |
| 229 | return; |
| 230 | } |
| 231 | |
| 232 | VLOG(2) << "IMU " << imu; |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 233 | imu->UnPackTo(&last_value_); |
| 234 | Eigen::Vector3d gyro(last_value_.gyro_x, last_value_.gyro_y, |
| 235 | last_value_.gyro_z); |
| 236 | Eigen::Vector3d accel(last_value_.accelerometer_x, |
| 237 | last_value_.accelerometer_y, |
| 238 | last_value_.accelerometer_z); |
| 239 | |
| 240 | data_->AddImu(imu_factory_->ToDistributedClock(monotonic_clock::time_point( |
| 241 | chrono::nanoseconds(imu->monotonic_timestamp_ns()))), |
Austin Schuh | 5b37907 | 2021-12-26 16:01:04 -0800 | [diff] [blame] | 242 | gyro, accel * kG); |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 243 | } |
| 244 | |
| 245 | } // namespace vision |
| 246 | } // namespace frc971 |