Changes to camera extrinsic calibration to improve accuracy

Adds Outlier Rejection

Do proper rotation (Quaternion) averaging

When camera sees two targets at once, store that, and store
a single observation to match with other cameras.  This leads
to a lot more good connections

Removed dead code, and refactored a couple pieces, e.g., writing extrinsic file

Also refactored some of the utilities to use quaternion averaging from utils,
and move other utility functions to vision_utils_lib

Change-Id: I918ce9c937d80717daa6659abbb139006506d4cc
Signed-off-by: Jim Ostrowski <yimmy13@gmail.com>
diff --git a/y2024/vision/target_mapping.cc b/y2024/vision/target_mapping.cc
index f5fa34c..d9b067a 100644
--- a/y2024/vision/target_mapping.cc
+++ b/y2024/vision/target_mapping.cc
@@ -266,7 +266,7 @@
     }
 
     const TargetMapper::TargetPose target_pose =
-        PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
+        TargetMapper::TargetPoseFromFbs(*target_pose_fbs);
 
     Eigen::Affine3d H_camera_target =
         Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q;