Move over to ABSL logging and flags.

Removes gperftools too since that wants gflags.

Here come the fireworks.

Change-Id: I79cb7bcf60f1047fbfa28bfffc21a0fd692e4b1c
Signed-off-by: Austin Schuh <austin.linux@gmail.com>
diff --git a/y2022/vision/ball_color.cc b/y2022/vision/ball_color.cc
index 930142f..17db26e 100644
--- a/y2022/vision/ball_color.cc
+++ b/y2022/vision/ball_color.cc
@@ -4,7 +4,8 @@
 #include <cmath>
 #include <thread>
 
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
 #include "opencv2/imgproc.hpp"
 #include <opencv2/highgui/highgui.hpp>
 
diff --git a/y2022/vision/ball_color_main.cc b/y2022/vision/ball_color_main.cc
index 5f05b34..67d7711 100644
--- a/y2022/vision/ball_color_main.cc
+++ b/y2022/vision/ball_color_main.cc
@@ -1,3 +1,5 @@
+#include "absl/flags/flag.h"
+
 #include "aos/events/shm_event_loop.h"
 #include "aos/init.h"
 #include "y2022/constants.h"
@@ -7,7 +9,8 @@
 // bazel run //y2022/vision:ball_color_detector -- --config
 // y2022/aos_config.json
 //   --override_hostname pi-7971-1  --ignore_timestamps true
-DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
+ABSL_FLAG(std::string, config, "aos_config.json",
+          "Path to the config file to use.");
 
 namespace y2022::vision {
 namespace {
@@ -16,7 +19,7 @@
 
 void BallColorDetectorMain() {
   aos::FlatbufferDetachedBuffer<aos::Configuration> config =
-      aos::configuration::ReadConfig(FLAGS_config);
+      aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
 
   aos::ShmEventLoop event_loop(&config.message());
   std::shared_ptr<const constants::Values> values =
diff --git a/y2022/vision/ball_color_test.cc b/y2022/vision/ball_color_test.cc
index 96f59aa..6f018d1 100644
--- a/y2022/vision/ball_color_test.cc
+++ b/y2022/vision/ball_color_test.cc
@@ -2,7 +2,7 @@
 
 #include <cmath>
 
-#include "glog/logging.h"
+#include "absl/log/check.h"
 #include "gtest/gtest.h"
 #include <opencv2/highgui/highgui.hpp>
 #include <opencv2/imgproc.hpp>
@@ -12,9 +12,6 @@
 #include "aos/testing/test_logging.h"
 #include "y2022/constants.h"
 
-DEFINE_string(output_folder, "",
-              "If set, logs all channels to the provided logfile.");
-
 namespace y2022::vision::testing {
 
 class BallColorTest : public ::testing::Test {
diff --git a/y2022/vision/blob_detector.cc b/y2022/vision/blob_detector.cc
index 70ff1b2..887960d 100644
--- a/y2022/vision/blob_detector.cc
+++ b/y2022/vision/blob_detector.cc
@@ -4,6 +4,7 @@
 #include <optional>
 #include <string>
 
+#include "absl/flags/flag.h"
 #include "opencv2/features2d.hpp"
 #include "opencv2/highgui/highgui.hpp"
 #include "opencv2/imgproc.hpp"
@@ -12,28 +13,30 @@
 #include "aos/time/time.h"
 #include "frc971/vision/geometry.h"
 
-DEFINE_bool(
-    use_outdoors, true,
-    "If set, use the color filters and exposure for an outdoor setting.");
-DEFINE_int32(red_delta, 50, "Required difference between green pixels vs. red");
-DEFINE_int32(blue_delta, -20,
-             "Required difference between green pixels vs. blue");
-DEFINE_int32(outdoors_red_delta, 70,
-             "Required difference between green pixels vs. red when using "
-             "--use_outdoors");
-DEFINE_int32(outdoors_blue_delta, -10,
-             "Required difference between green pixels vs. blue when using "
-             "--use_outdoors");
+ABSL_FLAG(bool, use_outdoors, true,
+          "If set, use the color filters and exposure for an outdoor setting.");
+ABSL_FLAG(int32_t, red_delta, 50,
+          "Required difference between green pixels vs. red");
+ABSL_FLAG(int32_t, blue_delta, -20,
+          "Required difference between green pixels vs. blue");
+ABSL_FLAG(int32_t, outdoors_red_delta, 70,
+          "Required difference between green pixels vs. red when using "
+          "--use_outdoors");
+ABSL_FLAG(int32_t, outdoors_blue_delta, -10,
+          "Required difference between green pixels vs. blue when using "
+          "--use_outdoors");
 
 namespace y2022::vision {
 
 cv::Mat BlobDetector::ThresholdImage(cv::Mat bgr_image) {
   cv::Mat binarized_image(cv::Size(bgr_image.cols, bgr_image.rows), CV_8UC1);
 
-  const int red_delta =
-      (FLAGS_use_outdoors ? FLAGS_outdoors_red_delta : FLAGS_red_delta);
-  const int blue_delta =
-      (FLAGS_use_outdoors ? FLAGS_outdoors_blue_delta : FLAGS_blue_delta);
+  const int red_delta = (absl::GetFlag(FLAGS_use_outdoors)
+                             ? absl::GetFlag(FLAGS_outdoors_red_delta)
+                             : absl::GetFlag(FLAGS_red_delta));
+  const int blue_delta = (absl::GetFlag(FLAGS_use_outdoors)
+                              ? absl::GetFlag(FLAGS_outdoors_blue_delta)
+                              : absl::GetFlag(FLAGS_blue_delta));
 
   for (int row = 0; row < bgr_image.rows; row++) {
     for (int col = 0; col < bgr_image.cols; col++) {
diff --git a/y2022/vision/calibrate_extrinsics.cc b/y2022/vision/calibrate_extrinsics.cc
index 7b53d67..3388853 100644
--- a/y2022/vision/calibrate_extrinsics.cc
+++ b/y2022/vision/calibrate_extrinsics.cc
@@ -1,5 +1,6 @@
 #include "Eigen/Dense"
 #include "Eigen/Geometry"
+#include "absl/flags/flag.h"
 #include "absl/strings/str_format.h"
 
 #include "aos/events/logging/log_reader.h"
@@ -14,16 +15,17 @@
 #include "frc971/wpilib/imu_batch_generated.h"
 #include "y2022/control_loops/superstructure/superstructure_status_generated.h"
 
-DEFINE_string(pi, "pi-7971-2", "Pi name to calibrate.");
-DEFINE_bool(plot, false, "Whether to plot the resulting data.");
-DEFINE_bool(turret, true, "If true, the camera is on the turret");
-DEFINE_string(target_type, "charuco",
-              "Type of target: aruco|charuco|charuco_diamond");
-DEFINE_string(image_channel, "/camera", "Channel to listen for images on");
-DEFINE_string(output_logs, "/tmp/calibration/",
-              "Output folder for visualization logs.");
-DEFINE_string(base_intrinsics, "",
-              "Intrinsics to use for extrinsics calibration.");
+ABSL_FLAG(std::string, pi, "pi-7971-2", "Pi name to calibrate.");
+ABSL_FLAG(bool, plot, false, "Whether to plot the resulting data.");
+ABSL_FLAG(bool, turret, true, "If true, the camera is on the turret");
+ABSL_FLAG(std::string, target_type, "charuco",
+          "Type of target: aruco|charuco|charuco_diamond");
+ABSL_FLAG(std::string, image_channel, "/camera",
+          "Channel to listen for images on");
+ABSL_FLAG(std::string, output_logs, "/tmp/calibration/",
+          "Output folder for visualization logs.");
+ABSL_FLAG(std::string, base_intrinsics, "",
+          "Intrinsics to use for extrinsics calibration.");
 
 namespace frc971::vision {
 namespace chrono = std::chrono;
@@ -36,7 +38,7 @@
 void Main(int argc, char **argv) {
   CalibrationData data;
   std::optional<uint16_t> pi_number =
-      aos::network::ParsePiOrOrinNumber(FLAGS_pi);
+      aos::network::ParsePiOrOrinNumber(absl::GetFlag(FLAGS_pi));
   CHECK(pi_number);
   const std::string pi_name = absl::StrCat("pi", *pi_number);
   LOG(INFO) << "Pi " << *pi_number;
@@ -83,29 +85,30 @@
     std::unique_ptr<aos::EventLoop> logger_loop =
         factory.MakeEventLoop("logger", pi_node);
     aos::logger::Logger logger(logger_loop.get());
-    logger.StartLoggingOnRun(FLAGS_output_logs);
+    logger.StartLoggingOnRun(absl::GetFlag(FLAGS_output_logs));
 
     TargetType target_type = TargetType::kCharuco;
-    if (FLAGS_target_type == "aruco") {
+    if (absl::GetFlag(FLAGS_target_type) == "aruco") {
       target_type = TargetType::kAruco;
-    } else if (FLAGS_target_type == "charuco") {
+    } else if (absl::GetFlag(FLAGS_target_type) == "charuco") {
       target_type = TargetType::kCharuco;
-    } else if (FLAGS_target_type == "charuco_diamond") {
+    } else if (absl::GetFlag(FLAGS_target_type) == "charuco_diamond") {
       target_type = TargetType::kCharucoDiamond;
     } else {
-      LOG(FATAL) << "Unknown target type: " << FLAGS_target_type
+      LOG(FATAL) << "Unknown target type: " << absl::GetFlag(FLAGS_target_type)
                  << ", expected: aruco|charuco|charuco_diamond";
     }
 
     aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> intrinsics =
         aos::JsonFileToFlatbuffer<calibration::CameraCalibration>(
-            FLAGS_base_intrinsics);
+            absl::GetFlag(FLAGS_base_intrinsics));
     // Now, hook Calibration up to everything.
     Calibration extractor(&factory, pi_event_loop.get(), imu_event_loop.get(),
-                          FLAGS_pi, &intrinsics.message(), target_type,
-                          FLAGS_image_channel, &data);
+                          absl::GetFlag(FLAGS_pi), &intrinsics.message(),
+                          target_type, absl::GetFlag(FLAGS_image_channel),
+                          &data);
 
-    if (FLAGS_turret) {
+    if (absl::GetFlag(FLAGS_turret)) {
       aos::NodeEventLoopFactory *roborio_factory =
           factory.GetNodeEventLoopFactory(roborio_node->name()->string_view());
       roborio_event_loop->MakeWatcher(
@@ -253,12 +256,12 @@
                    nominal_board_to_world.inverse())
                    .transpose();
 
-  if (FLAGS_visualize) {
+  if (absl::GetFlag(FLAGS_visualize)) {
     LOG(INFO) << "Showing visualization";
     Visualize(data, calibration_parameters);
   }
 
-  if (FLAGS_plot) {
+  if (absl::GetFlag(FLAGS_plot)) {
     Plot(data, calibration_parameters);
   }
 }  // namespace vision
diff --git a/y2022/vision/camera_reader.cc b/y2022/vision/camera_reader.cc
index a077d09..b3e24a8 100644
--- a/y2022/vision/camera_reader.cc
+++ b/y2022/vision/camera_reader.cc
@@ -4,6 +4,7 @@
 #include <cmath>
 #include <thread>
 
+#include "absl/flags/flag.h"
 #include "opencv2/imgproc.hpp"
 
 #include "aos/events/event_loop.h"
@@ -15,7 +16,7 @@
 #include "frc971/vision/vision_generated.h"
 #include "y2022/vision/blob_detector.h"
 
-DEFINE_string(image_png, "", "A set of PNG images");
+ABSL_FLAG(std::string, image_png, "", "A set of PNG images");
 
 namespace y2022::vision {
 
@@ -145,9 +146,9 @@
 
 void CameraReader::ReadImage() {
   // Path is for reading from the Disk.
-  if (FLAGS_image_png != "") {
+  if (absl::GetFlag(FLAGS_image_png) != "") {
     std::vector<cv::String> file_list;
-    cv::glob(FLAGS_image_png + "/*.png", file_list, false);
+    cv::glob(absl::GetFlag(FLAGS_image_png) + "/*.png", file_list, false);
     for (auto file : file_list) {
       // Sleep for 0.05 seconds in order to not reach the max number of messages
       // that can be sent in a second.
diff --git a/y2022/vision/camera_reader_main.cc b/y2022/vision/camera_reader_main.cc
index 278f14b..80b19d2 100644
--- a/y2022/vision/camera_reader_main.cc
+++ b/y2022/vision/camera_reader_main.cc
@@ -1,3 +1,5 @@
+#include "absl/flags/flag.h"
+
 #include "aos/events/shm_event_loop.h"
 #include "aos/init.h"
 #include "y2022/vision/camera_reader.h"
@@ -5,14 +7,15 @@
 // config used to allow running camera_reader independently.  E.g.,
 // bazel run //y2022/vision:camera_reader -- --config y2022/aos_config.json
 //   --override_hostname pi-7971-1  --ignore_timestamps true
-DECLARE_bool(use_outdoors);
-DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
-DEFINE_double(duty_cycle, 0.65, "Duty cycle of the LEDs");
-DEFINE_uint32(exposure, 3,
-              "Exposure time, in 100us increments; 0 implies auto exposure");
-DEFINE_uint32(outdoors_exposure, 2,
-              "Exposure time when using --use_outdoors, in 100us increments; 0 "
-              "implies auto exposure");
+ABSL_DECLARE_FLAG(bool, use_outdoors);
+ABSL_FLAG(std::string, config, "aos_config.json",
+          "Path to the config file to use.");
+ABSL_FLAG(double, duty_cycle, 0.65, "Duty cycle of the LEDs");
+ABSL_FLAG(uint32_t, exposure, 3,
+          "Exposure time, in 100us increments; 0 implies auto exposure");
+ABSL_FLAG(uint32_t, outdoors_exposure, 2,
+          "Exposure time when using --use_outdoors, in 100us increments; 0 "
+          "implies auto exposure");
 
 namespace y2022::vision {
 namespace {
@@ -21,7 +24,7 @@
 
 void CameraReaderMain() {
   aos::FlatbufferDetachedBuffer<aos::Configuration> config =
-      aos::configuration::ReadConfig(FLAGS_config);
+      aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
 
   const aos::FlatbufferSpan<calibration::CalibrationData> calibration_data(
       CalibrationData());
@@ -38,8 +41,9 @@
   }
 
   V4L2Reader v4l2_reader(&event_loop, "/dev/video0");
-  const uint32_t exposure =
-      (FLAGS_use_outdoors ? FLAGS_outdoors_exposure : FLAGS_exposure);
+  const uint32_t exposure = (absl::GetFlag(FLAGS_use_outdoors)
+                                 ? absl::GetFlag(FLAGS_outdoors_exposure)
+                                 : absl::GetFlag(FLAGS_exposure));
   if (exposure > 0) {
     LOG(INFO) << "Setting camera to Manual Exposure mode with exposure = "
               << exposure << " or " << static_cast<double>(exposure) / 10.0
@@ -52,7 +56,7 @@
 
   CameraReader camera_reader(&event_loop, &calibration_data.message(),
                              &v4l2_reader);
-  camera_reader.SetDutyCycle(FLAGS_duty_cycle);
+  camera_reader.SetDutyCycle(absl::GetFlag(FLAGS_duty_cycle));
 
   event_loop.Run();
 }
diff --git a/y2022/vision/image_decimator.cc b/y2022/vision/image_decimator.cc
index e83659d..7a5d7de 100644
--- a/y2022/vision/image_decimator.cc
+++ b/y2022/vision/image_decimator.cc
@@ -1,9 +1,12 @@
+#include "absl/flags/flag.h"
+
 #include "aos/events/shm_event_loop.h"
 #include "aos/flatbuffers.h"
 #include "aos/init.h"
 #include "frc971/vision/vision_generated.h"
 
-DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
+ABSL_FLAG(std::string, config, "aos_config.json",
+          "Path to the config file to use.");
 
 namespace frc971::vision {
 // Reads images from /camera and resends them in /camera/decimated at a fixed
@@ -38,7 +41,7 @@
   aos::InitGoogle(&argc, &argv);
 
   aos::FlatbufferDetachedBuffer<aos::Configuration> config =
-      aos::configuration::ReadConfig(FLAGS_config);
+      aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
 
   aos::ShmEventLoop event_loop(&config.message());
   frc971::vision::ImageDecimator decimator(&event_loop);
diff --git a/y2022/vision/target_estimator.cc b/y2022/vision/target_estimator.cc
index ff72b11..ecff719 100644
--- a/y2022/vision/target_estimator.cc
+++ b/y2022/vision/target_estimator.cc
@@ -1,5 +1,6 @@
 #include "y2022/vision/target_estimator.h"
 
+#include "absl/flags/flag.h"
 #include "absl/strings/str_format.h"
 #include "ceres/ceres.h"
 #include "opencv2/core/core.hpp"
@@ -13,20 +14,20 @@
 #include "frc971/vision/geometry.h"
 #include "y2022/constants.h"
 
-DEFINE_bool(freeze_roll, false, "If true, don't solve for roll");
-DEFINE_bool(freeze_pitch, false, "If true, don't solve for pitch");
-DEFINE_bool(freeze_yaw, false, "If true, don't solve for yaw");
-DEFINE_bool(freeze_camera_height, true,
-            "If true, don't solve for camera height");
-DEFINE_bool(freeze_angle_to_camera, true,
-            "If true, don't solve for polar angle to camera");
+ABSL_FLAG(bool, freeze_roll, false, "If true, don't solve for roll");
+ABSL_FLAG(bool, freeze_pitch, false, "If true, don't solve for pitch");
+ABSL_FLAG(bool, freeze_yaw, false, "If true, don't solve for yaw");
+ABSL_FLAG(bool, freeze_camera_height, true,
+          "If true, don't solve for camera height");
+ABSL_FLAG(bool, freeze_angle_to_camera, true,
+          "If true, don't solve for polar angle to camera");
 
-DEFINE_uint64(max_solver_iterations, 200,
-              "Maximum number of iterations for the ceres solver");
-DEFINE_bool(solver_output, false,
-            "If true, log the solver progress and results");
-DEFINE_bool(draw_projected_hub, true,
-            "If true, draw the projected hub when drawing an estimate");
+ABSL_FLAG(uint64_t, max_solver_iterations, 200,
+          "Maximum number of iterations for the ceres solver");
+ABSL_FLAG(bool, solver_output, false,
+          "If true, log the solver progress and results");
+ABSL_FLAG(bool, draw_projected_hub, true,
+          "If true, draw the projected hub when drawing an estimate");
 
 namespace y2022::vision {
 
@@ -231,26 +232,28 @@
 
   // Constrain the rotation to be around the localizer's, otherwise there can be
   // multiple solutions. There shouldn't be too much roll or pitch
-  if (FLAGS_freeze_roll) {
+  if (absl::GetFlag(FLAGS_freeze_roll)) {
     roll_ = roll_seed;
   }
   constexpr double kMaxRollDelta = 0.1;
-  SetBoundsOrFreeze(&roll_, FLAGS_freeze_roll, roll_seed - kMaxRollDelta,
-                    roll_seed + kMaxRollDelta, &problem);
+  SetBoundsOrFreeze(&roll_, absl::GetFlag(FLAGS_freeze_roll),
+                    roll_seed - kMaxRollDelta, roll_seed + kMaxRollDelta,
+                    &problem);
 
-  if (FLAGS_freeze_pitch) {
+  if (absl::GetFlag(FLAGS_freeze_pitch)) {
     pitch_ = pitch_seed;
   }
   constexpr double kMaxPitchDelta = 0.15;
-  SetBoundsOrFreeze(&pitch_, FLAGS_freeze_pitch, pitch_seed - kMaxPitchDelta,
-                    pitch_seed + kMaxPitchDelta, &problem);
+  SetBoundsOrFreeze(&pitch_, absl::GetFlag(FLAGS_freeze_pitch),
+                    pitch_seed - kMaxPitchDelta, pitch_seed + kMaxPitchDelta,
+                    &problem);
   // Constrain the yaw to where the target would be visible
   constexpr double kMaxYawDelta = M_PI / 4.0;
-  SetBoundsOrFreeze(&yaw_, FLAGS_freeze_yaw, M_PI - kMaxYawDelta,
+  SetBoundsOrFreeze(&yaw_, absl::GetFlag(FLAGS_freeze_yaw), M_PI - kMaxYawDelta,
                     M_PI + kMaxYawDelta, &problem);
 
   constexpr double kMaxHeightDelta = 0.1;
-  SetBoundsOrFreeze(&camera_height_, FLAGS_freeze_camera_height,
+  SetBoundsOrFreeze(&camera_height_, absl::GetFlag(FLAGS_freeze_camera_height),
                     camera_height_ - kMaxHeightDelta,
                     camera_height_ + kMaxHeightDelta, &problem);
 
@@ -261,15 +264,16 @@
 
   // Keep the angle between +/- half of the angle between piece of tape
   constexpr double kMaxAngle = ((2.0 * M_PI) / kNumPiecesOfTape) / 2.0;
-  SetBoundsOrFreeze(&angle_to_camera_, FLAGS_freeze_angle_to_camera, -kMaxAngle,
+  SetBoundsOrFreeze(&angle_to_camera_,
+                    absl::GetFlag(FLAGS_freeze_angle_to_camera), -kMaxAngle,
                     kMaxAngle, &problem);
 
   ceres::Solver::Options options;
-  options.minimizer_progress_to_stdout = FLAGS_solver_output;
+  options.minimizer_progress_to_stdout = absl::GetFlag(FLAGS_solver_output);
   options.gradient_tolerance = 1e-12;
   options.function_tolerance = 1e-16;
   options.parameter_tolerance = 1e-12;
-  options.max_num_iterations = FLAGS_max_solver_iterations;
+  options.max_num_iterations = absl::GetFlag(FLAGS_max_solver_iterations);
   ceres::Solver::Summary summary;
   ceres::Solve(options, &problem, &summary);
 
@@ -302,7 +306,7 @@
       kSigmoidCapacity /
       (1.0 + kSigmoidScalar * std::exp(-kSigmoidGrowthRate * std_dev));
 
-  if (FLAGS_solver_output) {
+  if (absl::GetFlag(FLAGS_solver_output)) {
     LOG(INFO) << summary.FullReport();
 
     LOG(INFO) << "roll: " << roll_;
@@ -608,7 +612,7 @@
 }
 
 void TargetEstimator::DrawEstimate(cv::Mat view_image) const {
-  if (FLAGS_draw_projected_hub) {
+  if (absl::GetFlag(FLAGS_draw_projected_hub)) {
     // Draw projected hub
     const auto H_hub_camera = ComputeHubCameraTransform(
         roll_, pitch_, yaw_, distance_, angle_to_camera_, camera_height_);
diff --git a/y2022/vision/viewer.cc b/y2022/vision/viewer.cc
index b0bcdac..7638a4c 100644
--- a/y2022/vision/viewer.cc
+++ b/y2022/vision/viewer.cc
@@ -2,6 +2,7 @@
 #include <map>
 #include <random>
 
+#include "absl/flags/flag.h"
 #include "absl/strings/str_format.h"
 #include <opencv2/calib3d.hpp>
 #include <opencv2/features2d.hpp>
@@ -18,23 +19,25 @@
 #include "y2022/vision/target_estimate_generated.h"
 #include "y2022/vision/target_estimator.h"
 
-DEFINE_string(capture, "",
-              "If set, capture a single image and save it to this filename.");
-DEFINE_string(channel, "/camera", "Channel name for the image.");
-DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
-DEFINE_string(png_dir, "", "Path to a set of images to display.");
-DEFINE_string(png_pattern, "*", R"(Pattern to match pngs using '*'/'?'.)");
-DEFINE_string(calibration_node, "",
-              "If reading locally, use the calibration for this node");
-DEFINE_int32(
-    calibration_team_number, 971,
+ABSL_FLAG(std::string, capture, "",
+          "If set, capture a single image and save it to this filename.");
+ABSL_FLAG(std::string, channel, "/camera", "Channel name for the image.");
+ABSL_FLAG(std::string, config, "aos_config.json",
+          "Path to the config file to use.");
+ABSL_FLAG(std::string, png_dir, "", "Path to a set of images to display.");
+ABSL_FLAG(std::string, png_pattern, "*",
+          R"(Pattern to match pngs using '*'/'?'.)");
+ABSL_FLAG(std::string, calibration_node, "",
+          "If reading locally, use the calibration for this node");
+ABSL_FLAG(
+    int32_t, calibration_team_number, 971,
     "If reading locally, use the calibration for a node with this team number");
-DEFINE_uint64(skip, 0,
-              "Number of images to skip if doing local reading (png_dir set).");
-DEFINE_bool(show_features, true, "Show the blobs.");
-DEFINE_bool(display_estimation, false,
-            "If true, display the target estimation graphically");
-DEFINE_bool(sort_by_time, true, "If true, sort the images by time");
+ABSL_FLAG(uint64_t, skip, 0,
+          "Number of images to skip if doing local reading (png_dir set).");
+ABSL_FLAG(bool, show_features, true, "Show the blobs.");
+ABSL_FLAG(bool, display_estimation, false,
+          "If true, display the target estimation graphically");
+ABSL_FLAG(bool, sort_by_time, true, "If true, sort the images by time");
 
 namespace y2022::vision {
 namespace {
@@ -121,8 +124,8 @@
   cv::Mat bgr_image(cv::Size(image->cols(), image->rows()), CV_8UC3);
   cv::cvtColor(image_color_mat, bgr_image, cv::COLOR_YUV2BGR_YUYV);
 
-  if (!FLAGS_capture.empty()) {
-    cv::imwrite(FLAGS_capture, bgr_image);
+  if (!absl::GetFlag(FLAGS_capture).empty()) {
+    cv::imwrite(absl::GetFlag(FLAGS_capture), bgr_image);
     return false;
   }
 
@@ -157,15 +160,16 @@
 
 void ViewerMain() {
   aos::FlatbufferDetachedBuffer<aos::Configuration> config =
-      aos::configuration::ReadConfig(FLAGS_config);
+      aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
 
   aos::ShmEventLoop event_loop(&config.message());
 
-  image_fetcher =
-      event_loop.MakeFetcher<frc971::vision::CameraImage>(FLAGS_channel);
+  image_fetcher = event_loop.MakeFetcher<frc971::vision::CameraImage>(
+      absl::GetFlag(FLAGS_channel));
 
   target_estimate_fetcher =
-      event_loop.MakeFetcher<y2022::vision::TargetEstimate>(FLAGS_channel);
+      event_loop.MakeFetcher<y2022::vision::TargetEstimate>(
+          absl::GetFlag(FLAGS_channel));
 
   // Run the display loop
   event_loop.AddPhasedLoop(
@@ -199,11 +203,12 @@
 
 void ViewerLocal() {
   std::vector<cv::String> file_list;
-  cv::glob(absl::StrFormat("%s/%s.png", FLAGS_png_dir, FLAGS_png_pattern),
+  cv::glob(absl::StrFormat("%s/%s.png", absl::GetFlag(FLAGS_png_dir),
+                           absl::GetFlag(FLAGS_png_pattern)),
            file_list, false);
 
   // Sort the images by timestamp
-  if (FLAGS_sort_by_time) {
+  if (absl::GetFlag(FLAGS_sort_by_time)) {
     std::sort(file_list.begin(), file_list.end(),
               [](std::string_view filename_1, std::string_view filename_2) {
                 return (FindImageTimestamp(filename_1) <
@@ -215,9 +220,9 @@
       CalibrationData());
 
   const calibration::CameraCalibration *calibration =
-      CameraReader::FindCameraCalibration(&calibration_data.message(),
-                                          FLAGS_calibration_node,
-                                          FLAGS_calibration_team_number);
+      CameraReader::FindCameraCalibration(
+          &calibration_data.message(), absl::GetFlag(FLAGS_calibration_node),
+          absl::GetFlag(FLAGS_calibration_team_number));
   const auto intrinsics = CameraReader::CameraIntrinsics(calibration);
   const auto extrinsics = CameraReader::CameraExtrinsics(calibration);
   const auto dist_coeffs = CameraReader::CameraDistCoeffs(calibration);
@@ -228,7 +233,8 @@
 
   TargetEstimator estimator(intrinsics, extrinsics);
 
-  for (auto it = file_list.begin() + FLAGS_skip; it < file_list.end(); it++) {
+  for (auto it = file_list.begin() + absl::GetFlag(FLAGS_skip);
+       it < file_list.end(); it++) {
     LOG(INFO) << "Reading file " << (it - file_list.begin()) << ": " << *it;
     cv::Mat image_mat =
         CameraReader::UndistortImage(cv::imread(it->c_str()), undistort_maps);
@@ -249,8 +255,9 @@
               << ")";
 
     estimator.Solve(blob_result.filtered_stats,
-                    FLAGS_display_estimation ? std::make_optional(ret_image)
-                                             : std::nullopt);
+                    absl::GetFlag(FLAGS_display_estimation)
+                        ? std::make_optional(ret_image)
+                        : std::nullopt);
     if (blob_result.filtered_blobs.size() > 0) {
       estimator.DrawEstimate(ret_image);
       LOG(INFO) << "Read file " << (it - file_list.begin()) << ": " << *it;
@@ -277,7 +284,7 @@
 // Quick and lightweight viewer for images
 int main(int argc, char **argv) {
   aos::InitGoogle(&argc, &argv);
-  if (FLAGS_png_dir != "")
+  if (absl::GetFlag(FLAGS_png_dir) != "")
     y2022::vision::ViewerLocal();
   else
     y2022::vision::ViewerMain();
diff --git a/y2022/vision/viewer_replay.cc b/y2022/vision/viewer_replay.cc
index 15427e4..1df3363 100644
--- a/y2022/vision/viewer_replay.cc
+++ b/y2022/vision/viewer_replay.cc
@@ -12,19 +12,20 @@
 #include "y2022/control_loops/superstructure/superstructure_status_generated.h"
 #include "y2022/vision/blob_detector.h"
 
-DEFINE_string(pi, "pi3", "Node name to replay.");
-DEFINE_string(image_save_prefix, "/tmp/img",
-              "Prefix to use for saving images from the logfile.");
-DEFINE_bool(display, false, "If true, display the images with a timeout.");
-DEFINE_bool(detected_only, false,
-            "If true, only write images which had blobs (unfiltered) detected");
-DEFINE_bool(filtered_only, false,
-            "If true, only write images which had blobs (filtered) detected");
-DEFINE_bool(match_timestamps, false,
-            "If true, name the files based on the time since the robot was "
-            "enabled (match start). Only consider images during this time");
-DEFINE_string(logger_pi_log, "/tmp/logger_pi/", "Path to logger pi log");
-DEFINE_string(roborio_log, "/tmp/roborio/", "Path to roborio log");
+ABSL_FLAG(std::string, pi, "pi3", "Node name to replay.");
+ABSL_FLAG(std::string, image_save_prefix, "/tmp/img",
+          "Prefix to use for saving images from the logfile.");
+ABSL_FLAG(bool, display, false, "If true, display the images with a timeout.");
+ABSL_FLAG(bool, detected_only, false,
+          "If true, only write images which had blobs (unfiltered) detected");
+ABSL_FLAG(bool, filtered_only, false,
+          "If true, only write images which had blobs (filtered) detected");
+ABSL_FLAG(bool, match_timestamps, false,
+          "If true, name the files based on the time since the robot was "
+          "enabled (match start). Only consider images during this time");
+ABSL_FLAG(std::string, logger_pi_log, "/tmp/logger_pi/",
+          "Path to logger pi log");
+ABSL_FLAG(std::string, roborio_log, "/tmp/roborio/", "Path to roborio log");
 
 namespace y2022::vision {
 namespace {
@@ -47,8 +48,8 @@
   data->match_end = monotonic_clock::min_time;
 
   // Open logfiles
-  aos::logger::LogReader reader(
-      aos::logger::SortParts(aos::logger::FindLogs(FLAGS_roborio_log)));
+  aos::logger::LogReader reader(aos::logger::SortParts(
+      aos::logger::FindLogs(absl::GetFlag(FLAGS_roborio_log))));
   reader.Register();
   const aos::Node *roborio =
       aos::configuration::GetNode(reader.configuration(), "roborio");
@@ -140,7 +141,7 @@
 
 // Extract images from the pi logs
 void ReplayPi(const ReplayData &data) {
-  if (FLAGS_match_timestamps) {
+  if (absl::GetFlag(FLAGS_match_timestamps)) {
     CHECK_NE(data.match_start, monotonic_clock::min_time)
         << "Can't use match timestamps if match never started";
     CHECK_NE(data.match_end, monotonic_clock::min_time)
@@ -148,11 +149,11 @@
   }
 
   // Open logfiles
-  aos::logger::LogReader reader(
-      aos::logger::SortParts(aos::logger::FindLogs(FLAGS_logger_pi_log)));
+  aos::logger::LogReader reader(aos::logger::SortParts(
+      aos::logger::FindLogs(absl::GetFlag(FLAGS_logger_pi_log))));
   reader.Register();
-  const aos::Node *pi =
-      aos::configuration::GetNode(reader.configuration(), FLAGS_pi);
+  const aos::Node *pi = aos::configuration::GetNode(reader.configuration(),
+                                                    absl::GetFlag(FLAGS_pi));
 
   std::unique_ptr<aos::EventLoop> event_loop =
       reader.event_loop_factory()->MakeEventLoop("player", pi);
@@ -171,7 +172,7 @@
         const auto superstructure_state = ClosestElement(
             data.superstructure_states, event_loop->monotonic_now());
 
-        if (FLAGS_match_timestamps) {
+        if (absl::GetFlag(FLAGS_match_timestamps)) {
           if (event_loop->monotonic_now() < data.match_start) {
             // Ignore prematch images if we only care about ones during the
             // match
@@ -190,23 +191,24 @@
         cv::cvtColor(image_color_mat, image_mat, cv::COLOR_YUV2BGR_YUYV);
 
         bool use_image = true;
-        if (FLAGS_detected_only || FLAGS_filtered_only) {
+        if (absl::GetFlag(FLAGS_detected_only) ||
+            absl::GetFlag(FLAGS_filtered_only)) {
           // TODO(milind): if adding target estimation here in the future,
           // undistortion is needed
           BlobDetector::BlobResult blob_result;
           BlobDetector::ExtractBlobs(image_mat, &blob_result);
 
-          use_image =
-              ((FLAGS_filtered_only ? blob_result.filtered_blobs.size()
-                                    : blob_result.unfiltered_blobs.size()) > 0);
+          use_image = ((absl::GetFlag(FLAGS_filtered_only)
+                            ? blob_result.filtered_blobs.size()
+                            : blob_result.unfiltered_blobs.size()) > 0);
         }
 
         if (use_image) {
-          if (!FLAGS_image_save_prefix.empty()) {
+          if (!absl::GetFlag(FLAGS_image_save_prefix).empty()) {
             std::stringstream image_name;
-            image_name << FLAGS_image_save_prefix;
+            image_name << absl::GetFlag(FLAGS_image_save_prefix);
 
-            if (FLAGS_match_timestamps) {
+            if (absl::GetFlag(FLAGS_match_timestamps)) {
               // Add the time since match start into the image for debugging.
               // We can match images with the game recording.
               image_name << "match_"
@@ -239,9 +241,12 @@
 
             cv::imwrite(image_name.str(), image_mat);
           }
-          if (FLAGS_display) {
+          if (absl::GetFlag(FLAGS_display)) {
             cv::imshow("Display", image_mat);
-            cv::waitKey(FLAGS_detected_only || FLAGS_filtered_only ? 10 : 1);
+            cv::waitKey(absl::GetFlag(FLAGS_detected_only) ||
+                                absl::GetFlag(FLAGS_filtered_only)
+                            ? 10
+                            : 1);
           }
         }
       });