blob: f0a0d71ef1a065213a0711300949ed9784a45d70 [file] [log] [blame]
James Kuszmauld6199be2023-02-11 19:56:28 -08001#include "Eigen/Dense"
2#include "Eigen/Geometry"
3#include "absl/strings/str_format.h"
Philipp Schrader790cb542023-07-05 21:06:52 -07004#include <opencv2/core/eigen.hpp>
5
James Kuszmauld6199be2023-02-11 19:56:28 -08006#include "aos/events/logging/log_reader.h"
7#include "aos/events/logging/log_writer.h"
8#include "aos/init.h"
9#include "aos/network/team_number.h"
10#include "aos/time/time.h"
11#include "aos/util/file.h"
James Kuszmauld6199be2023-02-11 19:56:28 -080012#include "frc971/constants/constants_sender_lib.h"
Jim Ostrowski86203682023-02-22 19:43:10 -080013#include "frc971/control_loops/quaternion_utils.h"
James Kuszmauld6199be2023-02-11 19:56:28 -080014#include "frc971/vision/extrinsics_calibration.h"
15#include "frc971/vision/vision_generated.h"
16#include "frc971/wpilib/imu_batch_generated.h"
17#include "y2023/constants/constants_generated.h"
18#include "y2023/vision/vision_util.h"
19
20DEFINE_string(pi, "pi-7971-2", "Pi name to calibrate.");
21DEFINE_bool(plot, false, "Whether to plot the resulting data.");
Jim Ostrowski86203682023-02-22 19:43:10 -080022DEFINE_string(target_type, "charuco_diamond",
James Kuszmauld6199be2023-02-11 19:56:28 -080023 "Type of target: aruco|charuco|charuco_diamond");
24DEFINE_string(image_channel, "/camera", "Channel to listen for images on");
25DEFINE_string(output_logs, "/tmp/calibration/",
26 "Output folder for visualization logs.");
Jim Ostrowskie9085d42023-02-23 21:14:06 -080027DEFINE_string(base_calibration, "",
28 "Intrinsics (and optionally extrinsics) to use for extrinsics "
29 "calibration.");
James Kuszmauld6199be2023-02-11 19:56:28 -080030DEFINE_string(output_calibration, "",
Jim Ostrowskie9085d42023-02-23 21:14:06 -080031 "Output json file to use for the resulting calibration "
32 "(intrinsics and extrinsics).");
James Kuszmauld6199be2023-02-11 19:56:28 -080033
Stephan Pleinesf63bde82024-01-13 15:59:33 -080034namespace frc971::vision {
James Kuszmauld6199be2023-02-11 19:56:28 -080035namespace chrono = std::chrono;
36using aos::distributed_clock;
37using aos::monotonic_clock;
38
39struct CalibrationAccumulatorState {
40 CalibrationAccumulatorState(
41 aos::SimulatedEventLoopFactory *factory, CalibrationData *data,
42 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> *intrinsics)
43 : factory(factory), data(data), intrinsics(intrinsics) {}
44 aos::SimulatedEventLoopFactory *factory;
45 CalibrationData *data;
46 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> *intrinsics;
47 std::unique_ptr<aos::EventLoop> imu_event_loop;
48 std::unique_ptr<aos::EventLoop> pi_event_loop;
49 std::unique_ptr<aos::EventLoop> logger_event_loop;
50 std::unique_ptr<aos::logger::Logger> logger;
51 std::unique_ptr<Calibration> extractor;
52 void MaybeMakeExtractor() {
53 if (imu_event_loop && pi_event_loop) {
54 TargetType target_type = TargetTypeFromString(FLAGS_target_type);
55 std::unique_ptr<aos::EventLoop> constants_event_loop =
56 factory->MakeEventLoop("constants_fetcher", pi_event_loop->node());
Jim Ostrowskie9085d42023-02-23 21:14:06 -080057 if (FLAGS_base_calibration.empty()) {
Jim Ostrowski86203682023-02-22 19:43:10 -080058 frc971::constants::ConstantsFetcher<y2023::Constants> constants_fetcher(
59 constants_event_loop.get());
60 *intrinsics =
61 aos::RecursiveCopyFlatBuffer(y2023::vision::FindCameraCalibration(
62 constants_fetcher.constants(),
63 pi_event_loop->node()->name()->string_view()));
64 } else {
65 *intrinsics = aos::JsonFileToFlatbuffer<calibration::CameraCalibration>(
Jim Ostrowskie9085d42023-02-23 21:14:06 -080066 FLAGS_base_calibration);
Jim Ostrowski86203682023-02-22 19:43:10 -080067 }
James Kuszmauld6199be2023-02-11 19:56:28 -080068 extractor = std::make_unique<Calibration>(
69 factory, pi_event_loop.get(), imu_event_loop.get(), FLAGS_pi,
70 &intrinsics->message(), target_type, FLAGS_image_channel, data);
71 }
72 }
73};
74
75void Main(int argc, char **argv) {
76 CalibrationData data;
77 std::optional<uint16_t> pi_number = aos::network::ParsePiNumber(FLAGS_pi);
78 CHECK(pi_number);
79 const std::string pi_name = absl::StrCat("pi", *pi_number);
80
Jim Ostrowskie9085d42023-02-23 21:14:06 -080081 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> calibration =
James Kuszmauld6199be2023-02-11 19:56:28 -080082 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>::Empty();
83 {
84 // Now, accumulate all the data into the data object.
85 aos::logger::LogReader reader(
86 aos::logger::SortParts(aos::logger::FindLogs(argc, argv)));
Jim Ostrowski86203682023-02-22 19:43:10 -080087 reader.RemapLoggedChannel<foxglove::CompressedImage>("/pi1/camera");
88 reader.RemapLoggedChannel<foxglove::CompressedImage>("/pi2/camera");
89 reader.RemapLoggedChannel<foxglove::CompressedImage>("/pi3/camera");
90 reader.RemapLoggedChannel<foxglove::CompressedImage>("/pi4/camera");
91 reader.RemapLoggedChannel<foxglove::ImageAnnotations>("/pi1/camera");
92 reader.RemapLoggedChannel<foxglove::ImageAnnotations>("/pi2/camera");
93 reader.RemapLoggedChannel<foxglove::ImageAnnotations>("/pi3/camera");
94 reader.RemapLoggedChannel<foxglove::ImageAnnotations>("/pi4/camera");
James Kuszmauld6199be2023-02-11 19:56:28 -080095
96 aos::SimulatedEventLoopFactory factory(reader.configuration());
97 reader.RegisterWithoutStarting(&factory);
98
99 CHECK(aos::configuration::MultiNode(reader.configuration()));
100
101 // Find the nodes we care about.
102 const aos::Node *const imu_node =
103 aos::configuration::GetNode(factory.configuration(), "imu");
104
105 const aos::Node *const pi_node =
106 aos::configuration::GetNode(factory.configuration(), pi_name);
107
Jim Ostrowskie9085d42023-02-23 21:14:06 -0800108 CalibrationAccumulatorState accumulator_state(&factory, &data,
109 &calibration);
James Kuszmauld6199be2023-02-11 19:56:28 -0800110
111 reader.OnStart(imu_node, [&accumulator_state, imu_node, &factory]() {
112 accumulator_state.imu_event_loop =
113 factory.MakeEventLoop("calibration", imu_node);
114 accumulator_state.MaybeMakeExtractor();
115 });
116
117 reader.OnStart(imu_node, [&accumulator_state, pi_node, &factory]() {
118 accumulator_state.pi_event_loop =
119 factory.MakeEventLoop("logger", pi_node);
120 accumulator_state.logger_event_loop =
121 factory.MakeEventLoop("logger", pi_node);
122 accumulator_state.logger = std::make_unique<aos::logger::Logger>(
123 accumulator_state.logger_event_loop.get());
124 accumulator_state.logger->StartLoggingOnRun(FLAGS_output_logs);
125 accumulator_state.MaybeMakeExtractor();
126 });
127
128 factory.Run();
129
130 reader.Deregister();
131 }
132
133 LOG(INFO) << "Done with event_loop running";
134 CHECK(data.imu_samples_size() > 0) << "Didn't get any IMU data";
135 CHECK(data.camera_samples_size() > 0) << "Didn't get any camera observations";
136
137 // And now we have it, we can start processing it.
Jim Ostrowski86203682023-02-22 19:43:10 -0800138 // NOTE: For y2023, with no turret, pivot == imu
139
140 // Define the mapping that takes imu frame (with z up) to camera frame (with z
141 // pointing out)
142 const Eigen::Quaterniond R_precam_cam(
143 Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX()) *
144 Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitZ()));
145 // Set up initial conditions for the pis that are reasonable
146 Eigen::Quaternion<double> nominal_initial_orientation(
147 Eigen::AngleAxisd(0.0, Eigen::Vector3d::UnitZ()));
148 Eigen::Quaternion<double> nominal_pivot_to_camera(
149 Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitX()) *
150 Eigen::AngleAxisd(-0.75 * M_PI, Eigen::Vector3d::UnitY()));
151 Eigen::Vector3d nominal_pivot_to_camera_translation(8.0, 8.0, 0.0);
152 Eigen::Quaternion<double> nominal_board_to_world(
James Kuszmauld6199be2023-02-11 19:56:28 -0800153 Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX()));
James Kuszmauld6199be2023-02-11 19:56:28 -0800154 Eigen::Matrix<double, 6, 1> nominal_initial_state =
155 Eigen::Matrix<double, 6, 1>::Zero();
Jim Ostrowski86203682023-02-22 19:43:10 -0800156 // Set y value to -1 m (approx distance from imu to the board/world)
157 nominal_initial_state(1, 0) = 1.0;
James Kuszmauld6199be2023-02-11 19:56:28 -0800158
Jim Ostrowskie9085d42023-02-23 21:14:06 -0800159 // If available, pull extrinsics from the calibration file
160 const calibration::CameraCalibration *calib_msg = &calibration.message();
161 if (calib_msg->has_fixed_extrinsics()) {
162 LOG(INFO) << "Using extrinsiscs from calibration file as initial condition";
163 const cv::Mat extrinsics_cv(
164 4, 4, CV_32F,
165 const_cast<void *>(static_cast<const void *>(
166 calib_msg->fixed_extrinsics()->data()->data())));
167 CHECK_EQ(extrinsics_cv.total(),
168 calib_msg->fixed_extrinsics()->data()->size());
169 Eigen::Matrix4d ext_mat;
170 cv::cv2eigen(extrinsics_cv, ext_mat);
171 Eigen::Affine3d extrinsics(ext_mat);
172 Eigen::Affine3d H_camera_imu = extrinsics.inverse();
173 nominal_pivot_to_camera = H_camera_imu.rotation();
174 nominal_pivot_to_camera_translation = H_camera_imu.translation();
175 }
176
James Kuszmauld6199be2023-02-11 19:56:28 -0800177 CalibrationParameters calibration_parameters;
178 calibration_parameters.initial_orientation = nominal_initial_orientation;
179 calibration_parameters.pivot_to_camera = nominal_pivot_to_camera;
Jim Ostrowski86203682023-02-22 19:43:10 -0800180 calibration_parameters.pivot_to_camera_translation =
181 nominal_pivot_to_camera_translation;
182 // Board to world rotation
James Kuszmauld6199be2023-02-11 19:56:28 -0800183 calibration_parameters.board_to_world = nominal_board_to_world;
Jim Ostrowski86203682023-02-22 19:43:10 -0800184 // Initial imu location (and velocity)
James Kuszmauld6199be2023-02-11 19:56:28 -0800185 calibration_parameters.initial_state = nominal_initial_state;
186 calibration_parameters.has_pivot = false;
187
Jim Ostrowski86203682023-02-22 19:43:10 -0800188 // Show the inverse of pivot_to_camera, since camera_to_pivot tells where
189 // the camera is with respect to the pivot frame
James Kuszmauld6199be2023-02-11 19:56:28 -0800190 const Eigen::Affine3d nominal_affine_pivot_to_camera =
191 Eigen::Translation3d(calibration_parameters.pivot_to_camera_translation) *
192 nominal_pivot_to_camera;
193 const Eigen::Quaterniond nominal_camera_to_pivot_rotation(
194 nominal_affine_pivot_to_camera.inverse().rotation());
195 const Eigen::Vector3d nominal_camera_to_pivot_translation(
196 nominal_affine_pivot_to_camera.inverse().translation());
197
198 LOG(INFO) << "Initial Conditions for solver. Assumes:\n"
199 << "1) board origin is same as world, but rotated pi/2 about "
200 "x-axis, so z points out\n"
Jim Ostrowski86203682023-02-22 19:43:10 -0800201 << "2) pivot origin matches imu origin (since there's no turret)\n"
James Kuszmauld6199be2023-02-11 19:56:28 -0800202 << "3) camera is offset from pivot (depends on which camera)";
203
Jim Ostrowski86203682023-02-22 19:43:10 -0800204 LOG(INFO) << "Nominal initial_orientation of imu w.r.t. world "
205 "(angle-axis vector): "
206 << frc971::controls::ToRotationVectorFromQuaternion(
207 nominal_initial_orientation)
208 .transpose();
James Kuszmauld6199be2023-02-11 19:56:28 -0800209 LOG(INFO) << "Nominal initial_state: \n"
210 << "Position: "
211 << nominal_initial_state.block<3, 1>(0, 0).transpose() << "\n"
212 << "Velocity: "
213 << nominal_initial_state.block<3, 1>(3, 0).transpose();
Jim Ostrowski86203682023-02-22 19:43:10 -0800214 LOG(INFO) << "Nominal camera_to_pivot rotation (angle-axis vector): "
James Kuszmauld6199be2023-02-11 19:56:28 -0800215 << frc971::controls::ToRotationVectorFromQuaternion(
216 nominal_camera_to_pivot_rotation)
217 .transpose();
218 LOG(INFO) << "Nominal camera_to_pivot translation: "
219 << nominal_camera_to_pivot_translation.transpose();
220
221 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
222 solved_extrinsics = Solve(data, &calibration_parameters);
Jim Ostrowskie9085d42023-02-23 21:14:06 -0800223 calibration.mutable_message()->clear_fixed_extrinsics();
224 calibration.mutable_message()->clear_turret_extrinsics();
James Kuszmauld6199be2023-02-11 19:56:28 -0800225 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
Jim Ostrowskie9085d42023-02-23 21:14:06 -0800226 merged_calibration = aos::MergeFlatBuffers(&calibration.message(),
James Kuszmauld6199be2023-02-11 19:56:28 -0800227 &solved_extrinsics.message());
228
229 if (!FLAGS_output_calibration.empty()) {
230 aos::WriteFlatbufferToJson(FLAGS_output_calibration, merged_calibration);
Jim Ostrowski86203682023-02-22 19:43:10 -0800231 } else {
232 LOG(WARNING) << "Calibration filename not provided, so not saving it";
James Kuszmauld6199be2023-02-11 19:56:28 -0800233 }
234
235 LOG(INFO) << "RESULTS OF CALIBRATION SOLVER:";
236 std::cout << aos::FlatbufferToJson(&merged_calibration.message())
237 << std::endl;
Jim Ostrowski86203682023-02-22 19:43:10 -0800238
James Kuszmauld6199be2023-02-11 19:56:28 -0800239 LOG(INFO) << "initial_orientation of imu w.r.t. world (angle-axis vector): "
240 << frc971::controls::ToRotationVectorFromQuaternion(
241 calibration_parameters.initial_orientation)
242 .transpose();
243 LOG(INFO)
Jim Ostrowski86203682023-02-22 19:43:10 -0800244 << "initial_state (imu): \n"
James Kuszmauld6199be2023-02-11 19:56:28 -0800245 << "Position: "
246 << calibration_parameters.initial_state.block<3, 1>(0, 0).transpose()
247 << "\n"
248 << "Velocity: "
249 << calibration_parameters.initial_state.block<3, 1>(3, 0).transpose();
250
251 const Eigen::Affine3d affine_pivot_to_camera =
252 Eigen::Translation3d(calibration_parameters.pivot_to_camera_translation) *
253 calibration_parameters.pivot_to_camera;
Jim Ostrowski86203682023-02-22 19:43:10 -0800254 const Eigen::Affine3d affine_camera_to_pivot =
255 affine_pivot_to_camera.inverse();
James Kuszmauld6199be2023-02-11 19:56:28 -0800256 const Eigen::Quaterniond camera_to_pivot_rotation(
Jim Ostrowski86203682023-02-22 19:43:10 -0800257 affine_camera_to_pivot.rotation());
James Kuszmauld6199be2023-02-11 19:56:28 -0800258 const Eigen::Vector3d camera_to_pivot_translation(
Jim Ostrowski86203682023-02-22 19:43:10 -0800259 affine_camera_to_pivot.translation());
260 LOG(INFO) << "camera to pivot(imu) rotation (angle-axis vec): "
James Kuszmauld6199be2023-02-11 19:56:28 -0800261 << frc971::controls::ToRotationVectorFromQuaternion(
262 camera_to_pivot_rotation)
263 .transpose();
Jim Ostrowski86203682023-02-22 19:43:10 -0800264 LOG(INFO) << "camera to pivot(imu) translation: "
James Kuszmauld6199be2023-02-11 19:56:28 -0800265 << camera_to_pivot_translation.transpose();
266 LOG(INFO) << "board_to_world (rotation) "
267 << frc971::controls::ToRotationVectorFromQuaternion(
268 calibration_parameters.board_to_world)
269 .transpose();
270 LOG(INFO) << "accelerometer bias "
271 << calibration_parameters.accelerometer_bias.transpose();
272 LOG(INFO) << "gyro_bias " << calibration_parameters.gyro_bias.transpose();
273 LOG(INFO) << "gravity " << 9.81 * calibration_parameters.gravity_scalar;
274
Jim Ostrowski86203682023-02-22 19:43:10 -0800275 LOG(INFO) << "Checking delta from nominal (initial condition) to solved "
276 "values:";
277 LOG(INFO) << "nominal_pivot_to_camera rotation: "
278 << frc971::controls::ToRotationVectorFromQuaternion(
279 R_precam_cam * nominal_pivot_to_camera)
280 .transpose();
281 LOG(INFO) << "solved pivot_to_camera rotation: "
282 << frc971::controls::ToRotationVectorFromQuaternion(
283 R_precam_cam * calibration_parameters.pivot_to_camera)
284 .transpose();
285
286 LOG(INFO) << "pivot_to_camera rotation delta (zero if the IC's match the "
287 "solved value) "
James Kuszmauld6199be2023-02-11 19:56:28 -0800288 << frc971::controls::ToRotationVectorFromQuaternion(
289 calibration_parameters.pivot_to_camera *
290 nominal_pivot_to_camera.inverse())
291 .transpose();
Jim Ostrowski86203682023-02-22 19:43:10 -0800292 LOG(INFO) << "board_to_world rotation change "
James Kuszmauld6199be2023-02-11 19:56:28 -0800293 << frc971::controls::ToRotationVectorFromQuaternion(
294 calibration_parameters.board_to_world *
295 nominal_board_to_world.inverse())
296 .transpose();
297
298 if (FLAGS_visualize) {
299 LOG(INFO) << "Showing visualization";
300 Visualize(data, calibration_parameters);
301 }
302
303 if (FLAGS_plot) {
304 Plot(data, calibration_parameters);
305 }
306} // namespace vision
307
Stephan Pleinesf63bde82024-01-13 15:59:33 -0800308} // namespace frc971::vision
James Kuszmauld6199be2023-02-11 19:56:28 -0800309
310int main(int argc, char **argv) {
311 aos::InitGoogle(&argc, &argv);
312
313 frc971::vision::Main(argc, argv);
314}