blob: e77c74b64904b6d9c8a110ad0e521d21a2fb9482 [file] [log] [blame]
milind-u8c72d532021-12-11 15:02:42 -08001#include "y2020/vision/calibration_accumulator.h"
2
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"
14#include "y2020/vision/charuco_lib.h"
15
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
25void CalibrationData::AddCameraPose(
26 distributed_clock::time_point distributed_now, Eigen::Vector3d rvec,
27 Eigen::Vector3d tvec) {
28 rot_trans_points_.emplace_back(distributed_now, std::make_pair(rvec, tvec));
29}
30
31void CalibrationData::AddImu(distributed_clock::time_point distributed_now,
32 Eigen::Vector3d gyro, Eigen::Vector3d accel) {
33 imu_points_.emplace_back(distributed_now, std::make_pair(gyro, accel));
34}
35
36void CalibrationData::ReviewData(CalibrationDataObserver *observer) {
37 size_t next_imu_point = 0;
38 size_t next_camera_point = 0;
39 while (true) {
40 if (next_imu_point != imu_points_.size()) {
41 // There aren't that many combinations, so just brute force them all
42 // rather than being too clever.
43 if (next_camera_point != rot_trans_points_.size()) {
44 if (imu_points_[next_imu_point].first >
45 rot_trans_points_[next_camera_point].first) {
46 // Camera!
47 observer->UpdateCamera(rot_trans_points_[next_camera_point].first,
48 rot_trans_points_[next_camera_point].second);
49 ++next_camera_point;
50 } else {
51 // IMU!
52 observer->UpdateIMU(imu_points_[next_imu_point].first,
53 imu_points_[next_imu_point].second);
54 ++next_imu_point;
55 }
56 } else {
57 if (next_camera_point != rot_trans_points_.size()) {
58 // Camera!
59 observer->UpdateCamera(rot_trans_points_[next_camera_point].first,
60 rot_trans_points_[next_camera_point].second);
61 ++next_camera_point;
62 } else {
63 // Nothing left for either list of points, so we are done.
64 break;
65 }
66 }
67 }
68 }
69}
70
71Calibration::Calibration(aos::SimulatedEventLoopFactory *event_loop_factory,
72 aos::EventLoop *image_event_loop,
73 aos::EventLoop *imu_event_loop, std::string_view pi,
74 CalibrationData *data)
75 : image_event_loop_(image_event_loop),
76 image_factory_(event_loop_factory->GetNodeEventLoopFactory(
77 image_event_loop_->node())),
78 imu_event_loop_(imu_event_loop),
79 imu_factory_(
80 event_loop_factory->GetNodeEventLoopFactory(imu_event_loop_->node())),
81 charuco_extractor_(
82 image_event_loop_, pi,
83 [this](cv::Mat rgb_image, monotonic_clock::time_point eof,
84 std::vector<int> charuco_ids,
85 std::vector<cv::Point2f> charuco_corners, bool valid,
86 Eigen::Vector3d rvec_eigen, Eigen::Vector3d tvec_eigen) {
87 HandleCharuco(rgb_image, eof, charuco_ids, charuco_corners, valid,
88 rvec_eigen, tvec_eigen);
89 }),
90 data_(data) {
91 imu_factory_->OnShutdown([]() { cv::destroyAllWindows(); });
92
93 imu_event_loop_->MakeWatcher(
94 "/drivetrain", [this](const frc971::IMUValuesBatch &imu) {
95 if (!imu.has_readings()) {
96 return;
97 }
98 for (const frc971::IMUValues *value : *imu.readings()) {
99 HandleIMU(value);
100 }
101 });
102}
103
104void Calibration::HandleCharuco(cv::Mat rgb_image,
105 const monotonic_clock::time_point eof,
106 std::vector<int> /*charuco_ids*/,
107 std::vector<cv::Point2f> /*charuco_corners*/,
108 bool valid, Eigen::Vector3d rvec_eigen,
109 Eigen::Vector3d tvec_eigen) {
110 if (valid) {
111 data_->AddCameraPose(image_factory_->ToDistributedClock(eof), rvec_eigen,
112 tvec_eigen);
113
114 // TODO(austin): Need a gravity vector input.
115 //
116 // TODO(austin): Need a state, covariance, and model.
117 //
118 // TODO(austin): Need to record all the values out of a log and run it
119 // as a batch run so we can feed it into ceres.
120
121 // Z -> up
122 // Y -> away from cameras 2 and 3
123 // X -> left
124 Eigen::Vector3d imu(last_value_.accelerometer_x,
125 last_value_.accelerometer_y,
126 last_value_.accelerometer_z);
127
128 Eigen::Quaternion<double> imu_to_camera(
129 Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX()));
130
131 Eigen::Quaternion<double> board_to_world(
132 Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitX()));
133
134 Eigen::IOFormat HeavyFmt(Eigen::FullPrecision, 0, ", ", ",\n", "[", "]",
135 "[", "]");
136
137 const double age_double =
138 std::chrono::duration_cast<std::chrono::duration<double>>(
139 image_event_loop_->monotonic_now() - eof)
140 .count();
141 LOG(INFO) << std::fixed << std::setprecision(6) << "Age: " << age_double
142 << ", Pose is R:" << rvec_eigen.transpose().format(HeavyFmt)
143 << " T:" << tvec_eigen.transpose().format(HeavyFmt);
144 }
145
146 cv::imshow("Display", rgb_image);
147
148 if (FLAGS_display_undistorted) {
149 const cv::Size image_size(rgb_image.cols, rgb_image.rows);
150 cv::Mat undistorted_rgb_image(image_size, CV_8UC3);
151 cv::undistort(rgb_image, undistorted_rgb_image,
152 charuco_extractor_.camera_matrix(),
153 charuco_extractor_.dist_coeffs());
154
155 cv::imshow("Display undist", undistorted_rgb_image);
156 }
157}
158
159void Calibration::HandleIMU(const frc971::IMUValues *imu) {
160 VLOG(1) << "IMU " << imu;
161 imu->UnPackTo(&last_value_);
162 Eigen::Vector3d gyro(last_value_.gyro_x, last_value_.gyro_y,
163 last_value_.gyro_z);
164 Eigen::Vector3d accel(last_value_.accelerometer_x,
165 last_value_.accelerometer_y,
166 last_value_.accelerometer_z);
167
168 data_->AddImu(imu_factory_->ToDistributedClock(monotonic_clock::time_point(
169 chrono::nanoseconds(imu->monotonic_timestamp_ns()))),
170 gyro, accel);
171}
172
173} // namespace vision
174} // namespace frc971