blob: 83d87608276a097dc84f9f83423a5d784483d20b [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 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 Schuh2895f4c2022-02-26 16:38:46 -080021DEFINE_bool(turret, false, "If true, the camera is on the turret");
Austin Schuhbb4aae72021-10-08 22:12:25 -070022
23namespace frc971 {
24namespace vision {
25namespace chrono = std::chrono;
26using aos::distributed_clock;
27using aos::monotonic_clock;
28
Austin Schuhbb4aae72021-10-08 22:12:25 -070029void Main(int argc, char **argv) {
30 CalibrationData data;
31
32 {
33 // Now, accumulate all the data into the data object.
34 aos::logger::LogReader reader(
35 aos::logger::SortParts(aos::logger::FindLogs(argc, argv)));
36
37 aos::SimulatedEventLoopFactory factory(reader.configuration());
38 reader.Register(&factory);
39
40 CHECK(aos::configuration::MultiNode(reader.configuration()));
41
42 // Find the nodes we care about.
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080043 const aos::Node *const imu_node =
44 aos::configuration::GetNode(factory.configuration(), "imu");
Austin Schuhbb4aae72021-10-08 22:12:25 -070045 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
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080054 LOG(INFO) << "imu " << aos::FlatbufferToJson(imu_node);
Austin Schuhbb4aae72021-10-08 22:12:25 -070055 LOG(INFO) << "roboRIO " << aos::FlatbufferToJson(roborio_node);
56 LOG(INFO) << "Pi " << aos::FlatbufferToJson(pi_node);
57
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080058 std::unique_ptr<aos::EventLoop> imu_event_loop =
59 factory.MakeEventLoop("calibration", imu_node);
Austin Schuhbb4aae72021-10-08 22:12:25 -070060 std::unique_ptr<aos::EventLoop> roborio_event_loop =
61 factory.MakeEventLoop("calibration", roborio_node);
62 std::unique_ptr<aos::EventLoop> pi_event_loop =
63 factory.MakeEventLoop("calibration", pi_node);
64
65 // Now, hook Calibration up to everything.
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080066 Calibration extractor(&factory, pi_event_loop.get(), imu_event_loop.get(),
67 FLAGS_pi, &data);
Austin Schuhbb4aae72021-10-08 22:12:25 -070068
Austin Schuh2895f4c2022-02-26 16:38:46 -080069 if (FLAGS_turret) {
70 aos::NodeEventLoopFactory *roborio_factory =
71 factory.GetNodeEventLoopFactory(roborio_node->name()->string_view());
72 roborio_event_loop->MakeWatcher(
73 "/superstructure",
74 [roborio_factory, roborio_event_loop = roborio_event_loop.get(),
75 &data](const y2020::control_loops::superstructure::Status &status) {
76 data.AddTurret(
77 roborio_factory->ToDistributedClock(
78 roborio_event_loop->context().monotonic_event_time),
79 Eigen::Vector2d(status.turret()->position(),
80 status.turret()->velocity()));
81 });
82 }
83
Austin Schuhbb4aae72021-10-08 22:12:25 -070084 factory.Run();
85
86 reader.Deregister();
87 }
88
89 LOG(INFO) << "Done with event_loop running";
90 // And now we have it, we can start processing it.
milind-u8c72d532021-12-11 15:02:42 -080091
Austin Schuh5b379072021-12-26 16:01:04 -080092 const Eigen::Quaternion<double> nominal_initial_orientation(
milind-ue53bf552021-12-11 14:42:00 -080093 frc971::controls::ToQuaternionFromRotationVector(
94 Eigen::Vector3d(0.0, 0.0, M_PI)));
Austin Schuh2895f4c2022-02-26 16:38:46 -080095 const Eigen::Quaternion<double> nominal_pivot_to_camera(
milind-ue53bf552021-12-11 14:42:00 -080096 Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX()));
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080097 const Eigen::Quaternion<double> nominal_pivot_to_imu(
98 Eigen::AngleAxisd(0.0, Eigen::Vector3d::UnitX()));
Austin Schuh5b379072021-12-26 16:01:04 -080099 const Eigen::Quaternion<double> nominal_board_to_world(
100 Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitX()));
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800101 Eigen::Matrix<double, 6, 1> nominal_initial_state =
102 Eigen::Matrix<double, 6, 1>::Zero();
103 // Set y value to -1 m (approx distance from imu to board/world
104 nominal_initial_state(1, 0) = -1.0;
milind-ue53bf552021-12-11 14:42:00 -0800105
Austin Schuhdcb6b362022-02-25 18:06:21 -0800106 CalibrationParameters calibration_parameters;
107 calibration_parameters.initial_orientation = nominal_initial_orientation;
Austin Schuh2895f4c2022-02-26 16:38:46 -0800108 calibration_parameters.pivot_to_camera = nominal_pivot_to_camera;
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800109 calibration_parameters.pivot_to_imu = nominal_pivot_to_imu;
Austin Schuhdcb6b362022-02-25 18:06:21 -0800110 calibration_parameters.board_to_world = nominal_board_to_world;
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800111 calibration_parameters.initial_state = nominal_initial_state;
112 if (data.turret_samples_size() > 0) {
113 LOG(INFO) << "Have turret, so using pivot setup";
114 calibration_parameters.has_pivot = true;
115 }
Austin Schuh5b379072021-12-26 16:01:04 -0800116
Austin Schuhdcb6b362022-02-25 18:06:21 -0800117 Solve(data, &calibration_parameters);
118 LOG(INFO) << "Nominal initial_orientation "
119 << nominal_initial_orientation.coeffs().transpose();
Austin Schuh2895f4c2022-02-26 16:38:46 -0800120 LOG(INFO) << "Nominal pivot_to_camera "
121 << nominal_pivot_to_camera.coeffs().transpose();
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800122 LOG(INFO) << "Nominal pivot_to_camera (rot-xyz) "
123 << frc971::controls::ToRotationVectorFromQuaternion(
124 nominal_pivot_to_camera)
125 .transpose();
126 LOG(INFO) << "pivot_to_camera change "
Austin Schuhdcb6b362022-02-25 18:06:21 -0800127 << frc971::controls::ToRotationVectorFromQuaternion(
Austin Schuh2895f4c2022-02-26 16:38:46 -0800128 calibration_parameters.pivot_to_camera *
129 nominal_pivot_to_camera.inverse())
Austin Schuhdcb6b362022-02-25 18:06:21 -0800130 .transpose();
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800131 LOG(INFO) << "Nominal pivot_to_imu "
132 << nominal_pivot_to_imu.coeffs().transpose();
Austin Schuhdcb6b362022-02-25 18:06:21 -0800133 LOG(INFO) << "board_to_world delta "
134 << frc971::controls::ToRotationVectorFromQuaternion(
135 calibration_parameters.board_to_world *
136 nominal_board_to_world.inverse())
137 .transpose();
milind-ue53bf552021-12-11 14:42:00 -0800138
Austin Schuhdcb6b362022-02-25 18:06:21 -0800139 if (FLAGS_plot) {
140 Plot(data, calibration_parameters);
milind-u8c72d532021-12-11 15:02:42 -0800141 }
Austin Schuhbb4aae72021-10-08 22:12:25 -0700142}
143
144} // namespace vision
145} // namespace frc971
146
147int main(int argc, char **argv) {
148 aos::InitGoogle(&argc, &argv);
149
150 frc971::vision::Main(argc, argv);
151}