blob: 49f2ca377263dcac246af23623bbe8688045866d [file] [log] [blame]
Austin Schuh3e145882022-02-26 16:48:43 -08001#include "frc971/vision/extrinsics_calibration.h"
2
3#include "Eigen/Dense"
4#include "Eigen/Geometry"
5#include "absl/strings/str_format.h"
6#include "aos/events/logging/log_reader.h"
7#include "aos/init.h"
8#include "aos/network/team_number.h"
9#include "aos/time/time.h"
10#include "aos/util/file.h"
11#include "frc971/control_loops/quaternion_utils.h"
12#include "frc971/vision/vision_generated.h"
13#include "frc971/wpilib/imu_batch_generated.h"
14#include "y2022/control_loops/superstructure/superstructure_status_generated.h"
15#include "y2020/vision/sift/sift_generated.h"
16#include "y2020/vision/sift/sift_training_generated.h"
17#include "y2020/vision/tools/python_code/sift_training_data.h"
18
19DEFINE_string(pi, "pi-7971-2", "Pi name to calibrate.");
20DEFINE_bool(plot, false, "Whether to plot the resulting data.");
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 roborio_node =
46 aos::configuration::GetNode(factory.configuration(), "roborio");
47
48 std::optional<uint16_t> pi_number = aos::network::ParsePiNumber(FLAGS_pi);
49 CHECK(pi_number);
50 LOG(INFO) << "Pi " << *pi_number;
51 const aos::Node *const pi_node = aos::configuration::GetNode(
52 factory.configuration(), absl::StrCat("pi", *pi_number));
53
54 LOG(INFO) << "roboRIO " << aos::FlatbufferToJson(roborio_node);
55 LOG(INFO) << "Pi " << aos::FlatbufferToJson(pi_node);
56
57 std::unique_ptr<aos::EventLoop> roborio_event_loop =
58 factory.MakeEventLoop("calibration", roborio_node);
59 std::unique_ptr<aos::EventLoop> pi_event_loop =
60 factory.MakeEventLoop("calibration", pi_node);
61
62 // Now, hook Calibration up to everything.
63 Calibration extractor(&factory, pi_event_loop.get(),
64 roborio_event_loop.get(), FLAGS_pi, &data);
65
66 aos::NodeEventLoopFactory *roborio_factory =
67 factory.GetNodeEventLoopFactory(roborio_node->name()->string_view());
68 roborio_event_loop->MakeWatcher(
69 "/superstructure",
70 [roborio_factory, roborio_event_loop = roborio_event_loop.get(),
71 &data](const y2022::control_loops::superstructure::Status &status) {
72 data.AddTurret(
73 roborio_factory->ToDistributedClock(
74 roborio_event_loop->context().monotonic_event_time),
75 Eigen::Vector2d(status.turret()->position(),
76 status.turret()->velocity()));
77 });
78
79 factory.Run();
80
81 reader.Deregister();
82 }
83
84 LOG(INFO) << "Done with event_loop running";
85 // And now we have it, we can start processing it.
86
87 const Eigen::Quaternion<double> nominal_initial_orientation(
88 frc971::controls::ToQuaternionFromRotationVector(
89 Eigen::Vector3d(0.0, 0.0, M_PI)));
90 const Eigen::Quaternion<double> nominal_pivot_to_camera(
91 Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX()));
92 const Eigen::Quaternion<double> nominal_board_to_world(
93 Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitX()));
94
95 CalibrationParameters calibration_parameters;
96 calibration_parameters.initial_orientation = nominal_initial_orientation;
97 calibration_parameters.pivot_to_camera = nominal_pivot_to_camera;
98 calibration_parameters.board_to_world = nominal_board_to_world;
99
100 Solve(data, &calibration_parameters);
101 LOG(INFO) << "Nominal initial_orientation "
102 << nominal_initial_orientation.coeffs().transpose();
103 LOG(INFO) << "Nominal pivot_to_camera "
104 << nominal_pivot_to_camera.coeffs().transpose();
105
106 LOG(INFO) << "pivot_to_camera delta "
107 << frc971::controls::ToRotationVectorFromQuaternion(
108 calibration_parameters.pivot_to_camera *
109 nominal_pivot_to_camera.inverse())
110 .transpose();
111 LOG(INFO) << "board_to_world delta "
112 << frc971::controls::ToRotationVectorFromQuaternion(
113 calibration_parameters.board_to_world *
114 nominal_board_to_world.inverse())
115 .transpose();
116
117 if (FLAGS_plot) {
118 Plot(data, calibration_parameters);
119 }
120}
121
122} // namespace vision
123} // namespace frc971
124
125int main(int argc, char **argv) {
126 aos::InitGoogle(&argc, &argv);
127
128 frc971::vision::Main(argc, argv);
129}