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/y2019/BUILD b/y2019/BUILD
index 7bc0c33..2bf0489 100644
--- a/y2019/BUILD
+++ b/y2019/BUILD
@@ -50,8 +50,9 @@
         "//y2019/control_loops/superstructure/stilts:stilts_plants",
         "//y2019/control_loops/superstructure/wrist:wrist_plants",
         "//y2019/vision:constants",
-        "@com_github_google_glog//:glog",
         "@com_google_absl//absl/base",
+        "@com_google_absl//absl/log",
+        "@com_google_absl//absl/log:check",
     ],
 )
 
diff --git a/y2019/constants.cc b/y2019/constants.cc
index 26188de..e88fb54 100644
--- a/y2019/constants.cc
+++ b/y2019/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/y2019/control_loops/drivetrain/BUILD b/y2019/control_loops/drivetrain/BUILD
index 71bd0ee..9c45c1f 100644
--- a/y2019/control_loops/drivetrain/BUILD
+++ b/y2019/control_loops/drivetrain/BUILD
@@ -200,7 +200,7 @@
         "//frc971/control_loops/drivetrain:splinedrivetrain",
         "//frc971/control_loops/drivetrain:trajectory",
         "//y2019:constants",
-        "@com_github_gflags_gflags//:gflags",
+        "@com_google_absl//absl/flags:flag",
     ] + cpu_select({
         "amd64": [
             "//third_party/matplotlib-cpp",
@@ -254,7 +254,8 @@
         "//aos/events/logging:log_reader",
         "//aos/events/logging:log_writer",
         "//frc971/control_loops/drivetrain:drivetrain_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/y2019/control_loops/drivetrain/drivetrain_replay.cc b/y2019/control_loops/drivetrain/drivetrain_replay.cc
index d9d928c..fa1c589 100644
--- a/y2019/control_loops/drivetrain/drivetrain_replay.cc
+++ b/y2019/control_loops/drivetrain/drivetrain_replay.cc
@@ -1,6 +1,6 @@
 #include <iostream>
 
-#include "gflags/gflags.h"
+#include "absl/flags/flag.h"
 
 #include "aos/configuration.h"
 #include "aos/events/logging/log_reader.h"
@@ -13,22 +13,24 @@
 #include "y2019/control_loops/drivetrain/drivetrain_base.h"
 #include "y2019/control_loops/drivetrain/event_loop_localizer.h"
 
-DEFINE_string(logfile, "/tmp/logfile.bfbs",
-              "Name of the logfile to read from.");
-DEFINE_string(config, "y2019/aos_config.json",
-              "Name of the config file to replay using.");
-DEFINE_string(output_file, "/tmp/replayed",
-              "Name of the logfile to write replayed data to.");
-DEFINE_int32(team, 971, "Team number to use for logfile replay.");
+ABSL_FLAG(std::string, logfile, "/tmp/logfile.bfbs",
+          "Name of the logfile to read from.");
+ABSL_FLAG(std::string, config, "y2019/aos_config.json",
+          "Name of the config file to replay using.");
+ABSL_FLAG(std::string, output_file, "/tmp/replayed",
+          "Name of the logfile to write replayed data to.");
+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));
 
   const aos::FlatbufferDetachedBuffer<aos::Configuration> config =
-      aos::configuration::ReadConfig(FLAGS_config);
+      aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
 
-  aos::logger::LogReader reader(FLAGS_logfile, &config.message());
+  aos::logger::LogReader reader(absl::GetFlag(FLAGS_logfile),
+                                &config.message());
   // TODO(james): Actually enforce not sending on the same buses as the logfile
   // spews out.
   reader.RemapLoggedChannel("/drivetrain",
@@ -43,7 +45,7 @@
   log_writer_event_loop->SkipAosLog();
   CHECK(nullptr == log_writer_event_loop->node());
   aos::logger::Logger writer(log_writer_event_loop.get());
-  writer.StartLoggingOnRun(FLAGS_output_file);
+  writer.StartLoggingOnRun(absl::GetFlag(FLAGS_output_file));
 
   std::unique_ptr<aos::EventLoop> drivetrain_event_loop =
       reader.event_loop_factory()->MakeEventLoop("drivetrain");
diff --git a/y2019/control_loops/drivetrain/localizer_test.cc b/y2019/control_loops/drivetrain/localizer_test.cc
index 278b958a..b92c466 100644
--- a/y2019/control_loops/drivetrain/localizer_test.cc
+++ b/y2019/control_loops/drivetrain/localizer_test.cc
@@ -3,7 +3,7 @@
 #include <queue>
 #include <random>
 
-#include "gflags/gflags.h"
+#include "absl/flags/flag.h"
 
 #include "aos/testing/random_seed.h"
 #include "aos/testing/test_shm.h"
@@ -17,7 +17,7 @@
 #include "y2019/constants.h"
 #include "y2019/control_loops/drivetrain/drivetrain_base.h"
 
-DEFINE_bool(plot, false, "If true, plot");
+ABSL_FLAG(bool, plot, false, "If true, plot");
 
 namespace y2019::control_loops::testing {
 
@@ -210,7 +210,7 @@
     printf("Each iteration of the simulation took on average %f seconds.\n",
            avg_time_.count());
 #if defined(SUPPORT_PLOT)
-    if (FLAGS_plot) {
+    if (absl::GetFlag(FLAGS_plot)) {
       matplotlibcpp::figure();
       matplotlibcpp::plot(simulation_t_, simulation_vl_, {{"label", "Vl"}});
       matplotlibcpp::plot(simulation_t_, simulation_vr_, {{"label", "Vr"}});
diff --git a/y2019/control_loops/drivetrain/replay_localizer.cc b/y2019/control_loops/drivetrain/replay_localizer.cc
index 80cf221..2e7591a 100644
--- a/y2019/control_loops/drivetrain/replay_localizer.cc
+++ b/y2019/control_loops/drivetrain/replay_localizer.cc
@@ -1,6 +1,6 @@
 #include <fcntl.h>
 
-#include "gflags/gflags.h"
+#include "absl/flags/flag.h"
 
 #include "aos/init.h"
 #include "aos/logging/implementations.h"
@@ -17,13 +17,13 @@
 #include "third_party/matplotlib-cpp/matplotlibcpp.h"
 #endif
 
-DEFINE_string(logfile, "", "Path to the logfile to replay.");
+ABSL_FLAG(std::string, logfile, "", "Path to the logfile to replay.");
 // TODO(james): Figure out how to reliably source team number from logfile.
-DEFINE_int32(team, 971, "Team number to use for logfile replay.");
-DEFINE_int32(plot_duration, 30,
-             "Duration, in seconds, to plot after the start time.");
-DEFINE_int32(start_offset, 0,
-             "Time, in seconds, to start replay plot after the first enable.");
+ABSL_FLAG(int32_t, team, 971, "Team number to use for logfile replay.");
+ABSL_FLAG(int32_t, plot_duration, 30,
+          "Duration, in seconds, to plot after the start time.");
+ABSL_FLAG(int32_t, start_offset, 0,
+          "Time, in seconds, to start replay plot after the first enable.");
 
 namespace y2019::control_loops::drivetrain {
 using ::y2019::constants::Field;
diff --git a/y2019/control_loops/drivetrain/trajectory_generator_main.cc b/y2019/control_loops/drivetrain/trajectory_generator_main.cc
index 8f18222..4219d8d 100644
--- a/y2019/control_loops/drivetrain/trajectory_generator_main.cc
+++ b/y2019/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, ::y2019::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/y2019/control_loops/superstructure/superstructure_lib_test.cc b/y2019/control_loops/superstructure/superstructure_lib_test.cc
index c2bf988..ec32d05 100644
--- a/y2019/control_loops/superstructure/superstructure_lib_test.cc
+++ b/y2019/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 "frc971/control_loops/capped_test_plant.h"
diff --git a/y2019/image_streamer/BUILD b/y2019/image_streamer/BUILD
index 5e49ebb..c4f7a6b 100644
--- a/y2019/image_streamer/BUILD
+++ b/y2019/image_streamer/BUILD
@@ -8,6 +8,7 @@
     target_compatible_with = ["@platforms//os:linux"],
     deps = [
         ":flip_image",
+        "//aos:init",
         "//aos/logging",
         "//aos/vision/blob:codec",
         "//aos/vision/events:epoll_events",
@@ -16,7 +17,7 @@
         "//aos/vision/image:image_stream",
         "//aos/vision/image:reader",
         "//y2019:vision_proto",
-        "@com_github_gflags_gflags//:gflags",
+        "@com_google_absl//absl/flags:flag",
     ],
 )
 
diff --git a/y2019/image_streamer/image_streamer.cc b/y2019/image_streamer/image_streamer.cc
index cbb4788..07acd6e 100644
--- a/y2019/image_streamer/image_streamer.cc
+++ b/y2019/image_streamer/image_streamer.cc
@@ -4,8 +4,9 @@
 #include <fstream>
 #include <string>
 
-#include "gflags/gflags.h"
+#include "absl/flags/flag.h"
 
+#include "aos/init.h"
 #include "aos/logging/implementations.h"
 #include "aos/logging/logging.h"
 #include "aos/vision/blob/codec.h"
@@ -24,13 +25,13 @@
 using ::aos::vision::Int32Codec;
 using ::y2019::VisionControl;
 
-DEFINE_string(roborio_ip, "10.9.71.2", "RoboRIO IP Address");
-DEFINE_string(log, "",
-              "If non-empty, log images to the specified prefix with the image "
-              "index appended to the filename");
-DEFINE_bool(single_camera, true, "If true, only use video0");
-DEFINE_int32(camera0_exposure, 600, "Exposure for video0");
-DEFINE_int32(camera1_exposure, 600, "Exposure for video1");
+ABSL_FLAG(std::string, roborio_ip, "10.9.71.2", "RoboRIO IP Address");
+ABSL_FLAG(std::string, log, "",
+          "If non-empty, log images to the specified prefix with the image "
+          "index appended to the filename");
+ABSL_FLAG(bool, single_camera, true, "If true, only use video0");
+ABSL_FLAG(int32_t, camera0_exposure, 600, "Exposure for video0");
+ABSL_FLAG(int32_t, camera1_exposure, 600, "Exposure for video1");
 
 aos::vision::DataRef mjpg_header =
     "HTTP/1.0 200 OK\r\n"
@@ -252,7 +253,7 @@
         tcp_server_(tcp_server),
         frame_callback_(frame_callback) {
     if (log) {
-      log_.reset(new BlobLog(FLAGS_log.c_str(), ".dat"));
+      log_.reset(new BlobLog(absl::GetFlag(FLAGS_log).c_str(), ".dat"));
     }
   }
 
@@ -307,30 +308,31 @@
 };
 
 int main(int argc, char **argv) {
-  gflags::ParseCommandLineFlags(&argc, &argv, false);
+  aos::InitGoogle(&argc, &argv);
+
   TCPServer<MjpegDataSocket> tcp_server_(80);
   aos::vision::CameraParams params0;
-  params0.set_exposure(FLAGS_camera0_exposure);
+  params0.set_exposure(absl::GetFlag(FLAGS_camera0_exposure));
   params0.set_brightness(-40);
   params0.set_width(320);
   // params0.set_fps(10);
   params0.set_height(240);
 
   aos::vision::CameraParams params1 = params0;
-  params1.set_exposure(FLAGS_camera1_exposure);
+  params1.set_exposure(absl::GetFlag(FLAGS_camera1_exposure));
 
   ::y2019::VisionStatus vision_status;
   AOS_LOG(INFO,
           "The UDP socket should be on port 5001 to 10.9.71.2 for "
           "the competition robot.\n");
   AOS_LOG(INFO, "Starting UDP socket on port 5001 to %s\n",
-          FLAGS_roborio_ip.c_str());
+          absl::GetFlag(FLAGS_roborio_ip).c_str());
   ::aos::events::ProtoTXUdpSocket<::y2019::VisionStatus> status_socket(
-      FLAGS_roborio_ip.c_str(), 5001);
+      absl::GetFlag(FLAGS_roborio_ip).c_str(), 5001);
 
   ::std::unique_ptr<CameraStream> camera1;
   ::std::unique_ptr<CameraStream> camera0(new CameraStream(
-      params0, "/dev/video0", &tcp_server_, !FLAGS_log.empty(),
+      params0, "/dev/video0", &tcp_server_, !absl::GetFlag(FLAGS_log).empty(),
       [&camera0, &status_socket, &vision_status]() {
         vision_status.set_low_frame_count(vision_status.low_frame_count() + 1);
         AOS_LOG(INFO, "Got a frame cam0\n");
@@ -338,7 +340,7 @@
           status_socket.Send(vision_status);
         }
       }));
-  if (!FLAGS_single_camera) {
+  if (!absl::GetFlag(FLAGS_single_camera)) {
     camera1.reset(new CameraStream(
         params1, "/dev/video1", &tcp_server_, false,
         [&camera1, &status_socket, &vision_status]() {
diff --git a/y2019/jevois/camera/BUILD b/y2019/jevois/camera/BUILD
index 6bd2b99..930571f 100644
--- a/y2019/jevois/camera/BUILD
+++ b/y2019/jevois/camera/BUILD
@@ -10,7 +10,8 @@
         "//aos/vision/image:camera_params",
         "//aos/vision/image:image_types",
         "//aos/vision/image:reader",
-        "@com_github_google_glog//:glog",
+        "@com_google_absl//absl/log",
+        "@com_google_absl//absl/log:check",
     ],
 )
 
diff --git a/y2019/jevois/camera/reader.cc b/y2019/jevois/camera/reader.cc
index 09e07db..57e0a26 100644
--- a/y2019/jevois/camera/reader.cc
+++ b/y2019/jevois/camera/reader.cc
@@ -13,7 +13,8 @@
 #include <cstdlib>
 #include <cstring>
 
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
 
 #include "aos/time/time.h"
 
diff --git a/y2019/vision/BUILD b/y2019/vision/BUILD
index 78298a1..af6da5b 100644
--- a/y2019/vision/BUILD
+++ b/y2019/vision/BUILD
@@ -40,7 +40,8 @@
     target_compatible_with = ["@platforms//os:linux"],
     deps = [
         "//aos/vision/image:image_types",
-        "@com_github_google_glog//:glog",
+        "@com_google_absl//absl/log",
+        "@com_google_absl//absl/log:check",
     ],
 )
 
@@ -94,7 +95,7 @@
         "//aos/vision/blob:transpose",
         "//aos/vision/debug:debug_framework",
         "//aos/vision/math:vector",
-        "@com_github_gflags_gflags//:gflags",
+        "@com_google_absl//absl/flags:flag",
     ],
 )
 
@@ -105,6 +106,7 @@
     deps = [
         ":image_writer",
         ":target_finder",
+        "//aos:init",
         "//aos/vision/blob:codec",
         "//aos/vision/blob:find_blob",
         "//aos/vision/events:epoll_events",
@@ -115,7 +117,8 @@
         "//y2019/jevois:uart",
         "//y2019/jevois/camera:image_stream",
         "//y2019/jevois/camera:reader",
-        "@com_github_google_glog//:glog",
+        "@com_google_absl//absl/log",
+        "@com_google_absl//absl/log:check",
         "@com_google_ceres_solver//:ceres",
     ],
 )
@@ -150,6 +153,7 @@
     target_compatible_with = VISION_TARGETS,
     deps = [
         ":target_finder",
+        "//aos:init",
         "//aos/logging",
         "//aos/vision/blob:codec",
         "//aos/vision/blob:find_blob",
diff --git a/y2019/vision/debug_viewer.cc b/y2019/vision/debug_viewer.cc
index 1a93f87..31fee54 100644
--- a/y2019/vision/debug_viewer.cc
+++ b/y2019/vision/debug_viewer.cc
@@ -1,6 +1,6 @@
 #include <iostream>
 
-#include "gflags/gflags.h"
+#include "absl/flags/flag.h"
 #include <Eigen/Dense>
 
 #include "aos/vision/blob/move_scale.h"
@@ -19,7 +19,7 @@
 using aos::vision::Segment;
 using aos::vision::Vector;
 
-DEFINE_int32(camera, 10, "The camera to use the intrinsics for");
+ABSL_FLAG(int32_t, camera, 10, "The camera to use the intrinsics for");
 
 namespace y2019::vision {
 
diff --git a/y2019/vision/global_calibration.cc b/y2019/vision/global_calibration.cc
index bb3259e..b502f3b 100644
--- a/y2019/vision/global_calibration.cc
+++ b/y2019/vision/global_calibration.cc
@@ -1,5 +1,8 @@
 #include <fstream>
 
+#include "absl/flags/flag.h"
+
+#include "aos/init.h"
 #include "aos/logging/implementations.h"
 #include "aos/logging/logging.h"
 #include "aos/vision/blob/codec.h"
@@ -14,28 +17,26 @@
 // CERES Clashes with logging symbols...
 #include "ceres/ceres.h"
 
-DEFINE_int32(camera_id, -1, "The camera ID to calibrate");
-DEFINE_string(prefix, "", "The image filename prefix");
+ABSL_FLAG(int32_t, camera_id, -1, "The camera ID to calibrate");
+ABSL_FLAG(std::string, prefix, "", "The image filename prefix");
 
-DEFINE_string(constants, "y2019/vision/constants.cc",
-              "Path to the constants file to update");
+ABSL_FLAG(std::string, constants, "y2019/vision/constants.cc",
+          "Path to the constants file to update");
 
-DEFINE_double(beginning_tape_measure_reading, 11,
-              "The tape measure measurement (in inches) of the first image.");
-DEFINE_int32(image_count, 75, "The number of images to capture");
-DEFINE_double(tape_start_x, -12.5,
-              "The starting location of the tape measure in x relative to the "
-              "CG in inches.");
-DEFINE_double(tape_start_y, -0.5,
-              "The starting location of the tape measure in y relative to the "
-              "CG in inches.");
+ABSL_FLAG(double, beginning_tape_measure_reading, 11,
+          "The tape measure measurement (in inches) of the first image.");
+ABSL_FLAG(int32_t, image_count, 75, "The number of images to capture");
+ABSL_FLAG(double, tape_start_x, -12.5,
+          "The starting location of the tape measure in x relative to the "
+          "CG in inches.");
+ABSL_FLAG(double, tape_start_y, -0.5,
+          "The starting location of the tape measure in y relative to the "
+          "CG in inches.");
 
-DEFINE_double(
-    tape_direction_x, -1.0,
-    "The x component of \"1\" inch along the tape measure in meters.");
-DEFINE_double(
-    tape_direction_y, 0.0,
-    "The y component of \"1\" inch along the tape measure in meters.");
+ABSL_FLAG(double, tape_direction_x, -1.0,
+          "The x component of \"1\" inch along the tape measure in meters.");
+ABSL_FLAG(double, tape_direction_y, 0.0,
+          "The y component of \"1\" inch along the tape measure in meters.");
 
 using ::aos::monotonic_clock;
 using ::aos::events::DataSocket;
@@ -88,17 +89,18 @@
 
 void main(int argc, char **argv) {
   using namespace y2019::vision;
-  ::gflags::ParseCommandLineFlags(&argc, &argv, false);
+  aos::InitGoogle(&argc, &argv);
 
+  std::string prefix = absl::GetFlag(FLAGS_prefix);
   DatasetInfo info = {
-      FLAGS_camera_id,
-      {{FLAGS_tape_start_x * kInchesToMeters,
-        FLAGS_tape_start_y * kInchesToMeters}},
-      {{FLAGS_tape_direction_x * kInchesToMeters,
-        FLAGS_tape_direction_y * kInchesToMeters}},
-      FLAGS_beginning_tape_measure_reading,
-      FLAGS_prefix.c_str(),
-      FLAGS_image_count,
+      absl::GetFlag(FLAGS_camera_id),
+      {{absl::GetFlag(FLAGS_tape_start_x) * kInchesToMeters,
+        absl::GetFlag(FLAGS_tape_start_y) * kInchesToMeters}},
+      {{absl::GetFlag(FLAGS_tape_direction_x) * kInchesToMeters,
+        absl::GetFlag(FLAGS_tape_direction_y) * kInchesToMeters}},
+      absl::GetFlag(FLAGS_beginning_tape_measure_reading),
+      prefix.c_str(),
+      absl::GetFlag(FLAGS_image_count),
   };
 
   TargetFinder target_finder;
@@ -140,8 +142,8 @@
   ::std::cout << "error = " << summary.final_cost << ";\n";
 
   for (int i = 0; i < info.num_images; ++i) {
-    ::aos::vision::DatasetFrame frame =
-        aos::vision::LoadFile(FLAGS_prefix + std::to_string(i) + ".yuyv");
+    ::aos::vision::DatasetFrame frame = aos::vision::LoadFile(
+        absl::GetFlag(FLAGS_prefix) + std::to_string(i) + ".yuyv");
 
     const ::aos::vision::ImageFormat fmt{640, 480};
     ::aos::vision::BlobList imgs =
@@ -289,7 +291,8 @@
   results.dataset = info;
   results.intrinsics = IntrinsicParams::get(&intrinsics[0]);
   results.geometry = CameraGeometry::get(&geometry[0]);
-  DumpCameraConstants(FLAGS_constants.c_str(), info.camera_id, results);
+  DumpCameraConstants(absl::GetFlag(FLAGS_constants).c_str(), info.camera_id,
+                      results);
 }
 
 }  // namespace y2019::vision
diff --git a/y2019/vision/image_writer.cc b/y2019/vision/image_writer.cc
index 9b73a81..18b8cae 100644
--- a/y2019/vision/image_writer.cc
+++ b/y2019/vision/image_writer.cc
@@ -4,7 +4,8 @@
 
 #include <fstream>
 
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
 
 namespace y2019::vision {
 
diff --git a/y2019/vision/target_sender.cc b/y2019/vision/target_sender.cc
index 650693c..6be52a5 100644
--- a/y2019/vision/target_sender.cc
+++ b/y2019/vision/target_sender.cc
@@ -4,6 +4,7 @@
 #include <random>
 #include <thread>
 
+#include "aos/init.h"
 #include "aos/vision/blob/codec.h"
 #include "aos/vision/blob/find_blob.h"
 #include "aos/vision/events/socket_types.h"
@@ -18,7 +19,8 @@
 
 // This has to be last to preserve compatibility with other headers using AOS
 // logging.
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
 
 using ::aos::monotonic_clock;
 using ::aos::events::DataSocket;
@@ -162,13 +164,9 @@
 }
 
 int main(int argc, char **argv) {
-  (void)argc;
-  (void)argv;
   using namespace y2019::vision;
   using frc971::jevois::CameraCommand;
-  // gflags::ParseCommandLineFlags(&argc, &argv, false);
-  FLAGS_logtostderr = true;
-  google::InitGoogleLogging(argv[0]);
+  aos::InitGoogle(&argc, &argv);
 
   int itsDev = open_terminos("/dev/ttyS0");
   frc971::jevois::CobsPacketizer<frc971::jevois::uart_to_camera_size()> cobs;