Updating modify_extrinsics to handle imu

Also, pushing updated  calibration files to match it

Here's the commands I used to create these (for reproducibility / checking)

Front camera (0 pitch, assuming cam-24-05 at orin1/camera0):
front sensor location: X: 11.118, Y: 8.928, Z: 17.439
bazel run -c opt //y2024/vision:modify_extrinsics -- ~/code/FRC/971-Robot-Code/y2024/constants/calib_files/calibration_orin-971-1-1_cam-24-05_1970-01-05_17-40-27.793683328.json --team_number=971 --node_name=orin1 --camera_number=0 --camera_x=11.118 --camera_y=8.928 --camera_z=17.439

Right camera (-15 deg pitch, -90 yaw assuming cam-24-06 at orin1/camera1):
right sensor location: X: 4.372, Y: -10.310, Z: 13.668
bazel run -c opt //y2024/vision:modify_extrinsics -- ~/code/FRC/971-Robot-Code/y2024/constants/calib_files/calibration_orin-971-1-0_cam-24-06_1970-01-05_17-40-29.245444672.json --team_number=971 --node_name=orin1 --camera_number=1 --camera_x=4.372 --camera_y=-10.310 --camera_z=13.668 --camera_pitch=-15 --camera_yaw=-90

Left camera (-15 deg pitch, 90 yaw assuming cam-24-07 at orin1/camera0):
left sensor location: X: 4.372, Y: 10.310, Z: 13.668
bazel run -c opt //y2024/vision:modify_extrinsics -- ~/code/FRC/971-Robot-Code/y2024/constants/calib_files/calibration_orin-971-1-0_cam-24-07_2024-02-24_19-52-27.338466592.json --team_number=971 --node_name=imu --camera_number=0 --camera_x=4.372 --camera_y=10.310 --camera_z=13.668 --camera_pitch=-15 --camera_yaw=90

Rear camera (-15 deg pitch, 1800 yaw assuming cam-24-08 at imu/camera1):
back sensor location: X: -12.652, Y: 10.561, Z: 18.528
bazel run -c opt //y2024/vision:modify_extrinsics -- ~/code/FRC/971-Robot-Code/y2024/constants/calib_files/calibration_orin-971-1-0_cam-24-08_2024-02-24_16-21-54.420797344.json --team_number=971 --node_name=imu --camera_number=1 --camera_x=-12.652 --camera_y=10.561 --camera_z=18.528 --camera_pitch=-15 --camera_yaw=180

