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/y2020/BUILD b/y2020/BUILD
index 3def80a..51fbb54 100644
--- a/y2020/BUILD
+++ b/y2020/BUILD
@@ -89,8 +89,9 @@
         "//y2020/control_loops/superstructure/hood:hood_plants",
         "//y2020/control_loops/superstructure/intake:intake_plants",
         "//y2020/control_loops/superstructure/turret:turret_plants",
-        "@com_github_google_glog//:glog",
         "@com_google_absl//absl/base",
+        "@com_google_absl//absl/log",
+        "@com_google_absl//absl/log:check",
     ],
 )
 
diff --git a/y2020/actors/autonomous_actor.cc b/y2020/actors/autonomous_actor.cc
index 404372d..f68c7f7 100644
--- a/y2020/actors/autonomous_actor.cc
+++ b/y2020/actors/autonomous_actor.cc
@@ -4,6 +4,8 @@
 #include <cinttypes>
 #include <cmath>
 
+#include "absl/flags/flag.h"
+
 #include "aos/logging/logging.h"
 #include "aos/network/team_number.h"
 #include "aos/util/math.h"
@@ -12,9 +14,9 @@
 #include "y2020/constants.h"
 #include "y2020/control_loops/drivetrain/drivetrain_base.h"
 
-DEFINE_bool(spline_auto, false, "If true, define a spline autonomous mode");
-DEFINE_bool(just_shoot, false,
-            "If true, run the autonomous that just shoots balls.");
+ABSL_FLAG(bool, spline_auto, false, "If true, define a spline autonomous mode");
+ABSL_FLAG(bool, just_shoot, false,
+          "If true, run the autonomous that just shoots balls.");
 
 namespace y2020::actors {
 
@@ -93,7 +95,7 @@
     return;
   }
   sent_starting_position_ = false;
-  if (FLAGS_spline_auto) {
+  if (absl::GetFlag(FLAGS_spline_auto)) {
     test_spline_ = PlanSpline(std::bind(&AutonomousSplines::TestSpline,
                                         &auto_splines_, std::placeholders::_1),
                               SplineDirection::kForward);
@@ -161,7 +163,7 @@
     AOS_LOG(INFO, "Aborting autonomous due to invalid alliance selection.");
     return false;
   }
-  if (FLAGS_spline_auto) {
+  if (absl::GetFlag(FLAGS_spline_auto)) {
     SplineAuto();
   } else {
     if (practice_robot_) {
diff --git a/y2020/actors/shooter_tuning_actor.cc b/y2020/actors/shooter_tuning_actor.cc
index a6efce7..ae34362 100644
--- a/y2020/actors/shooter_tuning_actor.cc
+++ b/y2020/actors/shooter_tuning_actor.cc
@@ -6,7 +6,8 @@
 #include <sstream>
 #include <utility>
 
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
 
 #include "aos/init.h"
 #include "frc971/autonomous/base_autonomous_actor.h"
diff --git a/y2020/constants.cc b/y2020/constants.cc
index b5456b4..7ae54b5 100644
--- a/y2020/constants.cc
+++ b/y2020/constants.cc
@@ -8,7 +8,8 @@
 #endif
 
 #include "absl/base/call_once.h"
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
 
 #include "aos/network/team_number.h"
 #include "aos/stl_mutex/stl_mutex.h"
diff --git a/y2020/control_loops/drivetrain/BUILD b/y2020/control_loops/drivetrain/BUILD
index feabb62..9bf0fab 100644
--- a/y2020/control_loops/drivetrain/BUILD
+++ b/y2020/control_loops/drivetrain/BUILD
@@ -192,8 +192,9 @@
         "//aos/testing:googletest",
         "//frc971/control_loops/drivetrain:drivetrain_lib",
         "//frc971/control_loops/drivetrain:trajectory_schema",
-        "@com_github_gflags_gflags//:gflags",
-        "@com_github_google_glog//:glog",
+        "@com_google_absl//absl/flags:flag",
+        "@com_google_absl//absl/log",
+        "@com_google_absl//absl/log:check",
     ],
 )
 
@@ -216,8 +217,9 @@
         "//frc971/control_loops/drivetrain:trajectory_generator",
         "//y2020:constants",
         "//y2020/control_loops/superstructure:superstructure_lib",
-        "@com_github_gflags_gflags//:gflags",
-        "@com_github_google_glog//:glog",
+        "@com_google_absl//absl/flags:flag",
+        "@com_google_absl//absl/log",
+        "@com_google_absl//absl/log:check",
     ],
 )
 
diff --git a/y2020/control_loops/drivetrain/drivetrain_replay.cc b/y2020/control_loops/drivetrain/drivetrain_replay.cc
index 326c184..5c5c20b 100644
--- a/y2020/control_loops/drivetrain/drivetrain_replay.cc
+++ b/y2020/control_loops/drivetrain/drivetrain_replay.cc
@@ -4,7 +4,7 @@
 // replayed, so that it can then be run through the plotting tool or analyzed
 // in some other way. The original drivetrain status data will be on the
 // /original/drivetrain channel.
-#include "gflags/gflags.h"
+#include "absl/flags/flag.h"
 
 #include "aos/configuration.h"
 #include "aos/events/logging/log_reader.h"
@@ -21,12 +21,13 @@
 #include "y2020/control_loops/drivetrain/localizer.h"
 #include "y2020/control_loops/superstructure/superstructure.h"
 
