blob: 521992c237f5275529fa7d2a584da36e1c1980ea [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");
21
22namespace frc971 {
23namespace vision {
24namespace chrono = std::chrono;
25using aos::distributed_clock;
26using aos::monotonic_clock;
27
28// TODO(austin): Source of IMU data? Is it the same?
29// TODO(austin): Intrinsics data?
30
31void Main(int argc, char **argv) {
32 CalibrationData data;
33
34 {
35 // Now, accumulate all the data into the data object.
36 aos::logger::LogReader reader(
37 aos::logger::SortParts(aos::logger::FindLogs(argc, argv)));
38
39 aos::SimulatedEventLoopFactory factory(reader.configuration());
40 reader.Register(&factory);
41
42 CHECK(aos::configuration::MultiNode(reader.configuration()));
43
44 // Find the nodes we care about.
45 const aos::Node *const imu_node =
46 aos::configuration::GetNode(factory.configuration(), "imu");
47 const aos::Node *const roborio_node =
48 aos::configuration::GetNode(factory.configuration(), "roborio");
49
50 std::optional<uint16_t> pi_number = aos::network::ParsePiNumber(FLAGS_pi);
51 CHECK(pi_number);
52 LOG(INFO) << "Pi " << *pi_number;
53 const aos::Node *const pi_node = aos::configuration::GetNode(
54 factory.configuration(), absl::StrCat("pi", *pi_number));
55
56 LOG(INFO) << "imu " << aos::FlatbufferToJson(imu_node);
57 LOG(INFO) << "roboRIO " << aos::FlatbufferToJson(roborio_node);
58 LOG(INFO) << "Pi " << aos::FlatbufferToJson(pi_node);
59
60 std::unique_ptr<aos::EventLoop> imu_event_loop =
61 factory.MakeEventLoop("calibration", imu_node);
62 std::unique_ptr<aos::EventLoop> roborio_event_loop =
63 factory.MakeEventLoop("calibration", roborio_node);
64 std::unique_ptr<aos::EventLoop> pi_event_loop =
65 factory.MakeEventLoop("calibration", pi_node);
66
67 // Now, hook Calibration up to everything.
68 Calibration extractor(&factory, pi_event_loop.get(), imu_event_loop.get(),
69 FLAGS_pi, &data);
70
71 if (FLAGS_turret) {
72 aos::NodeEventLoopFactory *roborio_factory =
73 factory.GetNodeEventLoopFactory(roborio_node->name()->string_view());
74 roborio_event_loop->MakeWatcher(
75 "/superstructure",
76 [roborio_factory, roborio_event_loop = roborio_event_loop.get(),
77 &data](const y2022::control_loops::superstructure::Status &status) {
78 data.AddTurret(
79 roborio_factory->ToDistributedClock(
80 roborio_event_loop->context().monotonic_event_time),
81 Eigen::Vector2d(status.turret()->position(),
82 status.turret()->velocity()));
83 });
84 }
85
86 factory.Run();
87
88 reader.Deregister();
89 }
90
91 LOG(INFO) << "Done with event_loop running";
92 CHECK(data.imu_samples_size() > 0) << "Didn't get any IMU data";
93 CHECK(data.camera_samples_size() > 0) << "Didn't get any camera observations";
94
95 // And now we have it, we can start processing it.
96 const Eigen::Quaternion<double> nominal_initial_orientation(
97 frc971::controls::ToQuaternionFromRotationVector(
98 Eigen::Vector3d(0.0, 0.0, M_PI)));
99 const Eigen::Quaternion<double> nominal_pivot_to_camera(
100 Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX()));
101 const Eigen::Quaternion<double> nominal_pivot_to_imu(
102 Eigen::AngleAxisd(0.0, Eigen::Vector3d::UnitX()));
103 const Eigen::Quaternion<double> nominal_board_to_world(
104 Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitX()));
105 Eigen::Matrix<double, 6, 1> nominal_initial_state =
106 Eigen::Matrix<double, 6, 1>::Zero();
107 // Set x value to 0.5 m (center view on the board)
108 // nominal_initial_state(0, 0) = 0.5;
109 // Set y value to -1 m (approx distance from imu to board/world)
110 nominal_initial_state(1, 0) = -1.0;
111
112 CalibrationParameters calibration_parameters;
113 calibration_parameters.initial_orientation = nominal_initial_orientation;
114 calibration_parameters.pivot_to_camera = nominal_pivot_to_camera;
115 calibration_parameters.pivot_to_imu = nominal_pivot_to_imu;
116 calibration_parameters.board_to_world = nominal_board_to_world;
117 calibration_parameters.initial_state = nominal_initial_state;
118
119 // Show the inverse of pivot_to_camera, since camera_to_pivot tells where the
120 // camera is with respect to the pivot frame
121 const Eigen::Affine3d nominal_affine_pivot_to_camera =
122 Eigen::Translation3d(calibration_parameters.pivot_to_camera_translation) *
123 nominal_pivot_to_camera;
124 const Eigen::Quaterniond nominal_camera_to_pivot_rotation(
125 nominal_affine_pivot_to_camera.inverse().rotation());
126 const Eigen::Vector3d nominal_camera_to_pivot_translation(
127 nominal_affine_pivot_to_camera.inverse().translation());
128
129 if (data.turret_samples_size() > 0) {
130 LOG(INFO) << "Have turret, so using pivot setup";
131 calibration_parameters.has_pivot = true;
132 }
133
134 LOG(INFO) << "Initial Conditions for solver. Assumes:\n"
135 << "1) board origin is same as world, but rotated pi/2 about "
136 "x-axis, so z points out\n"
137 << "2) pivot origin matches imu origin\n"
138 << "3) camera is offset from pivot (depends on which camera)";
139
140 LOG(INFO)
141 << "Nominal initial_orientation of imu w.r.t. world (angle-axis vector): "
142 << frc971::controls::ToRotationVectorFromQuaternion(
143 nominal_initial_orientation)
144 .transpose();
145 LOG(INFO) << "Nominal initial_state: \n"
146 << "Position: "
147 << nominal_initial_state.block<3, 1>(0, 0).transpose() << "\n"
148 << "Velocity: "
149 << nominal_initial_state.block<3, 1>(3, 0).transpose();
150 LOG(INFO) << "Nominal pivot_to_imu (angle-axis vector) "
151 << frc971::controls::ToRotationVectorFromQuaternion(
152 calibration_parameters.pivot_to_imu)
153 .transpose();
154 LOG(INFO) << "Nominal pivot_to_imu translation: "
155 << calibration_parameters.pivot_to_imu_translation.transpose();
156 // TODO<Jim>: Might be nice to take out the rotation component that maps into
157 // camera image coordinates (with x right, y down, z forward)
158 LOG(INFO) << "Nominal camera_to_pivot (angle-axis vector): "
159 << frc971::controls::ToRotationVectorFromQuaternion(
160 nominal_camera_to_pivot_rotation)
161 .transpose();
162 LOG(INFO) << "Nominal camera_to_pivot translation: "
163 << nominal_camera_to_pivot_translation.transpose();
164
165 Solve(data, &calibration_parameters);
166
167 LOG(INFO) << "RESULTS OF CALIBRATION SOLVER:";
168 LOG(INFO) << "initial_orientation of imu w.r.t. world (angle-axis vector): "
169 << frc971::controls::ToRotationVectorFromQuaternion(
170 calibration_parameters.initial_orientation)
171 .transpose();
172 LOG(INFO)
173 << "initial_state: \n"
174 << "Position: "
175 << calibration_parameters.initial_state.block<3, 1>(0, 0).transpose()
176 << "\n"
177 << "Velocity: "
178 << calibration_parameters.initial_state.block<3, 1>(3, 0).transpose();
179
180 LOG(INFO) << "pivot_to_imu rotation (angle-axis vec) "
181 << frc971::controls::ToRotationVectorFromQuaternion(
182 calibration_parameters.pivot_to_imu)
183 .transpose();
184 LOG(INFO) << "pivot_to_imu_translation "
185 << calibration_parameters.pivot_to_imu_translation.transpose();
186 const Eigen::Affine3d affine_pivot_to_camera =
187 Eigen::Translation3d(calibration_parameters.pivot_to_camera_translation) *
188 calibration_parameters.pivot_to_camera;
189 const Eigen::Quaterniond camera_to_pivot_rotation(
190 affine_pivot_to_camera.inverse().rotation());
191 const Eigen::Vector3d camera_to_pivot_translation(
192 affine_pivot_to_camera.inverse().translation());
193 LOG(INFO) << "camera to pivot (angle-axis vec): "
194 << frc971::controls::ToRotationVectorFromQuaternion(
195 camera_to_pivot_rotation)
196 .transpose();
197 LOG(INFO) << "camera to pivot translation: "
198 << camera_to_pivot_translation.transpose();
199 LOG(INFO) << "board_to_world (rotation) "
200 << frc971::controls::ToRotationVectorFromQuaternion(
201 calibration_parameters.board_to_world)
202 .transpose();
203 LOG(INFO) << "accelerometer bias "
204 << calibration_parameters.accelerometer_bias.transpose();
205 LOG(INFO) << "gyro_bias " << calibration_parameters.gyro_bias.transpose();
206 LOG(INFO) << "gravity " << 9.81 * calibration_parameters.gravity_scalar;
207
208 LOG(INFO) << "pivot_to_camera change "
209 << frc971::controls::ToRotationVectorFromQuaternion(
210 calibration_parameters.pivot_to_camera *
211 nominal_pivot_to_camera.inverse())
212 .transpose();
213 LOG(INFO) << "board_to_world delta "
214 << frc971::controls::ToRotationVectorFromQuaternion(
215 calibration_parameters.board_to_world *
216 nominal_board_to_world.inverse())
217 .transpose();
218
219 if (FLAGS_visualize) {
220 LOG(INFO) << "Showing visualization";
221 Visualize(data, calibration_parameters);
222 }
223
224 if (FLAGS_plot) {
225 Plot(data, calibration_parameters);
226 }
227}
228
229} // namespace vision
230} // namespace frc971
231
232int main(int argc, char **argv) {
233 aos::InitGoogle(&argc, &argv);
234
235 frc971::vision::Main(argc, argv);
236}