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/y2023/vision/april_detection_test.cc b/y2023/vision/april_detection_test.cc
index 9f4f8b7..7e50b09 100644
--- a/y2023/vision/april_detection_test.cc
+++ b/y2023/vision/april_detection_test.cc
@@ -11,6 +11,7 @@
 #include "frc971/constants/constants_sender_lib.h"
 #include "frc971/vision/target_mapper.h"
 #include "frc971/vision/vision_generated.h"
+#include "frc971/vision/vision_util_lib.h"
 #include "y2023/constants/constants_generated.h"
 #include "y2023/constants/constants_list_generated.h"
 #include "y2023/vision/aprilrobotics.h"
@@ -61,7 +62,7 @@
     ASSERT_EQ(april_pose_fetcher_->target_poses()->size(), 1);
 
     frc971::vision::TargetMapper::TargetPose target_pose =
-        frc971::vision::PoseUtils::TargetPoseFromFbs(
+        frc971::vision::TargetMapper::TargetPoseFromFbs(
             *april_pose_fetcher_->target_poses()->Get(0));
 
     ASSERT_EQ(april_pose_fetcher_->target_poses()->Get(0)->id(), 8);