blob: 89945b0e1296d36b3319107bed4723b118eaed8f [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
3#include <opencv2/aruco/charuco.hpp>
4#include <opencv2/calib3d.hpp>
5#include <opencv2/features2d.hpp>
6#include <opencv2/highgui/highgui.hpp>
7#include <opencv2/imgproc.hpp>
8
9#include "Eigen/Dense"
10#include "aos/events/simulated_event_loop.h"
11#include "aos/time/time.h"
12#include "frc971/control_loops/quaternion_utils.h"
13#include "frc971/wpilib/imu_batch_generated.h"
Austin Schuhdcb6b362022-02-25 18:06:21 -080014#include "frc971/vision/charuco_lib.h"
milind-u8c72d532021-12-11 15:02:42 -080015
16DEFINE_bool(display_undistorted, false,
17 "If true, display the undistorted image.");
18
19namespace frc971 {
20namespace vision {
21using aos::distributed_clock;
22using aos::monotonic_clock;
23namespace chrono = std::chrono;
24
Austin Schuh5b379072021-12-26 16:01:04 -080025constexpr double kG = 9.807;
26
milind-u8c72d532021-12-11 15:02:42 -080027void CalibrationData::AddCameraPose(
28 distributed_clock::time_point distributed_now, Eigen::Vector3d rvec,
29 Eigen::Vector3d tvec) {
Austin Schuh5b379072021-12-26 16:01:04 -080030 // Always start with IMU reading...
31 if (!imu_points_.empty() && imu_points_[0].first < distributed_now) {
32 rot_trans_points_.emplace_back(distributed_now, std::make_pair(rvec, tvec));
33 }
milind-u8c72d532021-12-11 15:02:42 -080034}
35
36void CalibrationData::AddImu(distributed_clock::time_point distributed_now,
37 Eigen::Vector3d gyro, Eigen::Vector3d accel) {
38 imu_points_.emplace_back(distributed_now, std::make_pair(gyro, accel));
39}
40
Austin Schuhdcb6b362022-02-25 18:06:21 -080041void CalibrationData::ReviewData(CalibrationDataObserver *observer) const {
milind-u8c72d532021-12-11 15:02:42 -080042 size_t next_imu_point = 0;
43 size_t next_camera_point = 0;
44 while (true) {
45 if (next_imu_point != imu_points_.size()) {
46 // There aren't that many combinations, so just brute force them all
47 // rather than being too clever.
48 if (next_camera_point != rot_trans_points_.size()) {
49 if (imu_points_[next_imu_point].first >
50 rot_trans_points_[next_camera_point].first) {
51 // Camera!
52 observer->UpdateCamera(rot_trans_points_[next_camera_point].first,
53 rot_trans_points_[next_camera_point].second);
54 ++next_camera_point;
55 } else {
56 // IMU!
57 observer->UpdateIMU(imu_points_[next_imu_point].first,
58 imu_points_[next_imu_point].second);
59 ++next_imu_point;
60 }
61 } else {
62 if (next_camera_point != rot_trans_points_.size()) {
63 // Camera!
64 observer->UpdateCamera(rot_trans_points_[next_camera_point].first,
65 rot_trans_points_[next_camera_point].second);
66 ++next_camera_point;
67 } else {
68 // Nothing left for either list of points, so we are done.
69 break;
70 }
71 }
72 }
73 }
74}
75
76Calibration::Calibration(aos::SimulatedEventLoopFactory *event_loop_factory,
77 aos::EventLoop *image_event_loop,
78 aos::EventLoop *imu_event_loop, std::string_view pi,
79 CalibrationData *data)
80 : image_event_loop_(image_event_loop),
81 image_factory_(event_loop_factory->GetNodeEventLoopFactory(
82 image_event_loop_->node())),
83 imu_event_loop_(imu_event_loop),
84 imu_factory_(
85 event_loop_factory->GetNodeEventLoopFactory(imu_event_loop_->node())),
86 charuco_extractor_(
87 image_event_loop_, pi,
88 [this](cv::Mat rgb_image, monotonic_clock::time_point eof,
89 std::vector<int> charuco_ids,
90 std::vector<cv::Point2f> charuco_corners, bool valid,
91 Eigen::Vector3d rvec_eigen, Eigen::Vector3d tvec_eigen) {
92 HandleCharuco(rgb_image, eof, charuco_ids, charuco_corners, valid,
93 rvec_eigen, tvec_eigen);
94 }),
95 data_(data) {
96 imu_factory_->OnShutdown([]() { cv::destroyAllWindows(); });
97
98 imu_event_loop_->MakeWatcher(
99 "/drivetrain", [this](const frc971::IMUValuesBatch &imu) {
100 if (!imu.has_readings()) {
101 return;
102 }
103 for (const frc971::IMUValues *value : *imu.readings()) {
104 HandleIMU(value);
105 }
106 });
107}
108
109void Calibration::HandleCharuco(cv::Mat rgb_image,
110 const monotonic_clock::time_point eof,
111 std::vector<int> /*charuco_ids*/,
112 std::vector<cv::Point2f> /*charuco_corners*/,
113 bool valid, Eigen::Vector3d rvec_eigen,
114 Eigen::Vector3d tvec_eigen) {
115 if (valid) {
116 data_->AddCameraPose(image_factory_->ToDistributedClock(eof), rvec_eigen,
117 tvec_eigen);
118
milind-u8c72d532021-12-11 15:02:42 -0800119 // Z -> up
120 // Y -> away from cameras 2 and 3
121 // X -> left
122 Eigen::Vector3d imu(last_value_.accelerometer_x,
123 last_value_.accelerometer_y,
124 last_value_.accelerometer_z);
125
126 Eigen::Quaternion<double> imu_to_camera(
127 Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX()));
128
129 Eigen::Quaternion<double> board_to_world(
130 Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitX()));
131
132 Eigen::IOFormat HeavyFmt(Eigen::FullPrecision, 0, ", ", ",\n", "[", "]",
133 "[", "]");
134
135 const double age_double =
136 std::chrono::duration_cast<std::chrono::duration<double>>(
137 image_event_loop_->monotonic_now() - eof)
138 .count();
139 LOG(INFO) << std::fixed << std::setprecision(6) << "Age: " << age_double
140 << ", Pose is R:" << rvec_eigen.transpose().format(HeavyFmt)
141 << " T:" << tvec_eigen.transpose().format(HeavyFmt);
142 }
143
144 cv::imshow("Display", rgb_image);
145
146 if (FLAGS_display_undistorted) {
147 const cv::Size image_size(rgb_image.cols, rgb_image.rows);
148 cv::Mat undistorted_rgb_image(image_size, CV_8UC3);
149 cv::undistort(rgb_image, undistorted_rgb_image,
150 charuco_extractor_.camera_matrix(),
151 charuco_extractor_.dist_coeffs());
152
153 cv::imshow("Display undist", undistorted_rgb_image);
154 }
155}
156
157void Calibration::HandleIMU(const frc971::IMUValues *imu) {
158 VLOG(1) << "IMU " << imu;
159 imu->UnPackTo(&last_value_);
160 Eigen::Vector3d gyro(last_value_.gyro_x, last_value_.gyro_y,
161 last_value_.gyro_z);
162 Eigen::Vector3d accel(last_value_.accelerometer_x,
163 last_value_.accelerometer_y,
164 last_value_.accelerometer_z);
165
166 data_->AddImu(imu_factory_->ToDistributedClock(monotonic_clock::time_point(
167 chrono::nanoseconds(imu->monotonic_timestamp_ns()))),
Austin Schuh5b379072021-12-26 16:01:04 -0800168 gyro, accel * kG);
milind-u8c72d532021-12-11 15:02:42 -0800169}
170
171} // namespace vision
172} // namespace frc971