blob: d0497e0aec8d456579d1fbd576d56340fa6659de [file] [log] [blame]
Austin Schuh2895f4c2022-02-26 16:38:46 -08001#include "frc971/vision/extrinsics_calibration.h"
2
Austin Schuhbb4aae72021-10-08 22:12:25 -07003#include "Eigen/Dense"
4#include "Eigen/Geometry"
Austin Schuhbb4aae72021-10-08 22:12:25 -07005#include "absl/strings/str_format.h"
Austin Schuhbb4aae72021-10-08 22:12:25 -07006#include "aos/events/logging/log_reader.h"
Austin Schuhbb4aae72021-10-08 22:12:25 -07007#include "aos/init.h"
8#include "aos/network/team_number.h"
9#include "aos/time/time.h"
10#include "aos/util/file.h"
milind-u8c72d532021-12-11 15:02:42 -080011#include "frc971/control_loops/quaternion_utils.h"
Jim Ostrowski977850f2022-01-22 21:04:22 -080012#include "frc971/vision/vision_generated.h"
milind-u8c72d532021-12-11 15:02:42 -080013#include "frc971/wpilib/imu_batch_generated.h"
Austin Schuh2895f4c2022-02-26 16:38:46 -080014#include "y2020/control_loops/superstructure/superstructure_status_generated.h"
Austin Schuhbb4aae72021-10-08 22:12:25 -070015#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"
Austin Schuhbb4aae72021-10-08 22:12:25 -070018
Austin Schuhc5fa6d92022-02-25 14:36:28 -080019DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
Austin Schuhbb4aae72021-10-08 22:12:25 -070020DEFINE_string(pi, "pi-7971-2", "Pi name to calibrate.");
milind-u0084be62021-12-27 12:29:38 +053021DEFINE_bool(plot, false, "Whether to plot the resulting data.");
Austin Schuh2895f4c2022-02-26 16:38:46 -080022DEFINE_bool(turret, false, "If true, the camera is on the turret");
Austin Schuhbb4aae72021-10-08 22:12:25 -070023
24namespace frc971 {
25namespace vision {
26namespace chrono = std::chrono;
27using aos::distributed_clock;
28using aos::monotonic_clock;
29
Austin Schuhbb4aae72021-10-08 22:12:25 -070030void Main(int argc, char **argv) {
31 CalibrationData data;
32
33 {
34 // Now, accumulate all the data into the data object.
35 aos::logger::LogReader reader(
36 aos::logger::SortParts(aos::logger::FindLogs(argc, argv)));
37
38 aos::SimulatedEventLoopFactory factory(reader.configuration());
39 reader.Register(&factory);
40
41 CHECK(aos::configuration::MultiNode(reader.configuration()));
42
43 // Find the nodes we care about.
44 const aos::Node *const roborio_node =
45 aos::configuration::GetNode(factory.configuration(), "roborio");
46
47 std::optional<uint16_t> pi_number = aos::network::ParsePiNumber(FLAGS_pi);
48 CHECK(pi_number);
49 LOG(INFO) << "Pi " << *pi_number;
50 const aos::Node *const pi_node = aos::configuration::GetNode(
51 factory.configuration(), absl::StrCat("pi", *pi_number));
52
53 LOG(INFO) << "roboRIO " << aos::FlatbufferToJson(roborio_node);
54 LOG(INFO) << "Pi " << aos::FlatbufferToJson(pi_node);
55
56 std::unique_ptr<aos::EventLoop> roborio_event_loop =
57 factory.MakeEventLoop("calibration", roborio_node);
58 std::unique_ptr<aos::EventLoop> pi_event_loop =
59 factory.MakeEventLoop("calibration", pi_node);
60
61 // Now, hook Calibration up to everything.
62 Calibration extractor(&factory, pi_event_loop.get(),
63 roborio_event_loop.get(), FLAGS_pi, &data);
64
Austin Schuh2895f4c2022-02-26 16:38:46 -080065 if (FLAGS_turret) {
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 y2020::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
Austin Schuhbb4aae72021-10-08 22:12:25 -070080 factory.Run();
81
82 reader.Deregister();
83 }
84
85 LOG(INFO) << "Done with event_loop running";
86 // And now we have it, we can start processing it.
milind-u8c72d532021-12-11 15:02:42 -080087
Austin Schuh5b379072021-12-26 16:01:04 -080088 const Eigen::Quaternion<double> nominal_initial_orientation(
milind-ue53bf552021-12-11 14:42:00 -080089 frc971::controls::ToQuaternionFromRotationVector(
90 Eigen::Vector3d(0.0, 0.0, M_PI)));
Austin Schuh2895f4c2022-02-26 16:38:46 -080091 const Eigen::Quaternion<double> nominal_pivot_to_camera(
milind-ue53bf552021-12-11 14:42:00 -080092 Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX()));
Austin Schuh5b379072021-12-26 16:01:04 -080093 const Eigen::Quaternion<double> nominal_board_to_world(
94 Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitX()));
milind-ue53bf552021-12-11 14:42:00 -080095
Austin Schuhdcb6b362022-02-25 18:06:21 -080096 CalibrationParameters calibration_parameters;
97 calibration_parameters.initial_orientation = nominal_initial_orientation;
Austin Schuh2895f4c2022-02-26 16:38:46 -080098 calibration_parameters.pivot_to_camera = nominal_pivot_to_camera;
Austin Schuhdcb6b362022-02-25 18:06:21 -080099 calibration_parameters.board_to_world = nominal_board_to_world;
Austin Schuh5b379072021-12-26 16:01:04 -0800100
Austin Schuhdcb6b362022-02-25 18:06:21 -0800101 Solve(data, &calibration_parameters);
102 LOG(INFO) << "Nominal initial_orientation "
103 << nominal_initial_orientation.coeffs().transpose();
Austin Schuh2895f4c2022-02-26 16:38:46 -0800104 LOG(INFO) << "Nominal pivot_to_camera "
105 << nominal_pivot_to_camera.coeffs().transpose();
milind-ue53bf552021-12-11 14:42:00 -0800106
Austin Schuh2895f4c2022-02-26 16:38:46 -0800107 LOG(INFO) << "pivot_to_camera delta "
Austin Schuhdcb6b362022-02-25 18:06:21 -0800108 << frc971::controls::ToRotationVectorFromQuaternion(
Austin Schuh2895f4c2022-02-26 16:38:46 -0800109 calibration_parameters.pivot_to_camera *
110 nominal_pivot_to_camera.inverse())
Austin Schuhdcb6b362022-02-25 18:06:21 -0800111 .transpose();
112 LOG(INFO) << "board_to_world delta "
113 << frc971::controls::ToRotationVectorFromQuaternion(
114 calibration_parameters.board_to_world *
115 nominal_board_to_world.inverse())
116 .transpose();
milind-ue53bf552021-12-11 14:42:00 -0800117
Austin Schuhdcb6b362022-02-25 18:06:21 -0800118 if (FLAGS_plot) {
119 Plot(data, calibration_parameters);
milind-u8c72d532021-12-11 15:02:42 -0800120 }
Austin Schuhbb4aae72021-10-08 22:12:25 -0700121}
122
123} // namespace vision
124} // namespace frc971
125
126int main(int argc, char **argv) {
127 aos::InitGoogle(&argc, &argv);
128
129 frc971::vision::Main(argc, argv);
130}