Add field for image channel in charuco lib

Allows us to easily send it to /camera/decimated for mapping, which is
what we're using until we start logging at full frequency.

Also, move some command line flags out of charuco lib to avoid manually setting flags.

Signed-off-by: Milind Upadhyay <milind.upadhyay@gmail.com>
Change-Id: Iae4d9ed06260154a0fb4d4c67ea03b06a28e4411
diff --git a/frc971/vision/calibration_accumulator.cc b/frc971/vision/calibration_accumulator.cc
index f1ab4fc..eee22f5 100644
--- a/frc971/vision/calibration_accumulator.cc
+++ b/frc971/vision/calibration_accumulator.cc
@@ -114,6 +114,7 @@
 Calibration::Calibration(aos::SimulatedEventLoopFactory *event_loop_factory,
                          aos::EventLoop *image_event_loop,
                          aos::EventLoop *imu_event_loop, std::string_view pi,
+                         TargetType target_type, std::string_view image_channel,
                          CalibrationData *data)
     : image_event_loop_(image_event_loop),
       image_factory_(event_loop_factory->GetNodeEventLoopFactory(
@@ -122,7 +123,7 @@
       imu_factory_(
           event_loop_factory->GetNodeEventLoopFactory(imu_event_loop_->node())),
       charuco_extractor_(
-          image_event_loop_, pi,
+          image_event_loop_, pi, target_type, image_channel,
           [this](cv::Mat rgb_image, monotonic_clock::time_point eof,
                  std::vector<cv::Vec4i> charuco_ids,
                  std::vector<std::vector<cv::Point2f>> charuco_corners,
@@ -135,7 +136,7 @@
           image_event_loop_,
           absl::StrCat("/pi",
                        std::to_string(aos::network::ParsePiNumber(pi).value()),
-                       "/camera"),
+                       image_channel),
           [this](cv::Mat rgb_image, const monotonic_clock::time_point eof) {
             charuco_extractor_.HandleImage(rgb_image, eof);
           }),