Change-Id: I6bcdca25cc15c80dac263c8ea102df9ae125323c
Signed-off-by: Jim Ostrowski <yimmy13@gmail.com>
diff --git a/y2024/constants/971.json b/y2024/constants/971.json
index 38b63d7..dbdc3d9 100644
--- a/y2024/constants/971.json
+++ b/y2024/constants/971.json
@@ -8,16 +8,16 @@
 {
   "cameras": [
     {
-      "calibration": {% include 'y2024/constants/calib_files/calibration_orin-971-1-1_cam-24-05_1970-01-05_17-40-27.793683328.json' %}
+      "calibration": {% include 'y2024/constants/calib_files/calibration_orin1-971-0_cam-24-05_2024-03-01_11-01-05.102438041.json' %}
     },
     {
-      "calibration": {% include 'y2024/constants/calib_files/calibration_orin-971-1-0_cam-24-06_1970-01-05_17-40-29.245444672.json' %}
+      "calibration": {% include 'y2024/constants/calib_files/calibration_orin1-971-1_cam-24-06_2024-03-01_11-01-20.409861949.json' %}
     },
     {
-      "calibration": {% include 'y2024/constants/calib_files/calibration_orin-971-1-0_cam-24-07_2024-02-24_19-52-27.338466592.json' %}
+      "calibration": {% include 'y2024/constants/calib_files/calibration_imu-971-0_cam-24-07_2024-03-01_11-01-32.895328333.json' %}
     },
     {
-      "calibration": {% include 'y2024/constants/calib_files/calibration_orin-971-1-0_cam-24-08_2024-02-24_16-21-54.420797344.json' %}
+      "calibration": {% include 'y2024/constants/calib_files/calibration_imu-971-1_cam-24-08_2024-03-01_11-02-11.982641320.json' %}
     }
   ],
   "robot": {
diff --git a/y2024/constants/calib_files/calibration_imu-971-0_cam-24-07_2024-03-01_11-01-32.895328333.json b/y2024/constants/calib_files/calibration_imu-971-0_cam-24-07_2024-03-01_11-01-32.895328333.json
new file mode 100755
index 0000000..d013e2a
--- /dev/null
+++ b/y2024/constants/calib_files/calibration_imu-971-0_cam-24-07_2024-03-01_11-01-32.895328333.json
@@ -0,0 +1,46 @@
+{
+ "node_name": "imu",
+ "team_number": 971,
+ "intrinsics": [
+  647.822815,
+  0.0,
+  715.37616,
+  0.0,
+  647.799316,
+  494.638641,
+  0.0,
+  0.0,
+  1.0
+ ],
+ "fixed_extrinsics": {
+  "data": [
+   1.0,
+   -0.0,
+   0.0,
+   0.111049,
+   0.0,
+   0.258819,
+   0.965926,
+   0.263806,
+   -0.0,
+   -0.965926,
+   0.258819,
+   0.347685,
+   0.0,
+   0.0,
+   0.0,
+   1.0
+  ]
+ },
+ "dist_coeffs": [
+  -0.2423,
+  0.057169,
+  0.000302,
+  0.000016,
+  -0.005638
+ ],
+ "calibration_timestamp": 1708833147338466592,
+ "camera_id": "24-07",
+ "camera_number": 0,
+ "reprojection_error": 1.362672
+}
\ No newline at end of file
diff --git a/y2024/constants/calib_files/calibration_imu-971-1_cam-24-08_2024-03-01_11-02-11.982641320.json b/y2024/constants/calib_files/calibration_imu-971-1_cam-24-08_2024-03-01_11-02-11.982641320.json
new file mode 100755
index 0000000..fbe79d5
--- /dev/null
+++ b/y2024/constants/calib_files/calibration_imu-971-1_cam-24-08_2024-03-01_11-02-11.982641320.json
@@ -0,0 +1,46 @@
+{
+ "node_name": "imu",
+ "team_number": 971,
+ "intrinsics": [
+  645.963562,
+  0.0,
+  751.21698,
+  0.0,
+  645.34906,
+  605.204102,
+  0.0,
+  0.0,
+  1.0
+ ],
+ "fixed_extrinsics": {
+  "data": [
+   0.0,
+   -0.258819,
+   -0.965926,
+   -0.323293,
+   1.0,
+   0.0,
+   -0.0,
+   0.268249,
+   0.0,
+   -0.965926,
+   0.258819,
+   0.471129,
+   0.0,
+   0.0,
+   0.0,
+   1.0
+  ]
+ },
+ "dist_coeffs": [
+  -0.248733,
+  0.06221,
+  -0.000901,
+  0.000128,
+  -0.006595
+ ],
+ "calibration_timestamp": 1708820514420797344,
+ "camera_id": "24-08",
+ "camera_number": 1,
+ "reprojection_error": 1.591953
+}
\ No newline at end of file
diff --git a/y2024/constants/calib_files/calibration_orin1-971-0_cam-24-05_2024-03-01_11-01-05.102438041.json b/y2024/constants/calib_files/calibration_orin1-971-0_cam-24-05_2024-03-01_11-01-05.102438041.json
new file mode 100755
index 0000000..317e453
--- /dev/null
+++ b/y2024/constants/calib_files/calibration_orin1-971-0_cam-24-05_2024-03-01_11-01-05.102438041.json
@@ -0,0 +1,46 @@
+{
+ "node_name": "orin1",
+ "team_number": 971,
+ "intrinsics": [
+  648.360168,
+  0.0,
+  729.818665,
+  0.0,
+  648.210327,
+  641.988037,
+  0.0,
+  0.0,
+  1.0
+ ],
+ "fixed_extrinsics": {
+  "data": [
+   0.0,
+   0.0,
+   1.0,
+   0.284397,
+   -1.0,
+   0.0,
+   0.0,
+   0.226771,
+   0.0,
+   -1.0,
+   0.0,
+   0.442951,
+   0.0,
+   0.0,
+   0.0,
+   1.0
+  ]
+ },
+ "dist_coeffs": [
+  -0.255473,
+  0.068444,
+  0.000028,
+  -0.000078,
+  -0.008004
+ ],
+ "calibration_timestamp": 409227793683328,
+ "camera_id": "24-05",
+ "camera_number": 0,
+ "reprojection_error": 1.058851
+}
\ No newline at end of file
diff --git a/y2024/constants/calib_files/calibration_orin1-971-1_cam-24-06_2024-03-01_11-01-20.409861949.json b/y2024/constants/calib_files/calibration_orin1-971-1_cam-24-06_2024-03-01_11-01-20.409861949.json
new file mode 100755
index 0000000..0eb10db
--- /dev/null
+++ b/y2024/constants/calib_files/calibration_orin1-971-1_cam-24-06_2024-03-01_11-01-20.409861949.json
@@ -0,0 +1,46 @@
+{
+ "node_name": "orin1",
+ "team_number": 971,
+ "intrinsics": [
+  648.644104,
+  0.0,
+  755.677979,
+  0.0,
+  648.522644,
+  597.744812,
+  0.0,
+  0.0,
+  1.0
+ ],
+ "fixed_extrinsics": {
+  "data": [
+   -1.0,
+   0.0,
+   0.0,
+   0.111049,
+   -0.0,
+   -0.258819,
+   -0.965926,
+   -0.263806,
+   0.0,
+   -0.965926,
+   0.258819,
+   0.347685,
+   0.0,
+   0.0,
+   0.0,
+   1.0
+  ]
+ },
+ "dist_coeffs": [
+  -0.25182,
+  0.063137,
+  0.000118,
+  0.000005,
+  -0.006342
+ ],
+ "calibration_timestamp": 409229245444672,
+ "camera_id": "24-06",
+ "camera_number": 1,
+ "reprojection_error": 1.344104
+}
\ No newline at end of file
diff --git a/y2024/vision/modify_extrinsics.cc b/y2024/vision/modify_extrinsics.cc
index fc1d348..9122191 100644
--- a/y2024/vision/modify_extrinsics.cc
+++ b/y2024/vision/modify_extrinsics.cc
@@ -26,7 +26,8 @@
               "Intrinsics to use for estimating board pose prior to solving "
               "for the new intrinsics.");
 DEFINE_string(calibration_folder, "/tmp", "Folder to place calibration files.");
-DEFINE_int32(orin_number, -1, "Orin number to use; unchanged if -1");
+DEFINE_string(node_name, "",
+              "Node name to use, e.g. orin1, imu; unchanged if blank");
 DEFINE_int32(team_number, -1, "Team number to use; unchanged if -1");
 DEFINE_int32(camera_number, -1, "Camera number to use; unchanged if -1");
 
@@ -134,19 +135,9 @@
               orig_calib_filename);
 
   // Populate the new variables from command-line or from base_calibration
