blob: c54a5cf8ee4ce985476ade5b11cc4afcb2546ec0 [file] [log] [blame]
Austin Schuhbb4aae72021-10-08 22:12:25 -07001#include "Eigen/Dense"
2#include "Eigen/Geometry"
3
Austin Schuhbb4aae72021-10-08 22:12:25 -07004#include "absl/strings/str_format.h"
Austin Schuhbb4aae72021-10-08 22:12:25 -07005#include "aos/events/logging/log_reader.h"
Austin Schuhbb4aae72021-10-08 22:12:25 -07006#include "aos/init.h"
7#include "aos/network/team_number.h"
8#include "aos/time/time.h"
9#include "aos/util/file.h"
milind-u8c72d532021-12-11 15:02:42 -080010#include "frc971/control_loops/quaternion_utils.h"
Jim Ostrowski977850f2022-01-22 21:04:22 -080011#include "frc971/vision/vision_generated.h"
Austin Schuhdcb6b362022-02-25 18:06:21 -080012#include "frc971/vision/extrinsics_calibration.h"
milind-u8c72d532021-12-11 15:02:42 -080013#include "frc971/wpilib/imu_batch_generated.h"
Austin Schuhbb4aae72021-10-08 22:12:25 -070014#include "y2020/vision/sift/sift_generated.h"
15#include "y2020/vision/sift/sift_training_generated.h"
16#include "y2020/vision/tools/python_code/sift_training_data.h"
Austin Schuhbb4aae72021-10-08 22:12:25 -070017
Austin Schuhc5fa6d92022-02-25 14:36:28 -080018DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
Austin Schuhbb4aae72021-10-08 22:12:25 -070019DEFINE_string(pi, "pi-7971-2", "Pi name to calibrate.");
milind-u0084be62021-12-27 12:29:38 +053020DEFINE_bool(plot, false, "Whether to plot the resulting data.");
Austin Schuhbb4aae72021-10-08 22:12:25 -070021
22namespace frc971 {
23namespace vision {
24namespace chrono = std::chrono;
25using aos::distributed_clock;
26using aos::monotonic_clock;
27
Austin Schuhbb4aae72021-10-08 22:12:25 -070028void Main(int argc, char **argv) {
29 CalibrationData data;
30
31 {
32 // Now, accumulate all the data into the data object.
33 aos::logger::LogReader reader(
34 aos::logger::SortParts(aos::logger::FindLogs(argc, argv)));
35
36 aos::SimulatedEventLoopFactory factory(reader.configuration());
37 reader.Register(&factory);
38
39 CHECK(aos::configuration::MultiNode(reader.configuration()));
40
41 // Find the nodes we care about.
42 const aos::Node *const roborio_node =
43 aos::configuration::GetNode(factory.configuration(), "roborio");
44
45 std::optional<uint16_t> pi_number = aos::network::ParsePiNumber(FLAGS_pi);
46 CHECK(pi_number);
47 LOG(INFO) << "Pi " << *pi_number;
48 const aos::Node *const pi_node = aos::configuration::GetNode(
49 factory.configuration(), absl::StrCat("pi", *pi_number));
50
51 LOG(INFO) << "roboRIO " << aos::FlatbufferToJson(roborio_node);
52 LOG(INFO) << "Pi " << aos::FlatbufferToJson(pi_node);
53
54 std::unique_ptr<aos::EventLoop> roborio_event_loop =
55 factory.MakeEventLoop("calibration", roborio_node);
56 std::unique_ptr<aos::EventLoop> pi_event_loop =
57 factory.MakeEventLoop("calibration", pi_node);
58
59 // Now, hook Calibration up to everything.
60 Calibration extractor(&factory, pi_event_loop.get(),
61 roborio_event_loop.get(), FLAGS_pi, &data);
62
63 factory.Run();
64
65 reader.Deregister();
66 }
67
68 LOG(INFO) << "Done with event_loop running";
69 // And now we have it, we can start processing it.
milind-u8c72d532021-12-11 15:02:42 -080070
Austin Schuh5b379072021-12-26 16:01:04 -080071 const Eigen::Quaternion<double> nominal_initial_orientation(
milind-ue53bf552021-12-11 14:42:00 -080072 frc971::controls::ToQuaternionFromRotationVector(
73 Eigen::Vector3d(0.0, 0.0, M_PI)));
Austin Schuh5b379072021-12-26 16:01:04 -080074 const Eigen::Quaternion<double> nominal_imu_to_camera(
milind-ue53bf552021-12-11 14:42:00 -080075 Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX()));
Austin Schuh5b379072021-12-26 16:01:04 -080076 const Eigen::Quaternion<double> nominal_board_to_world(
77 Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitX()));
milind-ue53bf552021-12-11 14:42:00 -080078
Austin Schuhdcb6b362022-02-25 18:06:21 -080079 CalibrationParameters calibration_parameters;
80 calibration_parameters.initial_orientation = nominal_initial_orientation;
81 calibration_parameters.imu_to_camera = nominal_imu_to_camera;
82 calibration_parameters.board_to_world = nominal_board_to_world;
Austin Schuh5b379072021-12-26 16:01:04 -080083
Austin Schuhdcb6b362022-02-25 18:06:21 -080084 Solve(data, &calibration_parameters);
85 LOG(INFO) << "Nominal initial_orientation "
86 << nominal_initial_orientation.coeffs().transpose();
87 LOG(INFO) << "Nominal imu_to_camera "
88 << nominal_imu_to_camera.coeffs().transpose();
milind-ue53bf552021-12-11 14:42:00 -080089
Austin Schuhdcb6b362022-02-25 18:06:21 -080090 LOG(INFO) << "imu_to_camera delta "
91 << frc971::controls::ToRotationVectorFromQuaternion(
92 calibration_parameters.imu_to_camera *
93 nominal_imu_to_camera.inverse())
94 .transpose();
95 LOG(INFO) << "board_to_world delta "
96 << frc971::controls::ToRotationVectorFromQuaternion(
97 calibration_parameters.board_to_world *
98 nominal_board_to_world.inverse())
99 .transpose();
milind-ue53bf552021-12-11 14:42:00 -0800100
Austin Schuhdcb6b362022-02-25 18:06:21 -0800101 if (FLAGS_plot) {
102 Plot(data, calibration_parameters);
milind-u8c72d532021-12-11 15:02:42 -0800103 }
Austin Schuhbb4aae72021-10-08 22:12:25 -0700104}
105
106} // namespace vision
107} // namespace frc971
108
109int main(int argc, char **argv) {
110 aos::InitGoogle(&argc, &argv);
111
112 frc971::vision::Main(argc, argv);
113}