-DEFINE_string(config, "y2020/aos_config.json",
-              "Name of the config file to replay using.");
-DEFINE_string(output_folder, "/tmp/replayed",
-              "Name of the folder to write replayed logs to.");
-DEFINE_int32(team, 971, "Team number to use for logfile replay.");
-DEFINE_bool(log_all_nodes, false, "Whether to rerun the logger on every node.");
+ABSL_FLAG(std::string, config, "y2020/aos_config.json",
+          "Name of the config file to replay using.");
+ABSL_FLAG(std::string, output_folder, "/tmp/replayed",
+          "Name of the folder to write replayed logs to.");
+ABSL_FLAG(int32_t, team, 971, "Team number to use for logfile replay.");
+ABSL_FLAG(bool, log_all_nodes, false,
+          "Whether to rerun the logger on every node.");
 
 // TODO(james): Currently, this replay produces logfiles that can't be read due
 // to time estimation issues. Pending the active refactorings of the
@@ -34,10 +35,10 @@
 int main(int argc, char **argv) {
   aos::InitGoogle(&argc, &argv);
 
-  aos::network::OverrideTeamNumber(FLAGS_team);
+  aos::network::OverrideTeamNumber(absl::GetFlag(FLAGS_team));
 
   const aos::FlatbufferDetachedBuffer<aos::Configuration> config =
-      aos::configuration::ReadConfig(FLAGS_config);
+      aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
 
   // sort logfiles
   const std::vector<aos::logger::LogFile> logfiles =
@@ -60,16 +61,17 @@
   reader.Register();
 
   std::vector<std::unique_ptr<aos::util::LoggerState>> loggers;
-  if (FLAGS_log_all_nodes) {
-    loggers = aos::util::MakeLoggersForAllNodes(reader.event_loop_factory(),
-                                                FLAGS_output_folder);
+  if (absl::GetFlag(FLAGS_log_all_nodes)) {
+    loggers = aos::util::MakeLoggersForAllNodes(
+        reader.event_loop_factory(), absl::GetFlag(FLAGS_output_folder));
   } else {
     // List of nodes to create loggers for (note: currently just roborio; this
     // code was refactored to allow easily adding new loggers to accommodate
     // debugging and potential future changes).
     const std::vector<std::string> nodes_to_log = {"roborio"};
-    loggers = aos::util::MakeLoggersForNodes(reader.event_loop_factory(),
-                                             nodes_to_log, FLAGS_output_folder);
+    loggers = aos::util::MakeLoggersForNodes(
+        reader.event_loop_factory(), nodes_to_log,
+        absl::GetFlag(FLAGS_output_folder));
   }
 
   const aos::Node *node = nullptr;
diff --git a/y2020/control_loops/drivetrain/drivetrain_replay_test.cc b/y2020/control_loops/drivetrain/drivetrain_replay_test.cc
index 8d096cd..62592c0 100644
--- a/y2020/control_loops/drivetrain/drivetrain_replay_test.cc
+++ b/y2020/control_loops/drivetrain/drivetrain_replay_test.cc
@@ -8,7 +8,7 @@
 // longer be valid.
 // TODO(james): Do something about that when the time comes--could just copy
 // the existing drivetrain config into this file and use it directly.
-#include "gflags/gflags.h"
+#include "absl/flags/flag.h"
 #include "gtest/gtest.h"
 
 #include "aos/configuration.h"
@@ -22,17 +22,18 @@
 #include "frc971/control_loops/drivetrain/trajectory_schema.h"
 #include "y2020/control_loops/drivetrain/drivetrain_base.h"
 
-DEFINE_string(logfile, "external/drivetrain_replay/",
-              "Name of the logfile to read from.");
-DEFINE_string(config, "y2020/aos_config.json",
-              "Name of the config file to replay using.");
+ABSL_FLAG(std::string, logfile, "external/drivetrain_replay/",
+          "Name of the logfile to read from.");
+ABSL_FLAG(std::string, config, "y2020/aos_config.json",
+          "Name of the config file to replay using.");
 
 namespace y2020::control_loops::drivetrain::testing {
 
 class DrivetrainReplayTest : public ::testing::Test {
  public:
   DrivetrainReplayTest()
-      : reader_(aos::logger::SortParts(aos::logger::FindLogs(FLAGS_logfile))) {
+      : reader_(aos::logger::SortParts(
+            aos::logger::FindLogs(absl::GetFlag(FLAGS_logfile)))) {
     aos::network::OverrideTeamNumber(971);
 
     // TODO(james): Actually enforce not sending on the same buses as the
diff --git a/y2020/control_loops/drivetrain/localizer.cc b/y2020/control_loops/drivetrain/localizer.cc
index 0943b28..f8518f3 100644
--- a/y2020/control_loops/drivetrain/localizer.cc
+++ b/y2020/control_loops/drivetrain/localizer.cc
@@ -1,10 +1,12 @@
 #include "y2020/control_loops/drivetrain/localizer.h"
 
+#include "absl/flags/flag.h"
+
 #include "y2020/constants.h"
 
-DEFINE_bool(send_empty_debug, false,
-            "If true, send LocalizerDebug messages on every tick, even if "
-            "they would be empty.");
+ABSL_FLAG(bool, send_empty_debug, false,
+          "If true, send LocalizerDebug messages on every tick, even if "
+          "they would be empty.");
 
 namespace y2020::control_loops::drivetrain {
 
@@ -181,7 +183,7 @@
       }
     }
   }
-  if (FLAGS_send_empty_debug || !debug_offsets.empty()) {
+  if (absl::GetFlag(FLAGS_send_empty_debug) || !debug_offsets.empty()) {
     const auto vector_offset =
         builder.fbb()->CreateVector(debug_offsets.data(), debug_offsets.size());
     const auto rejections_offset =
diff --git a/y2020/control_loops/drivetrain/localizer_test.cc b/y2020/control_loops/drivetrain/localizer_test.cc
index e509241..951a286 100644
--- a/y2020/control_loops/drivetrain/localizer_test.cc
+++ b/y2020/control_loops/drivetrain/localizer_test.cc
@@ -2,6 +2,7 @@
 
 #include <queue>
 
+#include "absl/flags/flag.h"
 #include "gtest/gtest.h"
 
 #include "aos/events/logging/log_writer.h"
@@ -14,8 +15,8 @@
 #include "y2020/control_loops/drivetrain/drivetrain_base.h"
 #include "y2020/control_loops/superstructure/superstructure_status_generated.h"
 
-DEFINE_string(output_file, "",
-              "If set, logs all channels to the provided logfile.");
+ABSL_FLAG(std::string, output_file, "",
+          "If set, logs all channels to the provided logfile.");
 
 // This file tests that the full 2020 localizer behaves sanely.
 
@@ -145,10 +146,10 @@
     set_team_id(frc971::control_loops::testing::kTeamNumber);
     set_battery_voltage(12.0);
 
-    if (!FLAGS_output_file.empty()) {
+    if (!absl::GetFlag(FLAGS_output_file).empty()) {
       logger_event_loop_ = MakeEventLoop("logger", roborio_);
       logger_ = std::make_unique<aos::logger::Logger>(logger_event_loop_.get());
-      logger_->StartLoggingOnRun(FLAGS_output_file);
+      logger_->StartLoggingOnRun(absl::GetFlag(FLAGS_output_file));
     }
 
     test_event_loop_->MakeWatcher(
diff --git a/y2020/control_loops/drivetrain/trajectory_generator_main.cc b/y2020/control_loops/drivetrain/trajectory_generator_main.cc
index 152822e..e7634b7 100644
--- a/y2020/control_loops/drivetrain/trajectory_generator_main.cc
+++ b/y2020/control_loops/drivetrain/trajectory_generator_main.cc
@@ -1,6 +1,8 @@
 #include <sys/resource.h>
 #include <sys/time.h>
 
+#include "absl/flags/flag.h"
+
 #include "aos/events/shm_event_loop.h"
 #include "aos/init.h"
 #include "frc971/control_loops/drivetrain/trajectory_generator.h"
@@ -8,8 +10,8 @@
 
 using ::frc971::control_loops::drivetrain::TrajectoryGenerator;
 
-DEFINE_bool(skip_renicing, false,
-            "If true, skip renicing the trajectory generator.");
+ABSL_FLAG(bool, skip_renicing, false,
+          "If true, skip renicing the trajectory generator.");
 
 int main(int argc, char *argv[]) {
   ::aos::InitGoogle(&argc, &argv);
@@ -22,7 +24,7 @@
       &event_loop, ::y2020::control_loops::drivetrain::GetDrivetrainConfig());
 
   event_loop.OnRun([]() {
-    if (FLAGS_skip_renicing) {
+    if (absl::GetFlag(FLAGS_skip_renicing)) {
       LOG(WARNING) << "Ignoring request to renice to -20 due to "
                       "--skip_renicing.";
     } else {
diff --git a/y2020/control_loops/superstructure/shooter/BUILD b/y2020/control_loops/superstructure/shooter/BUILD
index 96c933f..df676e4 100644
--- a/y2020/control_loops/superstructure/shooter/BUILD
+++ b/y2020/control_loops/superstructure/shooter/BUILD
@@ -57,7 +57,8 @@
         ":shooter_tuning_readings_fbs",
         "//aos:init",
         "//aos/events:shm_event_loop",
-        "@com_github_gflags_gflags//:gflags",
-        "@com_github_google_glog//:glog",
+        "@com_google_absl//absl/flags:flag",
+        "@com_google_absl//absl/log",
+        "@com_google_absl//absl/log:check",
     ],
 )
diff --git a/y2020/control_loops/superstructure/shooter/shooter_tuning_params_setter.cc b/y2020/control_loops/superstructure/shooter/shooter_tuning_params_setter.cc
index 5e3010d..abd5463 100644
--- a/y2020/control_loops/superstructure/shooter/shooter_tuning_params_setter.cc
+++ b/y2020/control_loops/superstructure/shooter/shooter_tuning_params_setter.cc
@@ -1,22 +1,26 @@
-#include "gflags/gflags.h"
-#include "glog/logging.h"
+#include "absl/flags/flag.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
 
 #include "aos/events/shm_event_loop.h"
 #include "aos/init.h"
 #include "y2020/control_loops/superstructure/shooter/shooter_tuning_params_generated.h"
 
-DEFINE_double(velocity_initial_finisher, 300.0, "Initial finisher velocity");
-DEFINE_double(velocity_final_finisher, 500.0, "Final finisher velocity");
-DEFINE_double(velocity_finisher_increment, 25.0, "Finisher velocity increment");
+ABSL_FLAG(double, velocity_initial_finisher, 300.0,
+          "Initial finisher velocity");
+ABSL_FLAG(double, velocity_final_finisher, 500.0, "Final finisher velocity");
+ABSL_FLAG(double, velocity_finisher_increment, 25.0,
+          "Finisher velocity increment");
 
-DEFINE_double(velocity_initial_accelerator, 180.0,
-              "Initial accelerator velocity");
-DEFINE_double(velocity_final_accelerator, 250.0, "Final accelerator velocity");
-DEFINE_double(velocity_accelerator_increment, 20.0,
-              "Accelerator velocity increment");
+ABSL_FLAG(double, velocity_initial_accelerator, 180.0,
+          "Initial accelerator velocity");
+ABSL_FLAG(double, velocity_final_accelerator, 250.0,
+          "Final accelerator velocity");
+ABSL_FLAG(double, velocity_accelerator_increment, 20.0,
+          "Accelerator velocity increment");
 
-DEFINE_int32(balls_per_iteration, 10,
-             "Balls to shoot per iteration in the velocity sweep");
+ABSL_FLAG(int32_t, balls_per_iteration, 10,
+          "Balls to shoot per iteration in the velocity sweep");
 
 namespace shooter = y2020::control_loops::superstructure::shooter;
 
@@ -43,16 +47,19 @@
   auto builder = sender.MakeBuilder();
 
   auto finisher_params = BuildFlywheelTuningParams(
-      builder, FLAGS_velocity_initial_finisher, FLAGS_velocity_final_finisher,
-      FLAGS_velocity_finisher_increment);
+      builder, absl::GetFlag(FLAGS_velocity_initial_finisher),
+      absl::GetFlag(FLAGS_velocity_final_finisher),
+      absl::GetFlag(FLAGS_velocity_finisher_increment));
   auto accelerator_params = BuildFlywheelTuningParams(
-      builder, FLAGS_velocity_initial_accelerator,
-      FLAGS_velocity_final_accelerator, FLAGS_velocity_accelerator_increment);
+      builder, absl::GetFlag(FLAGS_velocity_initial_accelerator),
+      absl::GetFlag(FLAGS_velocity_final_accelerator),
+      absl::GetFlag(FLAGS_velocity_accelerator_increment));
 
   auto tuning_params_builder = builder.MakeBuilder<shooter::TuningParams>();
   tuning_params_builder.add_finisher(finisher_params);
   tuning_params_builder.add_accelerator(accelerator_params);
-  tuning_params_builder.add_balls_per_iteration(FLAGS_balls_per_iteration);
+  tuning_params_builder.add_balls_per_iteration(
+      absl::GetFlag(FLAGS_balls_per_iteration));
   builder.CheckOk(builder.Send(tuning_params_builder.Finish()));
 
   return 0;
diff --git a/y2020/control_loops/superstructure/superstructure_lib_test.cc b/y2020/control_loops/superstructure/superstructure_lib_test.cc
index fad888c..1a9e228 100644
--- a/y2020/control_loops/superstructure/superstructure_lib_test.cc
+++ b/y2020/control_loops/superstructure/superstructure_lib_test.cc
@@ -3,7 +3,8 @@
 #include <chrono>
 #include <memory>
 
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
 #include "gtest/gtest.h"
 
 #include "aos/events/logging/log_reader.h"
@@ -21,12 +22,12 @@
 #include "y2020/control_loops/superstructure/intake/intake_plant.h"
 #include "y2020/control_loops/superstructure/superstructure.h"
 
-DEFINE_string(output_file, "",
-              "If set, logs all channels to the provided logfile.");
-DEFINE_string(replay_logfile, "external/superstructure_replay/",
-              "Name of the logfile to read from and replay.");
-DEFINE_string(config, "y2020/aos_config.json",
-              "Name of the config file to replay using.");
+ABSL_FLAG(std::string, output_file, "",
+          "If set, logs all channels to the provided logfile.");
+ABSL_FLAG(std::string, replay_logfile, "external/superstructure_replay/",
+          "Name of the logfile to read from and replay.");
+ABSL_FLAG(std::string, config, "y2020/aos_config.json",
+          "Name of the config file to replay using.");
 
 namespace y2020::control_loops::superstructure::testing {
 
@@ -263,8 +264,10 @@
                accelerator_left_plant_->voltage_offset();
 
     // Confirm that we aren't drawing too much current.
-    CHECK_NEAR(accelerator_left_plant_->battery_current(accelerator_left_U),
-               0.0, 75.0);
+    CHECK_LE(accelerator_left_plant_->battery_current(accelerator_left_U),
+             75.0);
+    CHECK_GE(accelerator_left_plant_->battery_current(accelerator_left_U),
+             -75.0);
 
     ::Eigen::Matrix<double, 1, 1> accelerator_right_U;
     accelerator_right_U
@@ -272,8 +275,10 @@
                accelerator_right_plant_->voltage_offset();
 
     // Confirm that we aren't drawing too much current.
-    CHECK_NEAR(accelerator_right_plant_->battery_current(accelerator_right_U),
-               0.0, 75.0);
+    CHECK_LE(accelerator_right_plant_->battery_current(accelerator_right_U),
+             75.0);
+    CHECK_GE(accelerator_right_plant_->battery_current(accelerator_right_U),
+             -75.0);
 
     ::Eigen::Matrix<double, 1, 1> finisher_U;
     finisher_U << superstructure_output_fetcher_->finisher_voltage() +
@@ -281,7 +286,8 @@
 
     // Confirm that we aren't drawing too much current.  2 motors -> twice the
     // lumped current since our model can't tell them apart.
-    CHECK_NEAR(finisher_plant_->battery_current(finisher_U), 0.0, 200.0);
+    CHECK_LE(finisher_plant_->battery_current(finisher_U), 200.0);
+    CHECK_GE(finisher_plant_->battery_current(finisher_U), -200.0);
 
     hood_plant_->Update(hood_U);
     intake_plant_->Update(intake_U);
@@ -440,11 +446,11 @@
         superstructure_plant_(superstructure_plant_event_loop_.get(), dt()) {
     set_team_id(::frc971::control_loops::testing::kTeamNumber);
 
-    if (!FLAGS_output_file.empty()) {
-      unlink(FLAGS_output_file.c_str());
+    if (!absl::GetFlag(FLAGS_output_file).empty()) {
+      unlink(absl::GetFlag(FLAGS_output_file).c_str());
       logger_event_loop_ = MakeEventLoop("logger", roborio_);
       logger_ = std::make_unique<aos::logger::Logger>(logger_event_loop_.get());
-      logger_->StartLoggingOnRun(FLAGS_output_file);
+      logger_->StartLoggingOnRun(absl::GetFlag(FLAGS_output_file));
     }
   }
 
@@ -1143,7 +1149,7 @@
  public:
   SuperstructureReplayTest()
       : reader_(aos::logger::SortParts(
-            aos::logger::FindLogs(FLAGS_replay_logfile))) {
+            aos::logger::FindLogs(absl::GetFlag(FLAGS_replay_logfile)))) {
     aos::network::OverrideTeamNumber(971);
 
     reader_.RemapLoggedChannel("/superstructure",
@@ -1168,12 +1174,12 @@
     superstructure_status_fetcher_ =
         test_event_loop_->MakeFetcher<Status>("/superstructure");
 
-    if (!FLAGS_output_file.empty()) {
-      unlink(FLAGS_output_file.c_str());
+    if (!absl::GetFlag(FLAGS_output_file).empty()) {
+      unlink(absl::GetFlag(FLAGS_output_file).c_str());
       logger_event_loop_ =
           reader_.event_loop_factory()->MakeEventLoop("logger", roborio_);
       logger_ = std::make_unique<aos::logger::Logger>(logger_event_loop_.get());
-      logger_->StartLoggingOnRun(FLAGS_output_file);
+      logger_->StartLoggingOnRun(absl::GetFlag(FLAGS_output_file));
     }
   }
 
diff --git a/y2020/control_loops/superstructure/superstructure_replay.cc b/y2020/control_loops/superstructure/superstructure_replay.cc
index 36a6778..27816ce 100644
--- a/y2020/control_loops/superstructure/superstructure_replay.cc
+++ b/y2020/control_loops/superstructure/superstructure_replay.cc
@@ -4,7 +4,7 @@
 // replayed, so that it can then be run through the plotting tool or analyzed
 // in some other way. The original drivetrain status data will be on the
 // /original/drivetrain channel.
-#include "gflags/gflags.h"
+#include "absl/flags/flag.h"
 
 #include "aos/events/logging/log_reader.h"
 #include "aos/events/simulated_event_loop.h"
@@ -15,12 +15,12 @@
 #include "y2020/constants.h"
 #include "y2020/control_loops/superstructure/superstructure.h"
 
-DEFINE_int32(team, 971, "Team number to use for logfile replay.");
+ABSL_FLAG(int32_t, team, 971, "Team number to use for logfile replay.");
 
 int main(int argc, char **argv) {
   aos::InitGoogle(&argc, &argv);
 
-  aos::network::OverrideTeamNumber(FLAGS_team);
+  aos::network::OverrideTeamNumber(absl::GetFlag(FLAGS_team));
   y2020::constants::InitValues();
 
   // open logfiles
diff --git a/y2020/setpoint_setter.cc b/y2020/setpoint_setter.cc
index 2bfb917..fe1738a 100644
--- a/y2020/setpoint_setter.cc
+++ b/y2020/setpoint_setter.cc
@@ -1,14 +1,13 @@
-#include "gflags/gflags.h"
-#include "glog/logging.h"
+#include "absl/flags/flag.h"
 
 #include "aos/events/shm_event_loop.h"
 #include "aos/init.h"
 #include "y2020/setpoint_generated.h"
 
-DEFINE_double(accelerator, 250.0, "Accelerator speed");
-DEFINE_double(finisher, 500.0, "Finsher speed");
-DEFINE_double(hood, 0.45, "Hood setpoint");
-DEFINE_double(turret, 0.0, "Turret setpoint");
+ABSL_FLAG(double, accelerator, 250.0, "Accelerator speed");
+ABSL_FLAG(double, finisher, 500.0, "Finsher speed");
+ABSL_FLAG(double, hood, 0.45, "Hood setpoint");
+ABSL_FLAG(double, turret, 0.0, "Turret setpoint");
 
 int main(int argc, char **argv) {
   aos::InitGoogle(&argc, &argv);
@@ -27,10 +26,10 @@
   y2020::joysticks::Setpoint::Builder setpoint_builder =
       builder.MakeBuilder<y2020::joysticks::Setpoint>();
 
-  setpoint_builder.add_accelerator(FLAGS_accelerator);
-  setpoint_builder.add_finisher(FLAGS_finisher);
-  setpoint_builder.add_hood(FLAGS_hood);
-  setpoint_builder.add_turret(FLAGS_turret);
+  setpoint_builder.add_accelerator(absl::GetFlag(FLAGS_accelerator));
+  setpoint_builder.add_finisher(absl::GetFlag(FLAGS_finisher));
+  setpoint_builder.add_hood(absl::GetFlag(FLAGS_hood));
+  setpoint_builder.add_turret(absl::GetFlag(FLAGS_turret));
   builder.CheckOk(builder.Send(setpoint_builder.Finish()));
 
   return 0;
diff --git a/y2020/vision/camera_reader.cc b/y2020/vision/camera_reader.cc
index 251f988..37d35e6 100644
--- a/y2020/vision/camera_reader.cc
+++ b/y2020/vision/camera_reader.cc
@@ -2,6 +2,7 @@
 
 #include <math.h>
 
+#include "absl/flags/flag.h"
 #include <opencv2/calib3d.hpp>
 #include <opencv2/features2d.hpp>
 #include <opencv2/imgproc.hpp>
@@ -16,12 +17,12 @@
 #include "y2020/vision/sift/sift_training_generated.h"
 #include "y2020/vision/tools/python_code/sift_training_data.h"
 
-DEFINE_bool(skip_sift, false,
-            "If true don't run any feature extraction.  Just forward images.");
-DEFINE_bool(ransac_pose, false,
-            "If true, do pose estimate with RANSAC; else, use ITERATIVE mode.");
-DEFINE_bool(use_prev_pose, true,
-            "If true, use previous pose estimate as seed for next estimate.");
+ABSL_FLAG(bool, skip_sift, false,
+          "If true don't run any feature extraction.  Just forward images.");
+ABSL_FLAG(bool, ransac_pose, false,
+          "If true, do pose estimate with RANSAC; else, use ITERATIVE mode.");
+ABSL_FLAG(bool, use_prev_pose, true,
+          "If true, use previous pose estimate as seed for next estimate.");
 
 namespace frc971::vision {
 
@@ -160,7 +161,7 @@
   std::vector<cv::KeyPoint> keypoints;
 
   cv::Mat descriptors;
-  if (!FLAGS_skip_sift) {
+  if (!absl::GetFlag(FLAGS_skip_sift)) {
     sift_->detectAndCompute(image_mat, cv::noArray(), keypoints, descriptors);
   }
 
@@ -176,7 +177,7 @@
   for (int image_idx = 0; image_idx < number_training_images(); ++image_idx) {
     // Then, match those features against our training data.
     std::vector<std::vector<cv::DMatch>> matches;
-    if (!FLAGS_skip_sift) {
+    if (!absl::GetFlag(FLAGS_skip_sift)) {
       matchers_[image_idx].knnMatch(/* queryDescriptors */ descriptors, matches,
                                     /* k */ 2);
     }
@@ -318,7 +319,7 @@
     // it's sometimes bouncing between two possible poses.  Putting it
     // near the previous pose helps it converge to the previous pose
     // estimate (assuming it's valid).
-    if (FLAGS_use_prev_pose) {
+    if (absl::GetFlag(FLAGS_use_prev_pose)) {
       R_camera_field_vec = prev_camera_field_R_vec_list_[i].clone();
       T_camera_field = prev_camera_field_T_list_[i].clone();
       VLOG(2) << "Using previous match for training image " << i
@@ -326,13 +327,13 @@
     }
 
     // Compute the pose of the camera (global origin relative to camera)
-    if (FLAGS_ransac_pose) {
+    if (absl::GetFlag(FLAGS_ransac_pose)) {
       // RANSAC computation is designed to be more robust to outliers.
       // But, we found it bounces around a lot, even with identical points
       cv::solvePnPRansac(per_image_good_match.training_points_3d,
                          per_image_good_match.query_points, CameraIntrinsics(),
                          CameraDistCoeffs(), R_camera_field_vec, T_camera_field,
-                         FLAGS_use_prev_pose);
+                         absl::GetFlag(FLAGS_use_prev_pose));
     } else {
       // ITERATIVE mode is potentially less robust to outliers, but we
       // found it to be more stable
@@ -340,7 +341,7 @@
       cv::solvePnP(per_image_good_match.training_points_3d,
                    per_image_good_match.query_points, CameraIntrinsics(),
                    CameraDistCoeffs(), R_camera_field_vec, T_camera_field,
-                   FLAGS_use_prev_pose, cv::SOLVEPNP_ITERATIVE);
+                   absl::GetFlag(FLAGS_use_prev_pose), cv::SOLVEPNP_ITERATIVE);
     }
 
     // We are occasionally seeing NaN in the prior estimate, so checking for
@@ -451,7 +452,7 @@
 
 void CameraReader::ReadImage() {
   if (!reader_->ReadLatestImage()) {
-    if (!FLAGS_skip_sift) {
+    if (!absl::GetFlag(FLAGS_skip_sift)) {
       LOG(INFO) << "No image, sleeping";
     }
     read_image_timer_->Schedule(event_loop_->monotonic_now() +
diff --git a/y2020/vision/camera_reader_main.cc b/y2020/vision/camera_reader_main.cc
index 1995151..90a2580 100644
--- a/y2020/vision/camera_reader_main.cc
+++ b/y2020/vision/camera_reader_main.cc
@@ -1,3 +1,6 @@
+#include "absl/flags/flag.h"
+#include "absl/log/check.h"
+
 #include "aos/events/shm_event_loop.h"
 #include "aos/init.h"
 #include "y2020/vision/camera_reader.h"
@@ -5,14 +8,15 @@
 // config used to allow running camera_reader independently.  E.g.,
 // bazel run //y2020/vision:camera_reader -- --config y2020/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 frc971::vision {
 namespace {
 
 void CameraReaderMain() {
   aos::FlatbufferDetachedBuffer<aos::Configuration> config =
-      aos::configuration::ReadConfig(FLAGS_config);
+      aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
 
   const aos::FlatbufferSpan<sift::TrainingData> training_data(
       SiftTrainingData());
diff --git a/y2020/vision/extrinsics_calibration.cc b/y2020/vision/extrinsics_calibration.cc
index ddbe9af..9f50373 100644
--- a/y2020/vision/extrinsics_calibration.cc
+++ b/y2020/vision/extrinsics_calibration.cc
@@ -2,6 +2,7 @@
 
 #include "Eigen/Dense"
 #include "Eigen/Geometry"
+#include "absl/flags/flag.h"
 #include "absl/strings/str_format.h"
 
 #include "aos/events/logging/log_reader.h"
@@ -15,11 +16,11 @@
 #include "frc971/wpilib/imu_batch_generated.h"
 #include "y2020/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, false, "If true, the camera is on the turret");
-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, false, "If true, the camera is on the turret");
+ABSL_FLAG(std::string, base_intrinsics, "",
+          "Intrinsics to use for extrinsics calibration.");
 
 namespace frc971::vision {
 namespace chrono = std::chrono;
@@ -46,7 +47,7 @@
         aos::configuration::GetNode(factory.configuration(), "roborio");
 
     std::optional<uint16_t> pi_number =
-        aos::network::ParsePiOrOrinNumber(FLAGS_pi);
+        aos::network::ParsePiOrOrinNumber(absl::GetFlag(FLAGS_pi));
     CHECK(pi_number);
     LOG(INFO) << "Pi " << *pi_number;
     const aos::Node *const pi_node = aos::configuration::GetNode(
@@ -65,13 +66,13 @@
 
     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(), TargetType::kCharuco,
-                          "/camera", &data);
+                          absl::GetFlag(FLAGS_pi), &intrinsics.message(),
+                          TargetType::kCharuco, "/camera", &data);
 
-    if (FLAGS_turret) {
+    if (absl::GetFlag(FLAGS_turret)) {
       aos::NodeEventLoopFactory *roborio_factory =
           factory.GetNodeEventLoopFactory(roborio_node->name()->string_view());
       roborio_event_loop->MakeWatcher(
@@ -141,7 +142,7 @@
                    nominal_board_to_world.inverse())
                    .transpose();
 
-  if (FLAGS_plot) {
+  if (absl::GetFlag(FLAGS_plot)) {
     Plot(data, calibration_parameters);
   }
 }
diff --git a/y2020/vision/sift/BUILD b/y2020/vision/sift/BUILD
index a220664..96afd01 100644
--- a/y2020/vision/sift/BUILD
+++ b/y2020/vision/sift/BUILD
@@ -21,7 +21,8 @@
         ":get_gaussian_kernel",
         "//aos/testing:googletest",
         "//third_party:opencv",
-        "@com_github_google_glog//:glog",
+        "@com_google_absl//absl/log",
+        "@com_google_absl//absl/log:check",
     ],
 )
 
@@ -158,7 +159,8 @@
     deps = [
         ":fast_gaussian",
         "//third_party:opencv",
-        "@com_github_google_glog//:glog",
+        "@com_google_absl//absl/log",
+        "@com_google_absl//absl/log:check",
     ],
 )
 
@@ -175,7 +177,8 @@
         ":fast_gaussian_all",
         "//third_party:halide_runtime",
         "//third_party:opencv",
-        "@com_github_google_glog//:glog",
+        "@com_google_absl//absl/log",
+        "@com_google_absl//absl/log:check",
     ],
 )
 
@@ -204,7 +207,8 @@
         "//aos/time",
         "//third_party:opencv",
         "//y2020/vision/sift:sift971",
-        "@com_github_google_glog//:glog",
+        "@com_google_absl//absl/log",
+        "@com_google_absl//absl/log:check",
     ],
 )
 
diff --git a/y2020/vision/sift/fast_gaussian.h b/y2020/vision/sift/fast_gaussian.h
index d9a5f07..4e246e9 100644
--- a/y2020/vision/sift/fast_gaussian.h
+++ b/y2020/vision/sift/fast_gaussian.h
@@ -3,7 +3,8 @@
 
 #include <type_traits>
 
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
 #include <opencv2/core/mat.hpp>
 
 #include "HalideBuffer.h"
diff --git a/y2020/vision/sift/get_gaussian_kernel_test.cc b/y2020/vision/sift/get_gaussian_kernel_test.cc
index 3d2674f..854db64 100644
--- a/y2020/vision/sift/get_gaussian_kernel_test.cc
+++ b/y2020/vision/sift/get_gaussian_kernel_test.cc
@@ -2,7 +2,8 @@
 
 #include <tuple>
 
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
 #include "gmock/gmock.h"
 #include "gtest/gtest.h"
 #include <opencv2/core/mat.hpp>
diff --git a/y2020/vision/sift/sift971.cc b/y2020/vision/sift/sift971.cc
index 21f9a97..1df8d1c 100644
--- a/y2020/vision/sift/sift971.cc
+++ b/y2020/vision/sift/sift971.cc
@@ -110,7 +110,8 @@
 #include <iostream>
 #include <mutex>
 
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
 #include <opencv2/core/hal/hal.hpp>
 #include <opencv2/imgproc.hpp>
 
diff --git a/y2020/vision/sift/testing_sift.cc b/y2020/vision/sift/testing_sift.cc
index c0d4ca2..73b5d08 100644
--- a/y2020/vision/sift/testing_sift.cc
+++ b/y2020/vision/sift/testing_sift.cc
@@ -1,6 +1,8 @@
 #include <memory>
 
-#include "glog/logging.h"
+#include "absl/flags/flag.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
 #include <opencv2/highgui/highgui.hpp>
 #include <opencv2/imgcodecs.hpp>
 #include <opencv2/imgproc.hpp>
@@ -10,15 +12,16 @@
 #include "y2020/vision/sift/fast_gaussian.h"
 #include "y2020/vision/sift/sift971.h"
 
-DEFINE_string(image, "", "Image to test with");
+ABSL_FLAG(std::string, image, "", "Image to test with");
 
 int main(int argc, char **argv) {
   aos::InitGoogle(&argc, &argv);
 
   cv::setNumThreads(4);
 
-  const cv::Mat raw_image = cv::imread(FLAGS_image);
-  CHECK(!raw_image.empty()) << ": Failed to read: " << FLAGS_image;
+  const cv::Mat raw_image = cv::imread(absl::GetFlag(FLAGS_image));
+  CHECK(!raw_image.empty())
+      << ": Failed to read: " << absl::GetFlag(FLAGS_image);
   CHECK_EQ(CV_8UC3, raw_image.type());
 #if 0
   cv::Mat color_image;
diff --git a/y2020/vision/tools/python_code/camera_param_test.cc b/y2020/vision/tools/python_code/camera_param_test.cc
index f47c327..68d7b4d 100644
--- a/y2020/vision/tools/python_code/camera_param_test.cc
+++ b/y2020/vision/tools/python_code/camera_param_test.cc
@@ -1,6 +1,7 @@
 #include <unistd.h>
 
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
 #include "gtest/gtest.h"
 #include <opencv2/features2d.hpp>
 #include <opencv2/imgproc.hpp>
diff --git a/y2020/vision/viewer.cc b/y2020/vision/viewer.cc
index 8ba2955..c44490e 100644
--- a/y2020/vision/viewer.cc
+++ b/y2020/vision/viewer.cc
@@ -1,6 +1,7 @@
 #include <map>
 #include <random>
 
+#include "absl/flags/flag.h"
 #include <opencv2/calib3d.hpp>
 #include <opencv2/features2d.hpp>
 #include <opencv2/highgui/highgui.hpp>
@@ -13,12 +14,13 @@
 #include "frc971/vision/vision_generated.h"
 #include "y2020/vision/sift/sift_generated.h"
 
-DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
-DEFINE_bool(show_features, true, "Show the SIFT features that matched.");
-DEFINE_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(bool, show_features, true, "Show the SIFT features that matched.");
+ABSL_FLAG(std::string, channel, "/camera", "Channel name for the image.");
 
-DEFINE_string(capture, "",
-              "If set, capture a single image and save it to this filename.");
+ABSL_FLAG(std::string, capture, "",
+          "If set, capture a single image and save it to this filename.");
 
 namespace frc971::vision {
 namespace {
@@ -72,8 +74,8 @@
   cv::Mat rgb_image(cv::Size(image->cols(), image->rows()), CV_8UC3);
   cv::cvtColor(image_color_mat, rgb_image, cv::COLOR_YUV2BGR_YUYV);
 
-  if (!FLAGS_capture.empty()) {
-    cv::imwrite(FLAGS_capture, rgb_image);
+  if (!absl::GetFlag(FLAGS_capture).empty()) {
+    cv::imwrite(absl::GetFlag(FLAGS_capture), rgb_image);
     return false;
   }
 
@@ -88,7 +90,8 @@
                  5);
     }
 
-    if (FLAGS_show_features && match->image_matches() != nullptr &&
+    if (absl::GetFlag(FLAGS_show_features) &&
+        match->image_matches() != nullptr &&
         match->image_matches()->size() > 0) {
       // Iterate through matches and draw matched keypoints
       for (uint model_match_ind = 0;
@@ -138,15 +141,16 @@
   palette_ = cv::Mat(3, 5, CV_8U, &colors);
 
   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<CameraImage>(FLAGS_channel);
+  image_fetcher =
+      event_loop.MakeFetcher<CameraImage>(absl::GetFlag(FLAGS_channel));
 
   // If we want to show the features, we have to use the detailed channel
-  std::string result_channel = FLAGS_channel;
-  if (FLAGS_show_features) {
+  std::string result_channel = absl::GetFlag(FLAGS_channel);
+  if (absl::GetFlag(FLAGS_show_features)) {
     result_channel += "/detailed";
   }
   match_fetcher =
diff --git a/y2020/vision/viewer_replay.cc b/y2020/vision/viewer_replay.cc
index ee1c8d5..98b1f34 100644
--- a/y2020/vision/viewer_replay.cc
+++ b/y2020/vision/viewer_replay.cc
@@ -1,3 +1,4 @@
+#include "absl/flags/flag.h"
 #include <opencv2/calib3d.hpp>
 #include <opencv2/features2d.hpp>
 #include <opencv2/highgui/highgui.hpp>
@@ -8,9 +9,9 @@
 #include "aos/init.h"
 #include "frc971/vision/vision_generated.h"
 
-DEFINE_string(node, "pi1", "Node name to replay.");
-DEFINE_string(image_save_prefix, "/tmp/img",
-              "Prefix to use for saving images from the logfile.");
+ABSL_FLAG(std::string, node, "pi1", "Node name to replay.");
+ABSL_FLAG(std::string, image_save_prefix, "/tmp/img",
+          "Prefix to use for saving images from the logfile.");
 
 namespace frc971::vision {
 namespace {
@@ -22,7 +23,8 @@
   reader.Register();
   const aos::Node *node = nullptr;
   if (aos::configuration::MultiNode(reader.configuration())) {
-    node = aos::configuration::GetNode(reader.configuration(), FLAGS_node);
+    node = aos::configuration::GetNode(reader.configuration(),
+                                       absl::GetFlag(FLAGS_node));
   }
   std::unique_ptr<aos::EventLoop> event_loop =
       reader.event_loop_factory()->MakeEventLoop("player", node);
@@ -38,7 +40,7 @@
     }
 
     cv::imshow("Display", image_mat);
-    if (!FLAGS_image_save_prefix.empty()) {
+    if (!absl::GetFlag(FLAGS_image_save_prefix).empty()) {
       cv::imwrite("/tmp/img" + std::to_string(image_count++) + ".png",
                   image_mat);
     }
diff --git a/y2020/wpilib_interface.cc b/y2020/wpilib_interface.cc
index f3ff00f..2213c16 100644
--- a/y2020/wpilib_interface.cc
+++ b/y2020/wpilib_interface.cc
@@ -20,8 +20,8 @@
 #include "frc971/wpilib/ahal/VictorSP.h"
 #undef ERROR
 
+#include "absl/flags/flag.h"
 #include "ctre/phoenix6/TalonFX.hpp"
-#include "gflags/gflags.h"
 
 #include "aos/commonmath.h"
 #include "aos/events/event_loop.h"
@@ -55,9 +55,9 @@
 #include "y2020/control_loops/superstructure/superstructure_output_generated.h"
 #include "y2020/control_loops/superstructure/superstructure_position_static.h"
 
-DEFINE_bool(shooter_tuning, true,
-            "If true, reads from ball beambreak sensors and sends shooter "
-            "tuning readings");
+ABSL_FLAG(bool, shooter_tuning, true,
+          "If true, reads from ball beambreak sensors and sends shooter "
+          "tuning readings");
 
 using ::aos::monotonic_clock;
 using ::y2020::constants::Values;
@@ -258,7 +258,7 @@
   }
 
   void Start() override {
-    if (FLAGS_shooter_tuning) {
+    if (absl::GetFlag(FLAGS_shooter_tuning)) {
       AddToDMA(&ball_beambreak_reader_);
     }
   }
@@ -344,7 +344,7 @@
       builder.CheckOk(builder.Send(auto_mode_builder.Finish()));
     }
 
-    if (FLAGS_shooter_tuning) {
+    if (absl::GetFlag(FLAGS_shooter_tuning)) {
       // Distance between beambreak sensors, in meters.
       constexpr double kDistanceBetweenBeambreaks = 0.4813;
 
@@ -606,7 +606,7 @@
 
     sensor_reader.set_ball_intake_beambreak(make_unique<frc::DigitalInput>(4));
 
-    if (FLAGS_shooter_tuning) {
+    if (absl::GetFlag(FLAGS_shooter_tuning)) {
       sensor_reader.set_ball_beambreak_inputs(
           make_unique<frc::DigitalInput>(6), make_unique<frc::DigitalInput>(7));
     }