-  CHECK(base_calibration.message().node_name()->str().find("orin") == 0)
-      << "This code is only available for calibrations on the orin (2024+)";
-  int cpu_number =
-      (FLAGS_orin_number == -1 ? std::atoi(base_calibration.message()
-                                               .node_name()
-                                               ->str()
-                                               .substr(4, 1)
-                                               .c_str())
-                               : FLAGS_orin_number);
   std::string node_name =
-      (FLAGS_orin_number == -1
-           ? base_calibration.message().node_name()->str()
-           : std::string("orin") + std::to_string(FLAGS_orin_number));
+      (FLAGS_node_name == "" ? base_calibration.message().node_name()->str()
+                             : FLAGS_node_name);
   int team_number =
       (FLAGS_team_number == -1 ? base_calibration.message().team_number()
                                : FLAGS_team_number);
@@ -171,8 +162,8 @@
            : FLAGS_calibration_folder);
   const std::string new_calib_filename =
       dirname + "/" +
-      absl::StrFormat("calibration_orin-%d-%d-%d_cam-%s_%s.json", team_number,
-                      cpu_number, camera_number, camera_id.c_str(),
+      absl::StrFormat("calibration_%s-%d-%d_cam-%s_%s.json", node_name.c_str(),
+                      team_number, camera_number, camera_id.c_str(),
                       time_ss.str());
 
   VLOG(1) << "From: " << orig_calib_filename << " -> "