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/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