A few more updates to handle pi/orin naming

Change-Id: I82006584955fe291e8fea43c19b1b39997cec1f2
Signed-off-by: Jim Ostrowski <yimmy13@gmail.com>
diff --git a/frc971/vision/intrinsics_calibration_lib.h b/frc971/vision/intrinsics_calibration_lib.h
index 2da33f1..3076ed9 100644
--- a/frc971/vision/intrinsics_calibration_lib.h
+++ b/frc971/vision/intrinsics_calibration_lib.h
@@ -21,7 +21,7 @@
 
 class IntrinsicsCalibration {
  public:
-  IntrinsicsCalibration(aos::EventLoop *event_loop, std::string_view pi,
+  IntrinsicsCalibration(aos::EventLoop *event_loop, std::string_view hostname,
                         std::string_view camera_id,
                         std::string_view base_intrinsics_file,
                         bool display_undistorted,
@@ -39,7 +39,8 @@
 
   static aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
   BuildCalibration(cv::Mat camera_matrix, cv::Mat dist_coeffs,
-                   aos::realtime_clock::time_point realtime_now, int pi_number,
+                   aos::realtime_clock::time_point realtime_now,
+                   std::string_view cpu_type, int cpu_number,
                    std::string_view camera_id, uint16_t team_number);
 
  private:
@@ -49,8 +50,9 @@
   static constexpr double kFrameDeltaRLimit = M_PI / 60;
   static constexpr double kFrameDeltaTLimit = 0.01;
 
-  std::string pi_;
-  const std::optional<uint16_t> pi_number_;
+  std::string hostname_;
+  const std::optional<std::string_view> cpu_type_;
+  const std::optional<uint16_t> cpu_number_;
   const std::string camera_id_;
 
   std::vector<std::vector<int>> all_charuco_ids_;