blob: b5005fe0198ecc3c5221df3dd5c1963215af73d0 [file] [log] [blame]
Jim Ostrowskiba2edd12022-12-03 15:44:37 -08001#include "Eigen/Dense"
2#include "Eigen/Geometry"
3#include "absl/strings/str_format.h"
4#include "aos/events/logging/log_reader.h"
5#include "aos/init.h"
6#include "aos/network/team_number.h"
7#include "aos/time/time.h"
8#include "aos/util/file.h"
9#include "frc971/control_loops/quaternion_utils.h"
10#include "frc971/vision/extrinsics_calibration.h"
11#include "frc971/vision/vision_generated.h"
12#include "frc971/wpilib/imu_batch_generated.h"
13#include "y2020/vision/sift/sift_generated.h"
14#include "y2020/vision/sift/sift_training_generated.h"
15#include "y2020/vision/tools/python_code/sift_training_data.h"
16#include "y2022/control_loops/superstructure/superstructure_status_generated.h"
17
18DEFINE_string(pi, "pi-7971-2", "Pi name to calibrate.");
19DEFINE_bool(plot, false, "Whether to plot the resulting data.");
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080020DEFINE_bool(turret, true, "If true, the camera is on the turret");
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080021DEFINE_string(target_type, "charuco",
milind-u09fb1252023-01-28 19:21:41 -080022 "Type of target: aruco|charuco|charuco_diamond");
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080023DEFINE_string(image_channel, "/camera", "Channel to listen for images on");
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080024
25namespace frc971 {
26namespace vision {
27namespace chrono = std::chrono;
28using aos::distributed_clock;
29using aos::monotonic_clock;
30
31// TODO(austin): Source of IMU data? Is it the same?
32// TODO(austin): Intrinsics data?
33
34void Main(int argc, char **argv) {
35 CalibrationData data;
36
37 {
38 // Now, accumulate all the data into the data object.
39 aos::logger::LogReader reader(
40 aos::logger::SortParts(aos::logger::FindLogs(argc, argv)));
41
42 aos::SimulatedEventLoopFactory factory(reader.configuration());
43 reader.Register(&factory);
44
45 CHECK(aos::configuration::MultiNode(reader.configuration()));
46
47 // Find the nodes we care about.
48 const aos::Node *const imu_node =
49 aos::configuration::GetNode(factory.configuration(), "imu");
50 const aos::Node *const roborio_node =
51 aos::configuration::GetNode(factory.configuration(), "roborio");
52
53 std::optional<uint16_t> pi_number = aos::network::ParsePiNumber(FLAGS_pi);
54 CHECK(pi_number);
55 LOG(INFO) << "Pi " << *pi_number;
56 const aos::Node *const pi_node = aos::configuration::GetNode(
57 factory.configuration(), absl::StrCat("pi", *pi_number));
58
59 LOG(INFO) << "imu " << aos::FlatbufferToJson(imu_node);
60 LOG(INFO) << "roboRIO " << aos::FlatbufferToJson(roborio_node);
61 LOG(INFO) << "Pi " << aos::FlatbufferToJson(pi_node);
62
63 std::unique_ptr<aos::EventLoop> imu_event_loop =
64 factory.MakeEventLoop("calibration", imu_node);
65 std::unique_ptr<aos::EventLoop> roborio_event_loop =
66 factory.MakeEventLoop("calibration", roborio_node);
67 std::unique_ptr<aos::EventLoop> pi_event_loop =
68 factory.MakeEventLoop("calibration", pi_node);
69
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080070 TargetType target_type = TargetType::kCharuco;
milind-u09fb1252023-01-28 19:21:41 -080071 if (FLAGS_target_type == "aruco") {
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080072 target_type = TargetType::kAruco;
73 } else if (FLAGS_target_type == "charuco") {
74 target_type = TargetType::kCharuco;
75 } else if (FLAGS_target_type == "charuco_diamond") {
76 target_type = TargetType::kCharucoDiamond;
77 } else {
78 LOG(FATAL) << "Unknown target type: " << FLAGS_target_type
milind-u09fb1252023-01-28 19:21:41 -080079 << ", expected: aruco|charuco|charuco_diamond";
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080080 }
81
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080082 // Now, hook Calibration up to everything.
83 Calibration extractor(&factory, pi_event_loop.get(), imu_event_loop.get(),
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080084 FLAGS_pi, target_type, FLAGS_image_channel, &data);
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080085
86 if (FLAGS_turret) {
87 aos::NodeEventLoopFactory *roborio_factory =
88 factory.GetNodeEventLoopFactory(roborio_node->name()->string_view());
89 roborio_event_loop->MakeWatcher(
90 "/superstructure",
91 [roborio_factory, roborio_event_loop = roborio_event_loop.get(),
92 &data](const y2022::control_loops::superstructure::Status &status) {
93 data.AddTurret(
94 roborio_factory->ToDistributedClock(
95 roborio_event_loop->context().monotonic_event_time),
96 Eigen::Vector2d(status.turret()->position(),
97 status.turret()->velocity()));
98 });
99 }
100
101 factory.Run();
102
103 reader.Deregister();
104 }
105
106 LOG(INFO) << "Done with event_loop running";
107 CHECK(data.imu_samples_size() > 0) << "Didn't get any IMU data";
108 CHECK(data.camera_samples_size() > 0) << "Didn't get any camera observations";
109
110 // And now we have it, we can start processing it.
111 const Eigen::Quaternion<double> nominal_initial_orientation(
112 frc971::controls::ToQuaternionFromRotationVector(
113 Eigen::Vector3d(0.0, 0.0, M_PI)));
114 const Eigen::Quaternion<double> nominal_pivot_to_camera(
115 Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX()));
116 const Eigen::Quaternion<double> nominal_pivot_to_imu(
117 Eigen::AngleAxisd(0.0, Eigen::Vector3d::UnitX()));
118 const Eigen::Quaternion<double> nominal_board_to_world(
119 Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitX()));
120 Eigen::Matrix<double, 6, 1> nominal_initial_state =
121 Eigen::Matrix<double, 6, 1>::Zero();
122 // Set x value to 0.5 m (center view on the board)
123 // nominal_initial_state(0, 0) = 0.5;
124 // Set y value to -1 m (approx distance from imu to board/world)
125 nominal_initial_state(1, 0) = -1.0;
126
127 CalibrationParameters calibration_parameters;
128 calibration_parameters.initial_orientation = nominal_initial_orientation;
129 calibration_parameters.pivot_to_camera = nominal_pivot_to_camera;
130 calibration_parameters.pivot_to_imu = nominal_pivot_to_imu;
131 calibration_parameters.board_to_world = nominal_board_to_world;
132 calibration_parameters.initial_state = nominal_initial_state;
133
134 // Show the inverse of pivot_to_camera, since camera_to_pivot tells where the
135 // camera is with respect to the pivot frame
136 const Eigen::Affine3d nominal_affine_pivot_to_camera =
137 Eigen::Translation3d(calibration_parameters.pivot_to_camera_translation) *
138 nominal_pivot_to_camera;
139 const Eigen::Quaterniond nominal_camera_to_pivot_rotation(
140 nominal_affine_pivot_to_camera.inverse().rotation());
141 const Eigen::Vector3d nominal_camera_to_pivot_translation(
142 nominal_affine_pivot_to_camera.inverse().translation());
143
144 if (data.turret_samples_size() > 0) {
145 LOG(INFO) << "Have turret, so using pivot setup";
146 calibration_parameters.has_pivot = true;
147 }
148
149 LOG(INFO) << "Initial Conditions for solver. Assumes:\n"
150 << "1) board origin is same as world, but rotated pi/2 about "
151 "x-axis, so z points out\n"
152 << "2) pivot origin matches imu origin\n"
153 << "3) camera is offset from pivot (depends on which camera)";
154
155 LOG(INFO)
156 << "Nominal initial_orientation of imu w.r.t. world (angle-axis vector): "
157 << frc971::controls::ToRotationVectorFromQuaternion(
158 nominal_initial_orientation)
159 .transpose();
160 LOG(INFO) << "Nominal initial_state: \n"
161 << "Position: "
162 << nominal_initial_state.block<3, 1>(0, 0).transpose() << "\n"
163 << "Velocity: "
164 << nominal_initial_state.block<3, 1>(3, 0).transpose();
165 LOG(INFO) << "Nominal pivot_to_imu (angle-axis vector) "
166 << frc971::controls::ToRotationVectorFromQuaternion(
167 calibration_parameters.pivot_to_imu)
168 .transpose();
169 LOG(INFO) << "Nominal pivot_to_imu translation: "
170 << calibration_parameters.pivot_to_imu_translation.transpose();
171 // TODO<Jim>: Might be nice to take out the rotation component that maps into
172 // camera image coordinates (with x right, y down, z forward)
173 LOG(INFO) << "Nominal camera_to_pivot (angle-axis vector): "
174 << frc971::controls::ToRotationVectorFromQuaternion(
175 nominal_camera_to_pivot_rotation)
176 .transpose();
177 LOG(INFO) << "Nominal camera_to_pivot translation: "
178 << nominal_camera_to_pivot_translation.transpose();
179
180 Solve(data, &calibration_parameters);
181
182 LOG(INFO) << "RESULTS OF CALIBRATION SOLVER:";
183 LOG(INFO) << "initial_orientation of imu w.r.t. world (angle-axis vector): "
184 << frc971::controls::ToRotationVectorFromQuaternion(
185 calibration_parameters.initial_orientation)
186 .transpose();
187 LOG(INFO)
188 << "initial_state: \n"
189 << "Position: "
190 << calibration_parameters.initial_state.block<3, 1>(0, 0).transpose()
191 << "\n"
192 << "Velocity: "
193 << calibration_parameters.initial_state.block<3, 1>(3, 0).transpose();
194
195 LOG(INFO) << "pivot_to_imu rotation (angle-axis vec) "
196 << frc971::controls::ToRotationVectorFromQuaternion(
197 calibration_parameters.pivot_to_imu)
198 .transpose();
199 LOG(INFO) << "pivot_to_imu_translation "
200 << calibration_parameters.pivot_to_imu_translation.transpose();
201 const Eigen::Affine3d affine_pivot_to_camera =
202 Eigen::Translation3d(calibration_parameters.pivot_to_camera_translation) *
203 calibration_parameters.pivot_to_camera;
204 const Eigen::Quaterniond camera_to_pivot_rotation(
205 affine_pivot_to_camera.inverse().rotation());
206 const Eigen::Vector3d camera_to_pivot_translation(
207 affine_pivot_to_camera.inverse().translation());
208 LOG(INFO) << "camera to pivot (angle-axis vec): "
209 << frc971::controls::ToRotationVectorFromQuaternion(
210 camera_to_pivot_rotation)
211 .transpose();
212 LOG(INFO) << "camera to pivot translation: "
213 << camera_to_pivot_translation.transpose();
214 LOG(INFO) << "board_to_world (rotation) "
215 << frc971::controls::ToRotationVectorFromQuaternion(
216 calibration_parameters.board_to_world)
217 .transpose();
218 LOG(INFO) << "accelerometer bias "
219 << calibration_parameters.accelerometer_bias.transpose();
220 LOG(INFO) << "gyro_bias " << calibration_parameters.gyro_bias.transpose();
221 LOG(INFO) << "gravity " << 9.81 * calibration_parameters.gravity_scalar;
222
223 LOG(INFO) << "pivot_to_camera change "
224 << frc971::controls::ToRotationVectorFromQuaternion(
225 calibration_parameters.pivot_to_camera *
226 nominal_pivot_to_camera.inverse())
227 .transpose();
228 LOG(INFO) << "board_to_world delta "
229 << frc971::controls::ToRotationVectorFromQuaternion(
230 calibration_parameters.board_to_world *
231 nominal_board_to_world.inverse())
232 .transpose();
233
234 if (FLAGS_visualize) {
235 LOG(INFO) << "Showing visualization";
236 Visualize(data, calibration_parameters);
237 }
238
239 if (FLAGS_plot) {
240 Plot(data, calibration_parameters);
241 }
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800242} // namespace vision
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800243
244} // namespace vision
245} // namespace frc971
246
247int main(int argc, char **argv) {
248 aos::InitGoogle(&argc, &argv);
249
250 frc971::vision::Main(argc, argv);
251}