Add a 2022 extrinsics main

This give us a place to add 2022 specific changes

Change-Id: Ife61345e48b09f0fe4971ff316048c4baa4b354c
Signed-off-by: Austin Schuh <austin.linux@gmail.com>
diff --git a/y2020/vision/extrinsics_calibration.cc b/y2020/vision/extrinsics_calibration.cc
index d0497e0..c561652 100644
--- a/y2020/vision/extrinsics_calibration.cc
+++ b/y2020/vision/extrinsics_calibration.cc
@@ -16,7 +16,6 @@
 #include "y2020/vision/sift/sift_training_generated.h"
 #include "y2020/vision/tools/python_code/sift_training_data.h"
 
-DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
 DEFINE_string(pi, "pi-7971-2", "Pi name to calibrate.");
 DEFINE_bool(plot, false, "Whether to plot the resulting data.");
 DEFINE_bool(turret, false, "If true, the camera is on the turret");
diff --git a/y2022/vision/BUILD b/y2022/vision/BUILD
index 284dd66..af9879d 100644
--- a/y2022/vision/BUILD
+++ b/y2022/vision/BUILD
@@ -183,3 +183,19 @@
         "//third_party:opencv",
     ],
 )
+
+cc_binary(
+    name = "extrinsics_calibration",
+    srcs = [
+        "extrinsics_calibration.cc",
+    ],
+    target_compatible_with = ["@platforms//os:linux"],
+    visibility = ["//y2022:__subpackages__"],
+    deps = [
+        "//aos:init",
+        "//aos/events/logging:log_reader",
+        "//frc971/control_loops:profiled_subsystem_fbs",
+        "//frc971/vision:extrinsics_calibration",
+        "//y2022/control_loops/superstructure:superstructure_status_fbs",
+    ],
+)
diff --git a/y2022/vision/extrinsics_calibration.cc b/y2022/vision/extrinsics_calibration.cc
new file mode 100644
index 0000000..49f2ca3
--- /dev/null
+++ b/y2022/vision/extrinsics_calibration.cc
@@ -0,0 +1,129 @@
+#include "frc971/vision/extrinsics_calibration.h"
+
+#include "Eigen/Dense"
+#include "Eigen/Geometry"
+#include "absl/strings/str_format.h"
+#include "aos/events/logging/log_reader.h"
+#include "aos/init.h"
+#include "aos/network/team_number.h"
+#include "aos/time/time.h"
+#include "aos/util/file.h"
+#include "frc971/control_loops/quaternion_utils.h"
+#include "frc971/vision/vision_generated.h"
+#include "frc971/wpilib/imu_batch_generated.h"
+#include "y2022/control_loops/superstructure/superstructure_status_generated.h"
+#include "y2020/vision/sift/sift_generated.h"
+#include "y2020/vision/sift/sift_training_generated.h"
+#include "y2020/vision/tools/python_code/sift_training_data.h"
+
+DEFINE_string(pi, "pi-7971-2", "Pi name to calibrate.");
+DEFINE_bool(plot, false, "Whether to plot the resulting data.");
+
+namespace frc971 {
+namespace vision {
+namespace chrono = std::chrono;
+using aos::distributed_clock;
+using aos::monotonic_clock;
+
+// TODO(austin): Source of IMU data?  Is it the same?
+// TODO(austin): Intrinsics data?
+
+void Main(int argc, char **argv) {
+  CalibrationData data;
+
+  {
+    // Now, accumulate all the data into the data object.
+    aos::logger::LogReader reader(
+        aos::logger::SortParts(aos::logger::FindLogs(argc, argv)));
+
+    aos::SimulatedEventLoopFactory factory(reader.configuration());
+    reader.Register(&factory);
+
+    CHECK(aos::configuration::MultiNode(reader.configuration()));
+
+    // Find the nodes we care about.
+    const aos::Node *const roborio_node =
+        aos::configuration::GetNode(factory.configuration(), "roborio");
+
+    std::optional<uint16_t> pi_number = aos::network::ParsePiNumber(FLAGS_pi);
+    CHECK(pi_number);
+    LOG(INFO) << "Pi " << *pi_number;
+    const aos::Node *const pi_node = aos::configuration::GetNode(
+        factory.configuration(), absl::StrCat("pi", *pi_number));
+
+    LOG(INFO) << "roboRIO " << aos::FlatbufferToJson(roborio_node);
+    LOG(INFO) << "Pi " << aos::FlatbufferToJson(pi_node);
+
+    std::unique_ptr<aos::EventLoop> roborio_event_loop =
+        factory.MakeEventLoop("calibration", roborio_node);
+    std::unique_ptr<aos::EventLoop> pi_event_loop =
+        factory.MakeEventLoop("calibration", pi_node);
+
+    // Now, hook Calibration up to everything.
+    Calibration extractor(&factory, pi_event_loop.get(),
+                          roborio_event_loop.get(), FLAGS_pi, &data);
+
+    aos::NodeEventLoopFactory *roborio_factory =
+        factory.GetNodeEventLoopFactory(roborio_node->name()->string_view());
+    roborio_event_loop->MakeWatcher(
+        "/superstructure",
+        [roborio_factory, roborio_event_loop = roborio_event_loop.get(),
+         &data](const y2022::control_loops::superstructure::Status &status) {
+          data.AddTurret(
+              roborio_factory->ToDistributedClock(
+                  roborio_event_loop->context().monotonic_event_time),
+              Eigen::Vector2d(status.turret()->position(),
+                              status.turret()->velocity()));
+        });
+
+    factory.Run();
+
+    reader.Deregister();
+  }
+
+  LOG(INFO) << "Done with event_loop running";
+  // And now we have it, we can start processing it.
+
+  const Eigen::Quaternion<double> nominal_initial_orientation(
+      frc971::controls::ToQuaternionFromRotationVector(
+          Eigen::Vector3d(0.0, 0.0, M_PI)));
+  const Eigen::Quaternion<double> nominal_pivot_to_camera(
+      Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX()));
+  const Eigen::Quaternion<double> nominal_board_to_world(
+      Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitX()));
+
+  CalibrationParameters calibration_parameters;
+  calibration_parameters.initial_orientation = nominal_initial_orientation;
+  calibration_parameters.pivot_to_camera = nominal_pivot_to_camera;
+  calibration_parameters.board_to_world = nominal_board_to_world;
+
+  Solve(data, &calibration_parameters);
+  LOG(INFO) << "Nominal initial_orientation "
+            << nominal_initial_orientation.coeffs().transpose();
+  LOG(INFO) << "Nominal pivot_to_camera "
+            << nominal_pivot_to_camera.coeffs().transpose();
+
+  LOG(INFO) << "pivot_to_camera delta "
+            << frc971::controls::ToRotationVectorFromQuaternion(
+                   calibration_parameters.pivot_to_camera *
+                   nominal_pivot_to_camera.inverse())
+                   .transpose();
+  LOG(INFO) << "board_to_world delta "
+            << frc971::controls::ToRotationVectorFromQuaternion(
+                   calibration_parameters.board_to_world *
+                   nominal_board_to_world.inverse())
+                   .transpose();
+
+  if (FLAGS_plot) {
+    Plot(data, calibration_parameters);
+  }
+}
+
+}  // namespace vision
+}  // namespace frc971
+
+int main(int argc, char **argv) {
+  aos::InitGoogle(&argc, &argv);
+
+  frc971::vision::Main(argc, argv);
+}