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/frc971/analysis/pdp_values.cc b/frc971/analysis/pdp_values.cc
index b314cc6..15b29b2 100644
--- a/frc971/analysis/pdp_values.cc
+++ b/frc971/analysis/pdp_values.cc
@@ -1,14 +1,15 @@
#include <fstream>
-#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/logging/log_reader.h"
#include "aos/events/simulated_event_loop.h"
#include "aos/init.h"
#include "frc971/wpilib/pdp_values_generated.h"
-DEFINE_string(output_path, "/tmp/pdp_values.csv", "");
+ABSL_FLAG(std::string, output_path, "/tmp/pdp_values.csv", "");
int main(int argc, char **argv) {
aos::InitGoogle(&argc, &argv);
@@ -27,7 +28,7 @@
event_loop_factory.MakeEventLoop("roborio", roborio);
std::ofstream file_stream;
- file_stream.open(FLAGS_output_path);
+ file_stream.open(absl::GetFlag(FLAGS_output_path));
file_stream << "timestamp,currents,voltage\n";
event_loop->SkipAosLog();
diff --git a/frc971/analysis/trim_log_to_enabled.cc b/frc971/analysis/trim_log_to_enabled.cc
index fb6b0c6..a92d74e 100644
--- a/frc971/analysis/trim_log_to_enabled.cc
+++ b/frc971/analysis/trim_log_to_enabled.cc
@@ -1,31 +1,34 @@
#include <optional>
-#include "gflags/gflags.h"
+#include "absl/flags/flag.h"
+#include "absl/flags/usage.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/events/logging/log_reader.h"
#include "aos/init.h"
#include "aos/util/simulation_logger.h"
#include "frc971/input/joystick_state_generated.h"
-DEFINE_string(output_folder, "/tmp/trimmed/",
- "Name of the folder to write the trimmed log to.");
-DEFINE_string(node, "roborio", "");
-DEFINE_bool(auto, false, "If set, trim the log to just the auto mode.");
-DEFINE_double(pre_enable_time_sec, 10.0,
- "Amount of time to leave in the new log before the first enable "
- "signal happens.");
-DEFINE_double(post_enable_time_sec, 1.0,
- "Amount of time to leave in the new log after the final enable "
- "signal ends.");
-DEFINE_double(force_start_monotonic, -1.0,
- "If set, time, in seconds, at which to forcibly trim the start "
- "of the log.");
-DEFINE_double(
- force_end_monotonic, -1.0,
+ABSL_FLAG(std::string, output_folder, "/tmp/trimmed/",
+ "Name of the folder to write the trimmed log to.");
+ABSL_FLAG(std::string, node, "roborio", "");
+ABSL_FLAG(bool, auto, false, "If set, trim the log to just the auto mode.");
+ABSL_FLAG(double, pre_enable_time_sec, 10.0,
+ "Amount of time to leave in the new log before the first enable "
+ "signal happens.");
+ABSL_FLAG(double, post_enable_time_sec, 1.0,
+ "Amount of time to leave in the new log after the final enable "
+ "signal ends.");
+ABSL_FLAG(double, force_start_monotonic, -1.0,
+ "If set, time, in seconds, at which to forcibly trim the start "
+ "of the log.");
+ABSL_FLAG(
+ double, force_end_monotonic, -1.0,
"If set, time, in seconds, at which to forcibly trim the end of the log.");
int main(int argc, char *argv[]) {
- gflags::SetUsageMessage(
+ absl::SetProgramUsageMessage(
"Trims the sections at the start/end of a log where the robot is "
"disabled.");
aos::InitGoogle(&argc, &argv);
@@ -34,35 +37,35 @@
std::optional<aos::monotonic_clock::time_point> start_time;
std::optional<aos::monotonic_clock::time_point> end_time;
bool printed_match = false;
- bool force_time_range = FLAGS_force_start_monotonic > 0;
+ bool force_time_range = absl::GetFlag(FLAGS_force_start_monotonic) > 0;
// We need to do two passes through the logfile; one to figure out when the
// start/end times are, one to actually do the trimming.
if (!force_time_range) {
aos::logger::LogReader reader(logfiles);
- const aos::Node *roborio =
- aos::configuration::GetNode(reader.configuration(), FLAGS_node);
+ const aos::Node *roborio = aos::configuration::GetNode(
+ reader.configuration(), absl::GetFlag(FLAGS_node));
reader.Register();
std::unique_ptr<aos::EventLoop> event_loop =
- reader.event_loop_factory()->MakeEventLoop(FLAGS_node, roborio);
- event_loop->MakeWatcher(
- "/aos", [&start_time, &end_time, &printed_match,
- &event_loop](const aos::JoystickState &msg) {
- if (!printed_match && msg.match_type() != aos::MatchType::kNone) {
- LOG(INFO) << "Match Type: "
- << aos::EnumNameMatchType(msg.match_type());
- LOG(INFO) << "Match #: " << msg.match_number();
- printed_match = true;
- }
+ reader.event_loop_factory()->MakeEventLoop(absl::GetFlag(FLAGS_node),
+ roborio);
+ event_loop->MakeWatcher("/aos", [&start_time, &end_time, &printed_match,
+ &event_loop](
+ const aos::JoystickState &msg) {
+ if (!printed_match && msg.match_type() != aos::MatchType::kNone) {
+ LOG(INFO) << "Match Type: " << aos::EnumNameMatchType(msg.match_type());
+ LOG(INFO) << "Match #: " << msg.match_number();
+ printed_match = true;
+ }
- if (msg.enabled() && (!FLAGS_auto || msg.autonomous())) {
- // Note that time is monotonic, so we don't need to e.g. do min's or
- // max's on the start/end time.
- if (!start_time.has_value()) {
- start_time = event_loop->context().monotonic_event_time;
- }
- end_time = event_loop->context().monotonic_event_time;
- }
- });
+ if (msg.enabled() && (!absl::GetFlag(FLAGS_auto) || msg.autonomous())) {
+ // Note that time is monotonic, so we don't need to e.g. do min's or
+ // max's on the start/end time.
+ if (!start_time.has_value()) {
+ start_time = event_loop->context().monotonic_event_time;
+ }
+ end_time = event_loop->context().monotonic_event_time;
+ }
+ });
reader.event_loop_factory()->Run();
@@ -76,26 +79,32 @@
LOG(INFO) << "First enable at " << start_time.value();
LOG(INFO) << "Final enable at " << end_time.value();
start_time.value() -= std::chrono::duration_cast<std::chrono::nanoseconds>(
- std::chrono::duration<double>(FLAGS_pre_enable_time_sec));
+ std::chrono::duration<double>(
+ absl::GetFlag(FLAGS_pre_enable_time_sec)));
end_time.value() += std::chrono::duration_cast<std::chrono::nanoseconds>(
- std::chrono::duration<double>(FLAGS_post_enable_time_sec));
+ std::chrono::duration<double>(
+ absl::GetFlag(FLAGS_post_enable_time_sec)));
} else {
- CHECK_LT(FLAGS_force_start_monotonic, FLAGS_force_end_monotonic);
+ CHECK_LT(absl::GetFlag(FLAGS_force_start_monotonic),
+ absl::GetFlag(FLAGS_force_end_monotonic));
start_time = aos::monotonic_clock::time_point(
std::chrono::duration_cast<std::chrono::nanoseconds>(
- std::chrono::duration<double>(FLAGS_force_start_monotonic)));
+ std::chrono::duration<double>(
+ absl::GetFlag(FLAGS_force_start_monotonic))));
end_time = aos::monotonic_clock::time_point(
std::chrono::duration_cast<std::chrono::nanoseconds>(
- std::chrono::duration<double>(FLAGS_force_end_monotonic)));
+ std::chrono::duration<double>(
+ absl::GetFlag(FLAGS_force_end_monotonic))));
}
{
aos::logger::LogReader reader(logfiles);
- const aos::Node *roborio =
- aos::configuration::GetNode(reader.configuration(), FLAGS_node);
+ const aos::Node *roborio = aos::configuration::GetNode(
+ reader.configuration(), absl::GetFlag(FLAGS_node));
reader.Register();
std::unique_ptr<aos::EventLoop> event_loop =
- reader.event_loop_factory()->MakeEventLoop(FLAGS_node, roborio);
+ reader.event_loop_factory()->MakeEventLoop(absl::GetFlag(FLAGS_node),
+ roborio);
auto exit_timer = event_loop->AddTimer(
[&reader]() { reader.event_loop_factory()->Exit(); });
exit_timer->Schedule(start_time.value());
@@ -107,13 +116,13 @@
// easily auto-detect which node to replay as when consuming the input logs.
auto loggers = aos::util::MakeLoggersForNodes(
reader.event_loop_factory(), {logger_nodes.begin(), logger_nodes.end()},
- FLAGS_output_folder);
+ absl::GetFlag(FLAGS_output_folder));
exit_timer->Schedule(end_time.value());
reader.event_loop_factory()->Run();
}
- LOG(INFO) << "Trimmed logs written to " << FLAGS_output_folder;
+ LOG(INFO) << "Trimmed logs written to " << absl::GetFlag(FLAGS_output_folder);
return EXIT_SUCCESS;
}
diff --git a/frc971/can_logger/BUILD b/frc971/can_logger/BUILD
index 7c4a319..f72f085 100644
--- a/frc971/can_logger/BUILD
+++ b/frc971/can_logger/BUILD
@@ -11,7 +11,8 @@
"//aos:init",
"//aos/events:shm_event_loop",
"//aos/time",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
)
@@ -26,7 +27,8 @@
":can_logging_fbs",
"//aos/events:shm_event_loop",
"//aos/scoped:scoped_fd",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
)
@@ -51,7 +53,8 @@
"//aos:init",
"//aos/events/logging:log_reader",
"//aos/time",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
)
@@ -67,6 +70,7 @@
":can_logging_fbs",
"//aos/events:event_loop",
"//aos/scoped:scoped_fd",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
)
diff --git a/frc971/can_logger/asc_logger.h b/frc971/can_logger/asc_logger.h
index e7d4e74..7ac8b5b 100644
--- a/frc971/can_logger/asc_logger.h
+++ b/frc971/can_logger/asc_logger.h
@@ -4,8 +4,9 @@
#include <iomanip>
#include <iostream>
-#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/event_loop.h"
#include "frc971/can_logger/can_logging_generated.h"
diff --git a/frc971/can_logger/can_logger.cc b/frc971/can_logger/can_logger.cc
index d020f6a..d350672 100644
--- a/frc971/can_logger/can_logger.cc
+++ b/frc971/can_logger/can_logger.cc
@@ -1,12 +1,14 @@
#include "frc971/can_logger/can_logger.h"
-DEFINE_bool(poll, false,
- "If true, poll the CAN bus every 100ms. If false, wake up for "
- "each frame and publish it.");
+#include "absl/flags/flag.h"
-DEFINE_int32(priority, 10,
- "If --poll is not set, set the realtime priority to this.");
-DEFINE_int32(affinity, -1, "If positive, pin to this core.");
+ABSL_FLAG(bool, poll, false,
+ "If true, poll the CAN bus every 100ms. If false, wake up for "
+ "each frame and publish it.");
+
+ABSL_FLAG(int32_t, priority, 10,
+ "If --poll is not set, set the realtime priority to this.");
+ABSL_FLAG(int32_t, affinity, -1, "If positive, pin to this core.");
namespace frc971::can_logger {
@@ -17,12 +19,12 @@
fd_(socket(PF_CAN, SOCK_RAW | SOCK_NONBLOCK, CAN_RAW)),
frames_sender_(shm_event_loop_->MakeSender<CanFrame>(channel_name)) {
// TODO(max): Figure out a proper priority
- if (!FLAGS_poll) {
- shm_event_loop_->SetRuntimeRealtimePriority(FLAGS_priority);
+ if (!absl::GetFlag(FLAGS_poll)) {
+ shm_event_loop_->SetRuntimeRealtimePriority(absl::GetFlag(FLAGS_priority));
}
- if (FLAGS_affinity >= 0) {
+ if (absl::GetFlag(FLAGS_affinity) >= 0) {
shm_event_loop_->SetRuntimeAffinity(
- aos::MakeCpusetFromCpus({FLAGS_affinity}));
+ aos::MakeCpusetFromCpus({absl::GetFlag(FLAGS_affinity)}));
}
struct ifreq ifr;
strcpy(ifr.ifr_name, interface_name.data());
@@ -49,7 +51,7 @@
CHECK_EQ(opt_size, sizeof(recieve_buffer_size));
VLOG(0) << "CAN recieve bufffer is " << recieve_buffer_size << " bytes large";
- if (FLAGS_poll) {
+ if (absl::GetFlag(FLAGS_poll)) {
aos::TimerHandler *timer_handler =
shm_event_loop_->AddTimer([this]() { Poll(); });
timer_handler->set_name("CAN logging Loop");
diff --git a/frc971/can_logger/log_to_asc.cc b/frc971/can_logger/log_to_asc.cc
index 73ddd4e..38c09af 100644
--- a/frc971/can_logger/log_to_asc.cc
+++ b/frc971/can_logger/log_to_asc.cc
@@ -5,8 +5,8 @@
#include "frc971/can_logger/asc_logger.h"
#include "frc971/can_logger/can_logging_generated.h"
-DEFINE_string(node, "", "Node to replay from the perspective of.");
-DEFINE_string(output_path, "/tmp/can_log.asc", "Log to output.");
+ABSL_FLAG(std::string, node, "", "Node to replay from the perspective of.");
+ABSL_FLAG(std::string, output_path, "/tmp/can_log.asc", "Log to output.");
int main(int argc, char *argv[]) {
aos::InitGoogle(&argc, &argv);
@@ -22,7 +22,7 @@
break;
}
}
- std::string replay_node = FLAGS_node;
+ std::string replay_node = absl::GetFlag(FLAGS_node);
if (replay_node.empty() && all_logs_from_same_node) {
LOG(INFO) << "Guessing \"" << logger_node
<< "\" as node given that --node was not specified.";
@@ -43,14 +43,14 @@
: aos::configuration::GetNode(reader.configuration(), replay_node);
std::unique_ptr<aos::EventLoop> can_event_loop;
- CHECK(!FLAGS_output_path.empty());
+ CHECK(!absl::GetFlag(FLAGS_output_path).empty());
std::unique_ptr<frc971::can_logger::AscLogger> relogger;
factory.GetNodeEventLoopFactory(node)->OnStartup([&relogger, &can_event_loop,
&reader, node]() {
can_event_loop = reader.event_loop_factory()->MakeEventLoop("can", node);
relogger = std::make_unique<frc971::can_logger::AscLogger>(
- can_event_loop.get(), FLAGS_output_path);
+ can_event_loop.get(), absl::GetFlag(FLAGS_output_path));
});
reader.event_loop_factory()->Run();
reader.Deregister();
diff --git a/frc971/constants/BUILD b/frc971/constants/BUILD
index 3a7e73a..57cae2e 100644
--- a/frc971/constants/BUILD
+++ b/frc971/constants/BUILD
@@ -11,8 +11,9 @@
"//aos/events:event_loop",
"//aos/events:shm_event_loop",
"//aos/network:team_number",
- "@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",
],
)
@@ -33,8 +34,9 @@
"//frc971/constants:constants_sender_lib",
"//frc971/constants/testdata:constants_data_fbs",
"//frc971/constants/testdata:constants_list_fbs",
- "@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",
],
)
@@ -61,6 +63,7 @@
"//aos/testing:path",
"//frc971/constants/testdata:constants_data_fbs",
"//frc971/constants/testdata:constants_list_fbs",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
)
diff --git a/frc971/constants/constants_sender_example.cc b/frc971/constants/constants_sender_example.cc
index a0b23ce..2beb9ec 100644
--- a/frc971/constants/constants_sender_example.cc
+++ b/frc971/constants/constants_sender_example.cc
@@ -1,5 +1,6 @@
-#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/configuration.h"
#include "aos/events/shm_event_loop.h"
@@ -9,19 +10,20 @@
#include "frc971/constants/testdata/constants_data_generated.h"
#include "frc971/constants/testdata/constants_list_generated.h"
-DEFINE_string(config, "frc971/constants/testdata/aos_config.json",
- "Path to the config.");
-DEFINE_string(constants_path, "frc971/constants/testdata/test_constants.json",
- "Path to the constant file");
+ABSL_FLAG(std::string, config, "frc971/constants/testdata/aos_config.json",
+ "Path to the config.");
+ABSL_FLAG(std::string, constants_path,
+ "frc971/constants/testdata/test_constants.json",
+ "Path to the constant file");
// This is just a sample binary
int main(int argc, char **argv) {
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::constants::ConstantSender<frc971::constants::testdata::ConstantsData,
frc971::constants::testdata::ConstantsList>
- constants_sender(&event_loop, FLAGS_constants_path);
+ constants_sender(&event_loop, absl::GetFlag(FLAGS_constants_path));
event_loop.Run();
return 0;
diff --git a/frc971/constants/constants_sender_lib.h b/frc971/constants/constants_sender_lib.h
index 203435a..58da8d2 100644
--- a/frc971/constants/constants_sender_lib.h
+++ b/frc971/constants/constants_sender_lib.h
@@ -1,8 +1,9 @@
#ifndef FRC971_CONSTANTS_CONSTANTS_SENDER_H_
#define FRC971_CONSTANTS_CONSTANTS_SENDER_H_
-#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/event_loop.h"
#include "aos/events/shm_event_loop.h"
diff --git a/frc971/constants/constants_sender_test.cc b/frc971/constants/constants_sender_test.cc
index e4920d3..c31499f 100644
--- a/frc971/constants/constants_sender_test.cc
+++ b/frc971/constants/constants_sender_test.cc
@@ -1,4 +1,5 @@
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "gtest/gtest.h"
#include "aos/configuration.h"
diff --git a/frc971/control_loops/BUILD b/frc971/control_loops/BUILD
index ccaac40..785d2c7 100644
--- a/frc971/control_loops/BUILD
+++ b/frc971/control_loops/BUILD
@@ -53,7 +53,8 @@
"@platforms//os:linux": [
"//aos/logging",
"//third_party/cddlib",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
"//conditions:default": [],
}),
@@ -106,7 +107,8 @@
],
target_compatible_with = ["@platforms//os:linux"],
deps = [
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
"@org_tuxfamily_eigen//:eigen",
],
)
@@ -123,7 +125,8 @@
":runge_kutta",
"//aos/testing:googletest",
"//aos/testing:random_seed",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
"@org_tuxfamily_eigen//:eigen",
],
)
@@ -386,7 +389,8 @@
],
target_compatible_with = ["@platforms//os:linux"],
deps = [
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
"@org_tuxfamily_eigen//:eigen",
],
)
diff --git a/frc971/control_loops/aiming/aiming.cc b/frc971/control_loops/aiming/aiming.cc
index 572ed1c..646dc13 100644
--- a/frc971/control_loops/aiming/aiming.cc
+++ b/frc971/control_loops/aiming/aiming.cc
@@ -1,6 +1,7 @@
#include "frc971/control_loops/aiming/aiming.h"
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "frc971/zeroing/wrap.h"
diff --git a/frc971/control_loops/catapult/mpc_problem.h b/frc971/control_loops/catapult/mpc_problem.h
index 04e3936..1cbeb10 100644
--- a/frc971/control_loops/catapult/mpc_problem.h
+++ b/frc971/control_loops/catapult/mpc_problem.h
@@ -1,6 +1,7 @@
#include "Eigen/Dense"
#include "Eigen/Sparse"
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/realtime.h"
#include "aos/time/time.h"
diff --git a/frc971/control_loops/control_loop_test.h b/frc971/control_loops/control_loop_test.h
index 8b6ba09..0b918e2 100644
--- a/frc971/control_loops/control_loop_test.h
+++ b/frc971/control_loops/control_loop_test.h
@@ -4,7 +4,8 @@
#include <chrono>
#include <string_view>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "gtest/gtest.h"
#include "aos/events/simulated_event_loop.h"
diff --git a/frc971/control_loops/double_jointed_arm/BUILD b/frc971/control_loops/double_jointed_arm/BUILD
index c7fcefc..79d464a 100644
--- a/frc971/control_loops/double_jointed_arm/BUILD
+++ b/frc971/control_loops/double_jointed_arm/BUILD
@@ -46,7 +46,7 @@
visibility = ["//visibility:public"],
deps = [
"//frc971/control_loops:runge_kutta",
- "@com_github_gflags_gflags//:gflags",
+ "@com_google_absl//absl/flags:flag",
"@org_tuxfamily_eigen//:eigen",
],
)
diff --git a/frc971/control_loops/double_jointed_arm/dynamics.cc b/frc971/control_loops/double_jointed_arm/dynamics.cc
index 4910e6c..76577ec 100644
--- a/frc971/control_loops/double_jointed_arm/dynamics.cc
+++ b/frc971/control_loops/double_jointed_arm/dynamics.cc
@@ -1,6 +1,6 @@
#include "frc971/control_loops/double_jointed_arm/dynamics.h"
-DEFINE_bool(gravity, true, "If true, enable gravity.");
+ABSL_FLAG(bool, gravity, true, "If true, enable gravity.");
namespace frc971::control_loops::arm {
diff --git a/frc971/control_loops/double_jointed_arm/dynamics.h b/frc971/control_loops/double_jointed_arm/dynamics.h
index c28a20d..7a92105 100644
--- a/frc971/control_loops/double_jointed_arm/dynamics.h
+++ b/frc971/control_loops/double_jointed_arm/dynamics.h
@@ -2,11 +2,12 @@
#define FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_DYNAMICS_H_
#include "Eigen/Dense"
-#include "gflags/gflags.h"
+#include "absl/flags/declare.h"
+#include "absl/flags/flag.h"
#include "frc971/control_loops/runge_kutta.h"
-DECLARE_bool(gravity);
+ABSL_DECLARE_FLAG(bool, gravity);
namespace frc971::control_loops::arm {
@@ -202,7 +203,7 @@
arm_constants_.r1 * arm_constants_.m1 * ::std::sin(X(2)) *
accel_due_to_gravity)
.finished() *
- (FLAGS_gravity ? 1.0 : 0.0);
+ (absl::GetFlag(FLAGS_gravity) ? 1.0 : 0.0);
}
const ::Eigen::Matrix<double, 4, 1> UnboundedDiscreteDynamics(
diff --git a/frc971/control_loops/double_jointed_arm/ekf.cc b/frc971/control_loops/double_jointed_arm/ekf.cc
index b1ae70a..ec63fd1 100644
--- a/frc971/control_loops/double_jointed_arm/ekf.cc
+++ b/frc971/control_loops/double_jointed_arm/ekf.cc
@@ -3,14 +3,15 @@
#include <iostream>
#include "Eigen/Dense"
+#include "absl/flags/flag.h"
#include "frc971/control_loops/double_jointed_arm/dynamics.h"
#include "frc971/control_loops/jacobian.h"
-DEFINE_double(proximal_voltage_error_uncertainty, 8.0,
- "Proximal joint voltage error uncertainty.");
-DEFINE_double(distal_voltage_error_uncertainty, 2.0,
- "Distal joint voltage error uncertainty.");
+ABSL_FLAG(double, proximal_voltage_error_uncertainty, 8.0,
+ "Proximal joint voltage error uncertainty.");
+ABSL_FLAG(double, distal_voltage_error_uncertainty, 2.0,
+ "Distal joint voltage error uncertainty.");
namespace frc971::control_loops::arm {
@@ -21,8 +22,8 @@
::Eigen::Matrix<double, 6, 6> Q_covariance(
(::Eigen::DiagonalMatrix<double, 6>().diagonal() << ::std::pow(0.1, 2),
::std::pow(2.0, 2), ::std::pow(0.1, 2), ::std::pow(2.0, 2),
- ::std::pow(FLAGS_proximal_voltage_error_uncertainty, 2),
- ::std::pow(FLAGS_distal_voltage_error_uncertainty, 2))
+ ::std::pow(absl::GetFlag(FLAGS_proximal_voltage_error_uncertainty), 2),
+ ::std::pow(absl::GetFlag(FLAGS_distal_voltage_error_uncertainty), 2))
.finished()
.asDiagonal());
} // namespace
@@ -32,8 +33,8 @@
Q_covariance =
((::Eigen::DiagonalMatrix<double, 6>().diagonal() << ::std::pow(0.1, 2),
::std::pow(2.0, 2), ::std::pow(0.1, 2), ::std::pow(2.0, 2),
- ::std::pow(FLAGS_proximal_voltage_error_uncertainty, 2),
- ::std::pow(FLAGS_distal_voltage_error_uncertainty, 2))
+ ::std::pow(absl::GetFlag(FLAGS_proximal_voltage_error_uncertainty), 2),
+ ::std::pow(absl::GetFlag(FLAGS_distal_voltage_error_uncertainty), 2))
.finished()
.asDiagonal());
P_ = Q_covariance;
diff --git a/frc971/control_loops/double_jointed_arm/trajectory.cc b/frc971/control_loops/double_jointed_arm/trajectory.cc
index 8b5129d..0eaf67e 100644
--- a/frc971/control_loops/double_jointed_arm/trajectory.cc
+++ b/frc971/control_loops/double_jointed_arm/trajectory.cc
@@ -1,17 +1,17 @@
#include "frc971/control_loops/double_jointed_arm/trajectory.h"
#include "Eigen/Dense"
-#include "gflags/gflags.h"
+#include "absl/flags/flag.h"
#include "aos/logging/logging.h"
#include "frc971/control_loops/dlqr.h"
#include "frc971/control_loops/double_jointed_arm/dynamics.h"
#include "frc971/control_loops/jacobian.h"
-DEFINE_double(lqr_proximal_pos, 0.15, "Position LQR gain");
-DEFINE_double(lqr_proximal_vel, 4.0, "Velocity LQR gain");
-DEFINE_double(lqr_distal_pos, 0.20, "Position LQR gain");
-DEFINE_double(lqr_distal_vel, 4.0, "Velocity LQR gain");
+ABSL_FLAG(double, lqr_proximal_pos, 0.15, "Position LQR gain");
+ABSL_FLAG(double, lqr_proximal_vel, 4.0, "Velocity LQR gain");
+ABSL_FLAG(double, lqr_distal_pos, 0.20, "Position LQR gain");
+ABSL_FLAG(double, lqr_distal_vel, 4.0, "Velocity LQR gain");
namespace frc971::control_loops::arm {
@@ -369,10 +369,10 @@
::Eigen::Matrix<double, 2, 6> TrajectoryFollower::K_at_state(
const ::Eigen::Matrix<double, 6, 1> &X,
const ::Eigen::Matrix<double, 2, 1> &U) {
- const double kProximalPos = FLAGS_lqr_proximal_pos;
- const double kProximalVel = FLAGS_lqr_proximal_vel;
- const double kDistalPos = FLAGS_lqr_distal_pos;
- const double kDistalVel = FLAGS_lqr_distal_vel;
+ const double kProximalPos = absl::GetFlag(FLAGS_lqr_proximal_pos);
+ const double kProximalVel = absl::GetFlag(FLAGS_lqr_proximal_vel);
+ const double kDistalPos = absl::GetFlag(FLAGS_lqr_distal_pos);
+ const double kDistalVel = absl::GetFlag(FLAGS_lqr_distal_vel);
const ::Eigen::DiagonalMatrix<double, 4> Q =
(::Eigen::DiagonalMatrix<double, 4>().diagonal()
<< 1.0 / ::std::pow(kProximalPos, 2),
diff --git a/frc971/control_loops/drivetrain/BUILD b/frc971/control_loops/drivetrain/BUILD
index 800af99..9aca44f 100644
--- a/frc971/control_loops/drivetrain/BUILD
+++ b/frc971/control_loops/drivetrain/BUILD
@@ -330,7 +330,7 @@
"//aos/testing:googletest",
"//aos/testing:test_shm",
"//third_party/matplotlib-cpp",
- "@com_github_gflags_gflags//:gflags",
+ "@com_google_absl//absl/flags:flag",
],
)
@@ -624,7 +624,7 @@
":spline",
"//aos/analysis:in_process_plotter",
"//aos/testing:googletest",
- "@com_github_gflags_gflags//:gflags",
+ "@com_google_absl//absl/flags:flag",
],
)
@@ -640,7 +640,8 @@
"//aos/logging",
"//frc971/control_loops:control_loops_fbs",
"//frc971/control_loops:fixed_quadrature",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
"@com_google_absl//absl/types:span",
"@org_tuxfamily_eigen//:eigen",
],
@@ -665,7 +666,7 @@
"//aos:flatbuffers",
"//aos/testing:googletest",
"//aos/testing:test_shm",
- "@com_github_gflags_gflags//:gflags",
+ "@com_google_absl//absl/flags:flag",
] + cpu_select({
"amd64": [
"//third_party/matplotlib-cpp",
@@ -721,7 +722,7 @@
"//aos/network:team_number",
"//third_party/matplotlib-cpp",
"//y2019/control_loops/drivetrain:drivetrain_base",
- "@com_github_gflags_gflags//:gflags",
+ "@com_google_absl//absl/flags:flag",
"@org_tuxfamily_eigen//:eigen",
],
)
@@ -774,7 +775,8 @@
"//frc971/control_loops:control_loops_fbs",
"//frc971/control_loops:quaternion_utils",
"//frc971/control_loops:runge_kutta",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
"@org_tuxfamily_eigen//:eigen",
],
)
diff --git a/frc971/control_loops/drivetrain/distance_spline.cc b/frc971/control_loops/drivetrain/distance_spline.cc
index 80ef4c4..015aca4 100644
--- a/frc971/control_loops/drivetrain/distance_spline.cc
+++ b/frc971/control_loops/drivetrain/distance_spline.cc
@@ -1,6 +1,7 @@
#include "frc971/control_loops/drivetrain/distance_spline.h"
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/logging/logging.h"
#include "frc971/control_loops/drivetrain/spline.h"
diff --git a/frc971/control_loops/drivetrain/distance_spline_test.cc b/frc971/control_loops/drivetrain/distance_spline_test.cc
index 806d39e..b2e6ac6 100644
--- a/frc971/control_loops/drivetrain/distance_spline_test.cc
+++ b/frc971/control_loops/drivetrain/distance_spline_test.cc
@@ -2,7 +2,7 @@
#include <vector>
-#include "gflags/gflags.h"
+#include "absl/flags/flag.h"
#include "gtest/gtest.h"
#include "aos/flatbuffers.h"
@@ -11,7 +11,7 @@
#include "third_party/matplotlib-cpp/matplotlibcpp.h"
#endif
-DEFINE_bool(plot, false, "If true, plot");
+ABSL_FLAG(bool, plot, false, "If true, plot");
namespace frc971::control_loops::drivetrain::testing {
@@ -78,7 +78,7 @@
#if defined(SUPPORT_PLOT)
// Conditionally plot the functions and their integrals to aid debugging.
- if (FLAGS_plot) {
+ if (absl::GetFlag(FLAGS_plot)) {
matplotlibcpp::figure();
matplotlibcpp::plot(distances_plot, x_plot, {{"label", "x"}});
matplotlibcpp::plot(distances_plot, ix_plot, {{"label", "ix"}});
@@ -138,7 +138,7 @@
#if defined(SUPPORT_PLOT)
// Conditionally plot the functions and their integrals to aid debugging.
- if (FLAGS_plot) {
+ if (absl::GetFlag(FLAGS_plot)) {
matplotlibcpp::figure();
matplotlibcpp::plot(distances_plot, theta_plot, {{"label", "theta"}});
matplotlibcpp::plot(distances_plot, itheta_plot, {{"label", "itheta"}});
diff --git a/frc971/control_loops/drivetrain/drivetrain_lib_test.cc b/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
index c1aa2a5..9cd669d 100644
--- a/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
+++ b/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
@@ -3,7 +3,7 @@
#include <chrono>
#include <memory>
-#include "gflags/gflags.h"
+#include "absl/flags/flag.h"
#include "gmock/gmock.h"
#include "gtest/gtest.h"
@@ -24,8 +24,8 @@
#include "frc971/control_loops/polytope.h"
#include "frc971/queues/gyro_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.");
namespace frc971::control_loops::drivetrain::testing {
@@ -65,11 +65,11 @@
set_send_delay(chrono::nanoseconds(0));
set_battery_voltage(12.0);
- 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");
logger_ = std::make_unique<aos::logger::Logger>(logger_event_loop_.get());
- logger_->StartLoggingOnRun(FLAGS_output_file);
+ logger_->StartLoggingOnRun(absl::GetFlag(FLAGS_output_file));
}
// Run for enough time to allow the gyro/imu zeroing code to run.
diff --git a/frc971/control_loops/drivetrain/drivetrain_test_lib.cc b/frc971/control_loops/drivetrain/drivetrain_test_lib.cc
index 394be07..fc32148 100644
--- a/frc971/control_loops/drivetrain/drivetrain_test_lib.cc
+++ b/frc971/control_loops/drivetrain/drivetrain_test_lib.cc
@@ -2,8 +2,9 @@
#include <chrono>
-#include "gflags/gflags.h"
-#include "glog/logging.h"
+#include "absl/flags/flag.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "gtest/gtest.h"
#include "frc971/control_loops/drivetrain/trajectory.h"
@@ -18,7 +19,7 @@
#include "y2016/control_loops/drivetrain/kalman_drivetrain_motor_plant.h"
#include "y2016/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h"
-DEFINE_bool(plot, false, "If true, plot");
+ABSL_FLAG(bool, plot, false, "If true, plot");
namespace frc971::control_loops::drivetrain::testing {
@@ -137,7 +138,7 @@
// Skip this the first time.
if (!first_) {
Simulate();
- if (FLAGS_plot) {
+ if (absl::GetFlag(FLAGS_plot)) {
EXPECT_TRUE(drivetrain_status_fetcher_.Fetch());
::Eigen::Matrix<double, 2, 1> actual_position = GetPosition();
@@ -368,7 +369,7 @@
void DrivetrainSimulation::MaybePlot() {
#if defined(SUPPORT_PLOT)
- if (FLAGS_plot) {
+ if (absl::GetFlag(FLAGS_plot)) {
std::cout << "Plotting." << ::std::endl;
matplotlibcpp::figure();
matplotlibcpp::plot(actual_x_, actual_y_, {{"label", "actual position"}});
diff --git a/frc971/control_loops/drivetrain/improved_down_estimator.h b/frc971/control_loops/drivetrain/improved_down_estimator.h
index c778ad5..a73d575 100644
--- a/frc971/control_loops/drivetrain/improved_down_estimator.h
+++ b/frc971/control_loops/drivetrain/improved_down_estimator.h
@@ -3,7 +3,8 @@
#include "Eigen/Dense"
#include "Eigen/Geometry"
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/events/event_loop.h"
#include "aos/time/time.h"
diff --git a/frc971/control_loops/drivetrain/improved_down_estimator_test.cc b/frc971/control_loops/drivetrain/improved_down_estimator_test.cc
index c128429..c6cda26 100644
--- a/frc971/control_loops/drivetrain/improved_down_estimator_test.cc
+++ b/frc971/control_loops/drivetrain/improved_down_estimator_test.cc
@@ -2,7 +2,8 @@
#include <random>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "gtest/gtest.h"
#include <Eigen/Geometry>
diff --git a/frc971/control_loops/drivetrain/line_follow_drivetrain_test.cc b/frc971/control_loops/drivetrain/line_follow_drivetrain_test.cc
index ed018b9..4d88ab1 100644
--- a/frc971/control_loops/drivetrain/line_follow_drivetrain_test.cc
+++ b/frc971/control_loops/drivetrain/line_follow_drivetrain_test.cc
@@ -2,7 +2,7 @@
#include <chrono>
-#include "gflags/gflags.h"
+#include "absl/flags/flag.h"
#include "gtest/gtest.h"
#include "third_party/matplotlib-cpp/matplotlibcpp.h"
@@ -10,7 +10,7 @@
#include "frc971/control_loops/drivetrain/drivetrain_test_lib.h"
#include "frc971/control_loops/drivetrain/trajectory.h"
-DECLARE_bool(plot);
+ABSL_DECLARE_FLAG(bool, plot);
namespace chrono = ::std::chrono;
@@ -117,7 +117,7 @@
}
void TearDown() override {
- if (FLAGS_plot) {
+ if (absl::GetFlag(FLAGS_plot)) {
matplotlibcpp::figure();
matplotlibcpp::plot(time_, simulation_ul_, {{"label", "ul"}});
matplotlibcpp::plot(time_, simulation_ur_, {{"label", "ur"}});
diff --git a/frc971/control_loops/drivetrain/localization/puppet_localizer_test.cc b/frc971/control_loops/drivetrain/localization/puppet_localizer_test.cc
index a4338a8..d08f8eb 100644
--- a/frc971/control_loops/drivetrain/localization/puppet_localizer_test.cc
+++ b/frc971/control_loops/drivetrain/localization/puppet_localizer_test.cc
@@ -2,7 +2,7 @@
#include <queue>
-#include "gtest/gtest.h"
+#include "absl/flags/flag.h"
#include "aos/events/logging/log_writer.h"
#include "aos/network/message_bridge_server_generated.h"
@@ -15,8 +15,8 @@
#include "frc971/control_loops/team_number_test_environment.h"
#include "y2022/control_loops/drivetrain/drivetrain_base.h"
-DEFINE_string(output_folder, "",
- "If set, logs all channels to the provided logfile.");
+ABSL_FLAG(std::string, output_folder, "",
+ "If set, logs all channels to the provided logfile.");
namespace frc971::control_loops::drivetrain::testing {
@@ -77,10 +77,10 @@
set_team_id(frc971::control_loops::testing::kTeamNumber);
set_battery_voltage(12.0);
- if (!FLAGS_output_folder.empty()) {
+ if (!absl::GetFlag(FLAGS_output_folder).empty()) {
logger_event_loop_ = MakeEventLoop("logger", roborio_);
logger_ = std::make_unique<aos::logger::Logger>(logger_event_loop_.get());
- logger_->StartLoggingOnRun(FLAGS_output_folder);
+ logger_->StartLoggingOnRun(absl::GetFlag(FLAGS_output_folder));
}
test_event_loop_->OnRun([this]() { SetStartingPosition({3.0, 2.0, 0.0}); });
diff --git a/frc971/control_loops/drivetrain/spline_test.cc b/frc971/control_loops/drivetrain/spline_test.cc
index b47f4ac..7209658 100644
--- a/frc971/control_loops/drivetrain/spline_test.cc
+++ b/frc971/control_loops/drivetrain/spline_test.cc
@@ -2,12 +2,12 @@
#include <vector>
-#include "gflags/gflags.h"
+#include "absl/flags/flag.h"
#include "gtest/gtest.h"
#include "aos/analysis/in_process_plotter.h"
-DEFINE_bool(plot, false, "If true, plot");
+ABSL_FLAG(bool, plot, false, "If true, plot");
namespace frc971::control_loops::drivetrain::testing {
@@ -21,13 +21,13 @@
class SplineTest : public ::testing::Test {
public:
static void SetUpTestSuite() {
- if (FLAGS_plot) {
+ if (absl::GetFlag(FLAGS_plot)) {
plotter_ = std::make_unique<aos::analysis::Plotter>();
}
}
static void TearDownTestSuite() {
- if (FLAGS_plot) {
+ if (absl::GetFlag(FLAGS_plot)) {
plotter_->Spin();
}
}
@@ -39,7 +39,7 @@
.finished()),
spline4_(control_points_),
spline6_(Spline4To6(control_points_)) {
- if (FLAGS_plot) {
+ if (absl::GetFlag(FLAGS_plot)) {
CHECK(plotter_);
plotter_->Title(TestName());
}
@@ -47,7 +47,7 @@
~SplineTest() {}
void TearDown() override {
- if (FLAGS_plot) {
+ if (absl::GetFlag(FLAGS_plot)) {
plotter_->Publish();
}
}
@@ -115,7 +115,7 @@
}
// Conditionally plot the functions and their integrals to aid debugging.
- if (FLAGS_plot) {
+ if (absl::GetFlag(FLAGS_plot)) {
plotter_->AddFigure("Spline Attributes Over Alpha");
plotter_->AddLine(alphas_plot, x_plot, "X");
plotter_->AddLine(alphas_plot, ix_plot, "Integrated X");
@@ -175,7 +175,7 @@
}
// Conditionally plot the functions and their integrals to aid debugging.
- if (FLAGS_plot) {
+ if (absl::GetFlag(FLAGS_plot)) {
plotter_->AddFigure("Heading Plot");
plotter_->AddLine(alphas_plot, theta_plot, "theta");
plotter_->AddLine(alphas_plot, itheta_plot, "Integrated theta");
@@ -226,7 +226,7 @@
}
// Conditionally plot the functions and their integrals to aid debugging.
- if (FLAGS_plot) {
+ if (absl::GetFlag(FLAGS_plot)) {
plotter_->AddFigure("Spline X/Y");
plotter_->AddLine(alphas_plot, x_plot, "X");
plotter_->AddLine(alphas_plot, y_plot, "Y");
diff --git a/frc971/control_loops/drivetrain/trajectory_plot.cc b/frc971/control_loops/drivetrain/trajectory_plot.cc
index 9eb95b5..8236e61 100644
--- a/frc971/control_loops/drivetrain/trajectory_plot.cc
+++ b/frc971/control_loops/drivetrain/trajectory_plot.cc
@@ -1,8 +1,9 @@
#include <chrono>
-#include "gflags/gflags.h"
+#include "absl/flags/flag.h"
#include "third_party/matplotlib-cpp/matplotlibcpp.h"
+#include "aos/init.h"
#include "aos/logging/implementations.h"
#include "aos/network/team_number.h"
#include "aos/time/time.h"
@@ -28,15 +29,15 @@
//
// https://photos.google.com/share/AF1QipPl34MOTPem2QmmTC3B21dL7GV2_HjxnseRrqxgR60TUasyIPliIuWmnH3yxuSNZw?key=cVhZLUYycXBIZlNTRy10cjZlWm0tcmlqQl9MTE13
-DEFINE_bool(plot, true, "If true, plot");
+ABSL_FLAG(bool, plot, true, "If true, plot");
-DEFINE_double(dx, 0.0, "Amount to disturb x at the start");
-DEFINE_double(dy, 0.0, "Amount to disturb y at the start");
-DEFINE_double(dt, 0.0, "Amount to disturb theta at the start");
-DEFINE_double(dvl, 0.0, "Amount to disturb vl at the start");
-DEFINE_double(dvr, 0.0, "Amount to disturb vr at the start");
+ABSL_FLAG(double, dx, 0.0, "Amount to disturb x at the start");
+ABSL_FLAG(double, dy, 0.0, "Amount to disturb y at the start");
+ABSL_FLAG(double, dt, 0.0, "Amount to disturb theta at the start");
+ABSL_FLAG(double, dvl, 0.0, "Amount to disturb vl at the start");
+ABSL_FLAG(double, dvr, 0.0, "Amount to disturb vr at the start");
-DEFINE_double(forward, 1.0, "Amount to drive forwards");
+ABSL_FLAG(double, forward, 1.0, "Amount to drive forwards");
namespace chrono = ::std::chrono;
@@ -45,12 +46,13 @@
void Main() {
const DrivetrainConfig<double> config =
::y2019::control_loops::drivetrain::GetDrivetrainConfig();
- Trajectory trajectory(
- DistanceSpline(Spline(Spline4To6(
- (::Eigen::Matrix<double, 2, 4>() << 0.0, 1.2 * FLAGS_forward,
- -0.2 * FLAGS_forward, FLAGS_forward, 0.0, 0.0, 1.0, 1.0)
- .finished()))),
- &config, nullptr);
+ Trajectory trajectory(DistanceSpline(Spline(Spline4To6(
+ (::Eigen::Matrix<double, 2, 4>() << 0.0,
+ 1.2 * absl::GetFlag(FLAGS_forward),
+ -0.2 * absl::GetFlag(FLAGS_forward),
+ absl::GetFlag(FLAGS_forward), 0.0, 0.0, 1.0, 1.0)
+ .finished()))),
+ &config, nullptr);
trajectory.set_lateral_acceleration(2.0);
trajectory.set_longitudinal_acceleration(1.0);
@@ -134,11 +136,11 @@
FinishedTrajectory finished_trajectory(&config, &trajectory_buffer.message());
::Eigen::Matrix<double, 5, 1> state = ::Eigen::Matrix<double, 5, 1>::Zero();
- state(0, 0) = FLAGS_dx;
- state(1, 0) = FLAGS_dy;
- state(2, 0) = FLAGS_dt;
- state(3, 0) = FLAGS_dvl;
- state(4, 0) = FLAGS_dvr;
+ state(0, 0) = absl::GetFlag(FLAGS_dx);
+ state(1, 0) = absl::GetFlag(FLAGS_dy);
+ state(2, 0) = absl::GetFlag(FLAGS_dt);
+ state(3, 0) = absl::GetFlag(FLAGS_dvl);
+ state(4, 0) = absl::GetFlag(FLAGS_dvr);
::std::vector<double> simulation_t = length_plan_t;
::std::vector<double> simulation_x;
::std::vector<double> error_x;
@@ -190,7 +192,7 @@
simulation_ur.push_back(U(1));
}
- if (FLAGS_plot) {
+ if (absl::GetFlag(FLAGS_plot)) {
matplotlibcpp::figure();
matplotlibcpp::plot(plan_segment_center_distance, plan_type,
{{"label", "plan_type"}});
@@ -230,7 +232,7 @@
} // namespace frc971::control_loops::drivetrain
int main(int argc, char **argv) {
- ::gflags::ParseCommandLineFlags(&argc, &argv, false);
+ aos::InitGoogle(&argc, &argv);
::aos::network::OverrideTeamNumber(971);
::frc971::control_loops::drivetrain::Main();
return 0;
diff --git a/frc971/control_loops/drivetrain/trajectory_test.cc b/frc971/control_loops/drivetrain/trajectory_test.cc
index 6e9089a..5ff8b5d 100644
--- a/frc971/control_loops/drivetrain/trajectory_test.cc
+++ b/frc971/control_loops/drivetrain/trajectory_test.cc
@@ -3,7 +3,8 @@
#include <chrono>
#include <vector>
-#include "gflags/gflags.h"
+#include "absl/flags/declare.h"
+#include "absl/flags/flag.h"
#include "gtest/gtest.h"
#include "aos/testing/test_shm.h"
@@ -18,10 +19,10 @@
#include "y2016/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h"
#include "y2019/control_loops/drivetrain/drivetrain_base.h"
-DECLARE_bool(plot);
+ABSL_DECLARE_FLAG(bool, plot);
-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.");
namespace frc971::control_loops::drivetrain::testing {
@@ -119,7 +120,7 @@
length_plan_xva_.size() *
::aos::time::DurationInSeconds(dt_config_.dt));
#if defined(SUPPORT_PLOT)
- if (FLAGS_plot) {
+ if (absl::GetFlag(FLAGS_plot)) {
::std::vector<double> distances = trajectory_->Distances();
for (size_t i = 0; i < length_plan_xva_.size(); ++i) {
diff --git a/frc971/control_loops/flywheel/flywheel_controller_test.cc b/frc971/control_loops/flywheel/flywheel_controller_test.cc
index eaac6e6..e52dc8e 100644
--- a/frc971/control_loops/flywheel/flywheel_controller_test.cc
+++ b/frc971/control_loops/flywheel/flywheel_controller_test.cc
@@ -1,6 +1,7 @@
#include "frc971/control_loops/flywheel/flywheel_controller.h"
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "gtest/gtest.h"
#include "aos/configuration.h"
@@ -37,7 +38,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(flywheel_plant_->battery_current(flywheel_U), 0.0, 200.0);
+ CHECK_LE(flywheel_plant_->battery_current(flywheel_U), 200.0);
+ CHECK_GE(flywheel_plant_->battery_current(flywheel_U), -200.0);
flywheel_plant_->Update(flywheel_U);
diff --git a/frc971/control_loops/polytope.h b/frc971/control_loops/polytope.h
index cba25f6..41c98e8 100644
--- a/frc971/control_loops/polytope.h
+++ b/frc971/control_loops/polytope.h
@@ -11,7 +11,8 @@
#include "third_party/cddlib/lib-src/cdd.h"
// clang-format on
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#endif // __linux__
namespace frc971::controls {
diff --git a/frc971/control_loops/quaternion_utils.h b/frc971/control_loops/quaternion_utils.h
index e96f5f1..3e40e3f4 100644
--- a/frc971/control_loops/quaternion_utils.h
+++ b/frc971/control_loops/quaternion_utils.h
@@ -3,7 +3,8 @@
#include "Eigen/Dense"
#include "Eigen/Geometry"
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
namespace frc971::controls {
diff --git a/frc971/control_loops/quaternion_utils_test.cc b/frc971/control_loops/quaternion_utils_test.cc
index 4e9e97a..2eaeaa0 100644
--- a/frc971/control_loops/quaternion_utils_test.cc
+++ b/frc971/control_loops/quaternion_utils_test.cc
@@ -3,7 +3,8 @@
#include <random>
#include "Eigen/Dense"
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "gtest/gtest.h"
#include "aos/testing/random_seed.h"
diff --git a/frc971/control_loops/runge_kutta.h b/frc971/control_loops/runge_kutta.h
index 173014e..7f2b6b6 100644
--- a/frc971/control_loops/runge_kutta.h
+++ b/frc971/control_loops/runge_kutta.h
@@ -1,7 +1,8 @@
#ifndef FRC971_CONTROL_LOOPS_RUNGE_KUTTA_H_
#define FRC971_CONTROL_LOOPS_RUNGE_KUTTA_H_
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include <Eigen/Dense>
#include "frc971/control_loops/runge_kutta_helpers.h"
diff --git a/frc971/control_loops/runge_kutta_helpers.h b/frc971/control_loops/runge_kutta_helpers.h
index f9a4ecf..dde7c70 100644
--- a/frc971/control_loops/runge_kutta_helpers.h
+++ b/frc971/control_loops/runge_kutta_helpers.h
@@ -1,7 +1,8 @@
#ifndef FRC971_CONTROL_LOOPS_RUNGE_KUTTA_HELPERS_H_
#define FRC971_CONTROL_LOOPS_RUNGE_KUTTA_HELPERS_H_
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include <Eigen/Dense>
namespace frc971::control_loops {
diff --git a/frc971/control_loops/state_feedback_loop.h b/frc971/control_loops/state_feedback_loop.h
index 988aaa9..32f27f8 100644
--- a/frc971/control_loops/state_feedback_loop.h
+++ b/frc971/control_loops/state_feedback_loop.h
@@ -12,7 +12,8 @@
#include "unsupported/Eigen/MatrixFunctions"
#if defined(__linux__)
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/logging/logging.h"
#endif
diff --git a/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test.cc b/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test.cc
index ea24ff3..c17b734 100644
--- a/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test.cc
+++ b/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test.cc
@@ -1,7 +1,8 @@
#include "frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "flatbuffers/flatbuffers.h"
-#include "glog/logging.h"
#include "gtest/gtest.h"
#include "frc971/control_loops/capped_test_plant.h"
diff --git a/frc971/control_loops/swerve/BUILD b/frc971/control_loops/swerve/BUILD
index ed2c604..0efe040 100644
--- a/frc971/control_loops/swerve/BUILD
+++ b/frc971/control_loops/swerve/BUILD
@@ -117,7 +117,8 @@
":motors",
"//aos:init",
"//aos/util:file",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
"@com_google_absl//absl/strings",
"@com_google_absl//absl/strings:str_format",
"@symengine",
diff --git a/frc971/control_loops/swerve/generate_physics.cc b/frc971/control_loops/swerve/generate_physics.cc
index 8a10f89..ee5850c 100644
--- a/frc971/control_loops/swerve/generate_physics.cc
+++ b/frc971/control_loops/swerve/generate_physics.cc
@@ -12,26 +12,30 @@
#include <numbers>
#include <utility>
+#include "absl/flags/flag.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "absl/strings/str_format.h"
#include "absl/strings/str_join.h"
#include "absl/strings/str_replace.h"
#include "absl/strings/substitute.h"
-#include "gflags/gflags.h"
-#include "glog/logging.h"
#include "aos/init.h"
#include "aos/util/file.h"
#include "frc971/control_loops/swerve/motors.h"
-DEFINE_string(output_base, "",
- "Path to strip off the front of the output paths.");
-DEFINE_string(cc_output_path, "", "Path to write generated cc code to");
-DEFINE_string(h_output_path, "", "Path to write generated header code to");
-DEFINE_string(py_output_path, "", "Path to write generated py code to");
-DEFINE_string(casadi_py_output_path, "",
- "Path to write casadi generated py code to");
+ABSL_FLAG(std::string, output_base, "",
+ "Path to strip off the front of the output paths.");
+ABSL_FLAG(std::string, cc_output_path, "",
+ "Path to write generated cc code to");
+ABSL_FLAG(std::string, h_output_path, "",
+ "Path to write generated header code to");
+ABSL_FLAG(std::string, py_output_path, "",
+ "Path to write generated py code to");
+ABSL_FLAG(std::string, casadi_py_output_path, "",
+ "Path to write casadi generated py code to");
-DEFINE_bool(symbolic, false, "If true, write everything out symbolically.");
+ABSL_FLAG(bool, symbolic, false, "If true, write everything out symbolically.");
using SymEngine::abs;
using SymEngine::add;
@@ -100,7 +104,7 @@
auto fy = symbol("fy");
auto moment = symbol("moment");
- if (FLAGS_symbolic) {
+ if (absl::GetFlag(FLAGS_symbolic)) {
Cx_ = symbol("Cx");
Cy_ = symbol("Cy");
@@ -335,7 +339,8 @@
std::vector<std::string> result_h;
std::string_view include_guard_stripped = h_path;
- CHECK(absl::ConsumePrefix(&include_guard_stripped, FLAGS_output_base));
+ CHECK(absl::ConsumePrefix(&include_guard_stripped,
+ absl::GetFlag(FLAGS_output_base)));
std::string include_guard =
absl::StrReplaceAll(absl::AsciiStrToUpper(include_guard_stripped),
{{"/", "_"}, {".", "_"}});
@@ -934,14 +939,16 @@
frc971::control_loops::swerve::SwerveSimulation sim;
- if (!FLAGS_cc_output_path.empty() && !FLAGS_h_output_path.empty()) {
- sim.Write(FLAGS_cc_output_path, FLAGS_h_output_path);
+ if (!absl::GetFlag(FLAGS_cc_output_path).empty() &&
+ !absl::GetFlag(FLAGS_h_output_path).empty()) {
+ sim.Write(absl::GetFlag(FLAGS_cc_output_path),
+ absl::GetFlag(FLAGS_h_output_path));
}
- if (!FLAGS_py_output_path.empty()) {
- sim.WritePy(FLAGS_py_output_path);
+ if (!absl::GetFlag(FLAGS_py_output_path).empty()) {
+ sim.WritePy(absl::GetFlag(FLAGS_py_output_path));
}
- if (!FLAGS_casadi_py_output_path.empty()) {
- sim.WriteCasadi(FLAGS_casadi_py_output_path);
+ if (!absl::GetFlag(FLAGS_casadi_py_output_path).empty()) {
+ sim.WriteCasadi(absl::GetFlag(FLAGS_casadi_py_output_path));
}
return 0;
diff --git a/frc971/image_streamer/BUILD b/frc971/image_streamer/BUILD
index dce389a..1eae3de 100644
--- a/frc971/image_streamer/BUILD
+++ b/frc971/image_streamer/BUILD
@@ -42,7 +42,8 @@
"//third_party:gstreamer",
"//third_party/seasocks",
"@com_github_google_flatbuffers//:flatbuffers",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
"@com_google_absl//absl/strings:str_format",
],
)
diff --git a/frc971/image_streamer/image_streamer.cc b/frc971/image_streamer/image_streamer.cc
index b89adc0..8e0c4d0 100644
--- a/frc971/image_streamer/image_streamer.cc
+++ b/frc971/image_streamer/image_streamer.cc
@@ -14,10 +14,11 @@
#include <map>
#include <thread>
+#include "absl/flags/flag.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "absl/strings/str_format.h"
#include "flatbuffers/flatbuffers.h"
-#include "gflags/gflags.h"
-#include "glog/logging.h"
#include "aos/events/glib_main_loop.h"
#include "aos/events/shm_event_loop.h"
@@ -30,27 +31,28 @@
#include "seasocks/StringUtil.h"
#include "seasocks/WebSocket.h"
-DEFINE_string(config, "aos_config.json",
- "Name of the config file to replay using.");
-DEFINE_string(device, "/dev/video0",
- "Camera fd. Ignored if reading from channel");
-DEFINE_string(data_dir, "image_streamer_www",
- "Directory to serve data files from");
-DEFINE_bool(publish_images, true,
- "If true, publish images read from v4l2 to /camera.");
-DEFINE_int32(width, 400, "Image width");
-DEFINE_int32(height, 300, "Image height");
-DEFINE_int32(framerate, 25, "Framerate (FPS)");
-DEFINE_int32(brightness, 50, "Camera brightness");
-DEFINE_int32(exposure, 300, "Manual exposure");
-DEFINE_int32(bitrate, 500000, "H264 encode bitrate");
-DEFINE_int32(streaming_port, 1180, "Port to stream images on with seasocks");
-DEFINE_int32(min_port, 5800, "Min rtp port");
-DEFINE_int32(max_port, 5810, "Max rtp port");
-DEFINE_string(listen_on, "",
- "Channel on which to receive frames from. Used in place of "
- "internal V4L2 reader. Note: width and height MUST match the "
- "expected size of channel images.");
+ABSL_FLAG(std::string, config, "aos_config.json",
+ "Name of the config file to replay using.");
+ABSL_FLAG(std::string, device, "/dev/video0",
+ "Camera fd. Ignored if reading from channel");
+ABSL_FLAG(std::string, data_dir, "image_streamer_www",
+ "Directory to serve data files from");
+ABSL_FLAG(bool, publish_images, true,
+ "If true, publish images read from v4l2 to /camera.");
+ABSL_FLAG(int32_t, width, 400, "Image width");
+ABSL_FLAG(int32_t, height, 300, "Image height");
+ABSL_FLAG(int32_t, framerate, 25, "Framerate (FPS)");
+ABSL_FLAG(int32_t, brightness, 50, "Camera brightness");
+ABSL_FLAG(int32_t, exposure, 300, "Manual exposure");
+ABSL_FLAG(int32_t, bitrate, 500000, "H264 encode bitrate");
+ABSL_FLAG(int32_t, streaming_port, 1180,
+ "Port to stream images on with seasocks");
+ABSL_FLAG(int32_t, min_port, 5800, "Min rtp port");
+ABSL_FLAG(int32_t, max_port, 5810, "Max rtp port");
+ABSL_FLAG(std::string, listen_on, "",
+ "Channel on which to receive frames from. Used in place of "
+ "internal V4L2 reader. Note: width and height MUST match the "
+ "expected size of channel images.");
class Connection;
@@ -87,9 +89,9 @@
// client since we don't expect more than 1 or 2.
std::string exposure;
- if (FLAGS_exposure > 0) {
+ if (absl::GetFlag(FLAGS_exposure) > 0) {
exposure = absl::StrFormat(",auto_exposure=1,exposure_time_absolute=%d",
- FLAGS_exposure);
+ absl::GetFlag(FLAGS_exposure));
}
pipeline_ = gst_parse_launch(
@@ -100,8 +102,10 @@
"name=appsink "
"emit-signals=true sync=false async=false "
"caps=video/x-raw,format=YUY2",
- FLAGS_device, FLAGS_brightness, exposure, FLAGS_width,
- FLAGS_height, FLAGS_framerate)
+ absl::GetFlag(FLAGS_device),
+ absl::GetFlag(FLAGS_brightness), exposure,
+ absl::GetFlag(FLAGS_width), absl::GetFlag(FLAGS_height),
+ absl::GetFlag(FLAGS_framerate))
.c_str(),
&error);
@@ -157,7 +161,7 @@
std::function<void(GstSample *)> callback)
: callback_(std::move(callback)) {
event_loop->MakeWatcher(
- FLAGS_listen_on,
+ absl::GetFlag(FLAGS_listen_on),
[this](const frc971::vision::CameraImage &image) { OnImage(image); });
}
@@ -167,8 +171,8 @@
VLOG(2) << "Skipping CameraImage with no data";
return;
}
- CHECK_EQ(image.rows(), FLAGS_height);
- CHECK_EQ(image.cols(), FLAGS_width);
+ CHECK_EQ(image.rows(), absl::GetFlag(FLAGS_height));
+ CHECK_EQ(image.cols(), absl::GetFlag(FLAGS_width));
GBytes *bytes = g_bytes_new(image.data()->data(), image.data()->size());
GstBuffer *buffer = gst_buffer_new_wrapped_bytes(bytes);
@@ -282,8 +286,8 @@
server_(server),
manual_restart_handle_(
event_loop_->AddTimer([this]() { event_loop_->Exit(); })) {
- if (FLAGS_listen_on.empty()) {
- if (FLAGS_publish_images) {
+ if (absl::GetFlag(FLAGS_listen_on).empty()) {
+ if (absl::GetFlag(FLAGS_publish_images)) {
sender_ = event_loop->MakeSender<frc971::vision::CameraImage>("/camera");
}
source_ =
@@ -377,7 +381,8 @@
"application/"
"x-rtp,media=video,encoding-name=H264,payload=96,clock-rate=90000 !"
"webrtcbin. ",
- FLAGS_width, FLAGS_height, FLAGS_bitrate / 1000)
+ absl::GetFlag(FLAGS_width), absl::GetFlag(FLAGS_height),
+ absl::GetFlag(FLAGS_bitrate) / 1000)
.c_str(),
&error);
@@ -415,8 +420,8 @@
g_object_get(G_OBJECT(webrtcbin_), "ice-agent", &ice, nullptr);
CHECK(ice != nullptr);
- g_object_set(ice, "min-rtp-port", FLAGS_min_port, "max-rtp-port",
- FLAGS_max_port, nullptr);
+ g_object_set(ice, "min-rtp-port", absl::GetFlag(FLAGS_min_port),
+ "max-rtp-port", absl::GetFlag(FLAGS_max_port), nullptr);
// We don't need upnp on a local network.
{
@@ -628,7 +633,7 @@
gst_init(&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());
{
@@ -637,14 +642,14 @@
seasocks::Server server(::std::shared_ptr<seasocks::Logger>(
new ::aos::seasocks::SeasocksLogger(seasocks::Logger::Level::Info)));
- LOG(INFO) << "Serving from " << FLAGS_data_dir;
+ LOG(INFO) << "Serving from " << absl::GetFlag(FLAGS_data_dir);
auto websocket_handler =
std::make_shared<WebsocketHandler>(&event_loop, &server);
server.addWebSocketHandler("/ws", websocket_handler);
- server.startListening(FLAGS_streaming_port);
- server.setStaticPath(FLAGS_data_dir.c_str());
+ server.startListening(absl::GetFlag(FLAGS_streaming_port));
+ server.setStaticPath(absl::GetFlag(FLAGS_data_dir).c_str());
aos::internal::EPoll *epoll = event_loop.epoll();
diff --git a/frc971/imu/imu_calibrator-tmpl.h b/frc971/imu/imu_calibrator-tmpl.h
index 6743106..49d5c20 100644
--- a/frc971/imu/imu_calibrator-tmpl.h
+++ b/frc971/imu/imu_calibrator-tmpl.h
@@ -1,7 +1,10 @@
+#include "absl/flags/declare.h"
+#include "absl/flags/flag.h"
+
#include "frc971/imu/imu_calibrator.h"
#include "frc971/math/interpolate.h"
-DECLARE_int32(imu_zeroing_buffer);
+ABSL_DECLARE_FLAG(int32_t, imu_zeroing_buffer);
namespace frc971::imu {
@@ -26,7 +29,8 @@
const bool plausibly_stationary =
reading.gyro.squaredNorm() < kGyroMaxZeroingValue * kGyroMaxZeroingValue;
bool stationary = plausibly_stationary;
- int earliest_affected_index = readings.size() - FLAGS_imu_zeroing_buffer;
+ int earliest_affected_index =
+ readings.size() - absl::GetFlag(FLAGS_imu_zeroing_buffer);
for (size_t index = std::max(0, earliest_affected_index);
index < readings.size(); ++index) {
if (!plausibly_stationary) {
@@ -75,7 +79,8 @@
template <typename Scalar>
void ImuCalibrator<Scalar>::EvaluateRelativeResiduals() {
for (const auto &readings : imu_readings_) {
- CHECK_LT(static_cast<size_t>(FLAGS_imu_zeroing_buffer * 2), readings.size())
+ CHECK_LT(static_cast<size_t>(absl::GetFlag(FLAGS_imu_zeroing_buffer) * 2),
+ readings.size())
<< ": Insufficient readings to perform calibration.";
}
Scalar base_clock = imu_readings_[origin_index_][0].capture_time_adjusted;
diff --git a/frc971/imu/imu_calibrator.cc b/frc971/imu/imu_calibrator.cc
index 03fa377..73e16e0 100644
--- a/frc971/imu/imu_calibrator.cc
+++ b/frc971/imu/imu_calibrator.cc
@@ -1,6 +1,6 @@
#include "frc971/imu/imu_calibrator.h"
-DEFINE_int32(
- imu_zeroing_buffer, 100,
+ABSL_FLAG(
+ int32_t, imu_zeroing_buffer, 100,
"We will only consider readings stationary for purposes if calibration if "
"this many readings to either side appear to be stationary.");
diff --git a/frc971/imu/imu_calibrator.h b/frc971/imu/imu_calibrator.h
index 58ff12b..d8b7aab 100644
--- a/frc971/imu/imu_calibrator.h
+++ b/frc971/imu/imu_calibrator.h
@@ -6,10 +6,11 @@
#include <tuple>
#include <vector>
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "absl/strings/str_format.h"
#include "absl/strings/str_join.h"
#include "ceres/ceres.h"
-#include "glog/logging.h"
#include <Eigen/Core>
#include <Eigen/Geometry>
diff --git a/frc971/imu/imu_calibrator_test.cc b/frc971/imu/imu_calibrator_test.cc
index a341b2a..2546da4 100644
--- a/frc971/imu/imu_calibrator_test.cc
+++ b/frc971/imu/imu_calibrator_test.cc
@@ -2,6 +2,7 @@
#include <random>
+#include "absl/flags/reflection.h"
#include "gtest/gtest.h"
#include "frc971/imu/imu_calibrator_solver.h"
@@ -140,7 +141,7 @@
// the IMU inputs; feeding in a sine wave works much better for allowing the
// solver to estimate the offset.
TEST(ImuCalibratorTest, TimeOffsetTest) {
- gflags::FlagSaver flag_saver;
+ absl::FlagSaver flag_saver;
std::vector<ImuConfig<double>> nominal_imus = {
ImuConfig<double>{true, std::nullopt},
diff --git a/frc971/imu_fdcan/BUILD b/frc971/imu_fdcan/BUILD
index c8a6cd7..51357c6 100644
--- a/frc971/imu_fdcan/BUILD
+++ b/frc971/imu_fdcan/BUILD
@@ -91,7 +91,8 @@
"//aos/events:simulated_event_loop",
"//aos/testing:googletest",
"//frc971/can_logger:can_logging_fbs",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
)
@@ -110,7 +111,8 @@
"//aos/events:simulated_event_loop",
"//aos/testing:googletest",
"//frc971/can_logger:can_logging_fbs",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
)
diff --git a/frc971/imu_fdcan/can_translator_lib_test.cc b/frc971/imu_fdcan/can_translator_lib_test.cc
index fcef6a4..b62bba6 100644
--- a/frc971/imu_fdcan/can_translator_lib_test.cc
+++ b/frc971/imu_fdcan/can_translator_lib_test.cc
@@ -1,6 +1,7 @@
#include "frc971/imu_fdcan/can_translator_lib.h"
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "gtest/gtest.h"
#include "aos/events/simulated_event_loop.h"
diff --git a/frc971/imu_fdcan/can_translator_main.cc b/frc971/imu_fdcan/can_translator_main.cc
index fdb7107..402448e 100644
--- a/frc971/imu_fdcan/can_translator_main.cc
+++ b/frc971/imu_fdcan/can_translator_main.cc
@@ -1,8 +1,10 @@
+#include "absl/flags/flag.h"
+
#include "aos/events/shm_event_loop.h"
#include "aos/init.h"
#include "frc971/imu_fdcan/can_translator_lib.h"
-DEFINE_string(channel, "/can", "The CAN channel to use");
+ABSL_FLAG(std::string, channel, "/can", "The CAN channel to use");
using frc971::imu_fdcan::CANTranslator;
@@ -14,7 +16,7 @@
::aos::ShmEventLoop event_loop(&config.message());
- CANTranslator translator(&event_loop, FLAGS_channel);
+ CANTranslator translator(&event_loop, absl::GetFlag(FLAGS_channel));
event_loop.Run();
diff --git a/frc971/imu_fdcan/dual_imu_blender_lib.cc b/frc971/imu_fdcan/dual_imu_blender_lib.cc
index d390102..3b746fc 100644
--- a/frc971/imu_fdcan/dual_imu_blender_lib.cc
+++ b/frc971/imu_fdcan/dual_imu_blender_lib.cc
@@ -1,9 +1,9 @@
#include "frc971/imu_fdcan/dual_imu_blender_lib.h"
-#include "gflags/gflags.h"
+#include "absl/flags/flag.h"
-DEFINE_bool(murata_only, false,
- "If true then only use the murata value and ignore the tdk.");
+ABSL_FLAG(bool, murata_only, false,
+ "If true then only use the murata value and ignore the tdk.");
// Saturation for the gyro is measured in +- radians/s
static constexpr double kMurataGyroSaturation = (300.0 * M_PI) / 180;
@@ -124,7 +124,7 @@
imu_values->set_accelerometer_z(dual_imu->murata()->accelerometer_z());
}
- if (FLAGS_murata_only) {
+ if (absl::GetFlag(FLAGS_murata_only)) {
imu_values->set_gyro_x(dual_imu->murata()->gyro_x());
imu_values->set_gyro_y(dual_imu->murata()->gyro_y());
imu_values->set_gyro_z(dual_imu->murata()->gyro_z());
diff --git a/frc971/imu_fdcan/dual_imu_blender_lib_test.cc b/frc971/imu_fdcan/dual_imu_blender_lib_test.cc
index 59c7e81..f830c4f 100644
--- a/frc971/imu_fdcan/dual_imu_blender_lib_test.cc
+++ b/frc971/imu_fdcan/dual_imu_blender_lib_test.cc
@@ -1,6 +1,7 @@
#include "frc971/imu_fdcan/dual_imu_blender_lib.h"
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "gtest/gtest.h"
#include "aos/events/simulated_event_loop.h"
diff --git a/frc971/imu_reader/BUILD b/frc971/imu_reader/BUILD
index 809a3fc..d204c56 100644
--- a/frc971/imu_reader/BUILD
+++ b/frc971/imu_reader/BUILD
@@ -17,7 +17,8 @@
"//aos/util:crc32",
"//frc971/wpilib:imu_batch_fbs",
"//frc971/wpilib:imu_fbs",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
"@com_google_absl//absl/types:span",
],
)
diff --git a/frc971/imu_reader/imu.cc b/frc971/imu_reader/imu.cc
index acdd6d9..1a74adf 100644
--- a/frc971/imu_reader/imu.cc
+++ b/frc971/imu_reader/imu.cc
@@ -1,6 +1,7 @@
#include "frc971/imu_reader/imu.h"
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/util/crc32.h"
diff --git a/frc971/input/BUILD b/frc971/input/BUILD
index 9e5fd9c..c992932 100644
--- a/frc971/input/BUILD
+++ b/frc971/input/BUILD
@@ -53,7 +53,8 @@
target_compatible_with = ["@platforms//os:linux"],
deps = [
":joystick_state_fbs",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
)
diff --git a/frc971/input/driver_station_data.cc b/frc971/input/driver_station_data.cc
index 06d2d69..34e8a86 100644
--- a/frc971/input/driver_station_data.cc
+++ b/frc971/input/driver_station_data.cc
@@ -1,6 +1,7 @@
#include "frc971/input/driver_station_data.h"
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
namespace frc971::input::driver_station {
diff --git a/frc971/math/BUILD b/frc971/math/BUILD
index b8cd2fc..b4ce504 100644
--- a/frc971/math/BUILD
+++ b/frc971/math/BUILD
@@ -22,8 +22,9 @@
deps = [
":matrix_fbs",
"//aos:json_to_flatbuffer",
- "@com_github_google_glog//:glog",
"@com_github_tartanllama_expected",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
"@org_tuxfamily_eigen//:eigen",
],
)
diff --git a/frc971/math/flatbuffers_matrix.h b/frc971/math/flatbuffers_matrix.h
index cfca897..356b4ec 100644
--- a/frc971/math/flatbuffers_matrix.h
+++ b/frc971/math/flatbuffers_matrix.h
@@ -3,7 +3,8 @@
// This library provides utilities for converting between a frc971.fbs.Matrix
// flatbuffer type and an Eigen::Matrix.
// The interesting methods are ToEigen(), ToEigenOrDie(), and FromEigen().
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "tl/expected.hpp"
#include <Eigen/Core>
diff --git a/frc971/orin/BUILD b/frc971/orin/BUILD
index 250ebef..a95bd84 100644
--- a/frc971/orin/BUILD
+++ b/frc971/orin/BUILD
@@ -52,8 +52,10 @@
"//aos/time",
"//third_party:cudart",
"//third_party/apriltag",
- "@com_github_google_glog//:glog",
"@com_github_nvidia_cccl//:cccl",
+ "@com_google_absl//absl/flags:flag",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
)
@@ -210,7 +212,8 @@
"//aos/events/logging:log_writer",
"//aos/events/logging:snappy_encoder",
"//aos/logging:log_namer",
- "@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/frc971/orin/apriltag.cc b/frc971/orin/apriltag.cc
index 92513c2..3aa0c1b 100644
--- a/frc971/orin/apriltag.cc
+++ b/frc971/orin/apriltag.cc
@@ -14,7 +14,8 @@
#include <cub/iterator/transform_input_iterator.cuh>
#include <vector>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "third_party/apriltag/common/g2d.h"
#include "aos/time/time.h"
diff --git a/frc971/orin/apriltag_detect.cc b/frc971/orin/apriltag_detect.cc
index 26de7fa..9420ef0 100644
--- a/frc971/orin/apriltag_detect.cc
+++ b/frc971/orin/apriltag_detect.cc
@@ -12,14 +12,16 @@
#include <cub/iterator/transform_input_iterator.cuh>
#include <vector>
-#include "glog/logging.h"
+#include "absl/flags/flag.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/time/time.h"
#include "frc971/orin/apriltag.h"
#include "frc971/orin/labeling_allegretti_2019_BKE.h"
#include "frc971/orin/threshold.h"
-DEFINE_int32(debug_blob_index, 4096, "Blob to print out for");
+ABSL_FLAG(int32_t, debug_blob_index, 4096, "Blob to print out for");
constexpr int kUndistortIterationThreshold = 100;
constexpr double kUndistortConvergenceEpsilon = 1e-6;
@@ -101,7 +103,7 @@
quad_corners_host_.resize(0);
VLOG(1) << "Considering " << fit_quads_host_.size();
for (const FitQuad &quad : fit_quads_host_) {
- bool print = quad.blob_index == FLAGS_debug_blob_index;
+ bool print = quad.blob_index == absl::GetFlag(FLAGS_debug_blob_index);
if (!quad.valid) {
continue;
}
diff --git a/frc971/orin/argus_camera.cc b/frc971/orin/argus_camera.cc
index c7825ae..e970754 100644
--- a/frc971/orin/argus_camera.cc
+++ b/frc971/orin/argus_camera.cc
@@ -4,7 +4,9 @@
#include <filesystem>
#include <thread>
-#include "glog/logging.h"
+#include "absl/flags/flag.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "Argus/Argus.h"
#include "Argus/EGLStream.h"
@@ -25,21 +27,22 @@
#include "frc971/vision/vision_generated.h"
#include "nvbufsurface.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.");
-DEFINE_int32(colorformat, NVBUF_COLOR_FORMAT_NV16,
- "Mode to use. Don't change unless you know what you are doing.");
-DEFINE_int32(camera, 0, "Camera number");
-DEFINE_int32(mode, 0, "Mode number to use.");
-DEFINE_int32(exposure, 100, "Exposure number to use.");
-DEFINE_int32(gain, 5, "gain number to use.");
-DEFINE_int32(width, 1456, "Image width");
-DEFINE_int32(height, 1088, "Image height");
-DEFINE_double(rgain, 1.0, "R gain");
-DEFINE_double(g1gain, 1.0, "G gain");
-DEFINE_double(g2gain, 1.0, "G gain");
-DEFINE_double(bgain, 1.0, "B gain");
-DEFINE_string(channel, "/camera", "Channel name for the image.");
+ABSL_FLAG(int32_t, colorformat, NVBUF_COLOR_FORMAT_NV16,
+ "Mode to use. Don't change unless you know what you are doing.");
+ABSL_FLAG(int32_t, camera, 0, "Camera number");
+ABSL_FLAG(int32_t, mode, 0, "Mode number to use.");
+ABSL_FLAG(int32_t, exposure, 100, "Exposure number to use.");
+ABSL_FLAG(int32_t, gain, 5, "gain number to use.");
+ABSL_FLAG(int32_t, width, 1456, "Image width");
+ABSL_FLAG(int32_t, height, 1088, "Image height");
+ABSL_FLAG(double, rgain, 1.0, "R gain");
+ABSL_FLAG(double, g1gain, 1.0, "G gain");
+ABSL_FLAG(double, g2gain, 1.0, "G gain");
+ABSL_FLAG(double, bgain, 1.0, "B gain");
+ABSL_FLAG(std::string, channel, "/camera", "Channel name for the image.");
namespace frc971 {
@@ -221,7 +224,8 @@
CHECK_GT(sensor_modes.size(), 0u);
Argus::ISensorMode *i_sensor_mode =
- Argus::interface_cast<Argus::ISensorMode>(sensor_modes[FLAGS_mode]);
+ Argus::interface_cast<Argus::ISensorMode>(
+ sensor_modes[absl::GetFlag(FLAGS_mode)]);
CHECK(i_sensor_mode);
{
@@ -264,10 +268,11 @@
// Build the DmaBuffers
for (size_t i = 0; i < native_buffers_.size(); ++i) {
- native_buffers_[i] = DmaBuffer::Create(
- i_sensor_mode->getResolution(),
- static_cast<NvBufSurfaceColorFormat>(FLAGS_colorformat),
- NVBUF_LAYOUT_PITCH);
+ native_buffers_[i] =
+ DmaBuffer::Create(i_sensor_mode->getResolution(),
+ static_cast<NvBufSurfaceColorFormat>(
+ absl::GetFlag(FLAGS_colorformat)),
+ NVBUF_LAYOUT_PITCH);
}
// Create EGLImages from the native buffers
@@ -350,18 +355,19 @@
i_source_settings->setFrameDurationRange(
i_sensor_mode->getFrameDurationRange().min());
- CHECK_EQ(i_source_settings->setSensorMode(sensor_modes[FLAGS_mode]),
+ CHECK_EQ(i_source_settings->setSensorMode(
+ sensor_modes[absl::GetFlag(FLAGS_mode)]),
Argus::STATUS_OK);
Argus::Range<float> sensor_mode_analog_gain_range;
- sensor_mode_analog_gain_range.min() = FLAGS_gain;
- sensor_mode_analog_gain_range.max() = FLAGS_gain;
+ sensor_mode_analog_gain_range.min() = absl::GetFlag(FLAGS_gain);
+ sensor_mode_analog_gain_range.max() = absl::GetFlag(FLAGS_gain);
CHECK_EQ(i_source_settings->setGainRange(sensor_mode_analog_gain_range),
Argus::STATUS_OK);
Argus::Range<uint64_t> limit_exposure_time_range;
- limit_exposure_time_range.min() = FLAGS_exposure * 1000;
- limit_exposure_time_range.max() = FLAGS_exposure * 1000;
+ limit_exposure_time_range.min() = absl::GetFlag(FLAGS_exposure) * 1000;
+ limit_exposure_time_range.max() = absl::GetFlag(FLAGS_exposure) * 1000;
CHECK_EQ(i_source_settings->setExposureTimeRange(limit_exposure_time_range),
Argus::STATUS_OK);
@@ -412,9 +418,9 @@
<< nvbuf_surf_->surfaceList->planeParams.bytesPerPix[i];
}
CHECK_EQ(nvbuf_surf_->surfaceList->planeParams.width[0],
- static_cast<size_t>(FLAGS_width));
+ static_cast<size_t>(absl::GetFlag(FLAGS_width)));
CHECK_EQ(nvbuf_surf_->surfaceList->planeParams.height[0],
- static_cast<size_t>(FLAGS_height));
+ static_cast<size_t>(absl::GetFlag(FLAGS_height)));
}
MappedBuffer(const MappedBuffer &other) = delete;
MappedBuffer &operator=(const MappedBuffer &other) = delete;
@@ -524,10 +530,11 @@
};
int Main() {
- std::this_thread::sleep_for(std::chrono::seconds(FLAGS_camera + 1));
+ std::this_thread::sleep_for(
+ std::chrono::seconds(absl::GetFlag(FLAGS_camera) + 1));
aos::FlatbufferDetachedBuffer<aos::Configuration> config =
- aos::configuration::ReadConfig(FLAGS_config);
+ aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
aos::ShmEventLoop event_loop(&config.message());
@@ -535,7 +542,8 @@
event_loop.SetRuntimeAffinity(aos::MakeCpusetFromCpus({2, 3, 4}));
aos::Sender<frc971::vision::CameraImage> sender =
- event_loop.MakeSender<frc971::vision::CameraImage>(FLAGS_channel);
+ event_loop.MakeSender<frc971::vision::CameraImage>(
+ absl::GetFlag(FLAGS_channel));
LOG(INFO) << "Started";
// Initialize the Argus camera provider.
@@ -565,7 +573,8 @@
}
{
- ArgusCamera camera(i_camera_provider, camera_devices[FLAGS_camera]);
+ ArgusCamera camera(i_camera_provider,
+ camera_devices[absl::GetFlag(FLAGS_camera)]);
aos::monotonic_clock::time_point last_time = aos::monotonic_clock::epoch();
@@ -586,18 +595,20 @@
sender.MakeBuilder();
uint8_t *data_pointer = nullptr;
- builder.fbb()->StartIndeterminateVector(FLAGS_width * FLAGS_height * 2,
- 1, 64, &data_pointer);
+ builder.fbb()->StartIndeterminateVector(
+ absl::GetFlag(FLAGS_width) * absl::GetFlag(FLAGS_height) * 2, 1, 64,
+ &data_pointer);
YCbCr422(buffer.nvbuf_surf(), data_pointer);
flatbuffers::Offset<flatbuffers::Vector<uint8_t>> data_offset =
builder.fbb()->EndIndeterminateVector(
- FLAGS_width * FLAGS_height * 2, 1);
+ absl::GetFlag(FLAGS_width) * absl::GetFlag(FLAGS_height) * 2,
+ 1);
auto image_builder = builder.MakeBuilder<frc971::vision::CameraImage>();
image_builder.add_data(data_offset);
- image_builder.add_rows(FLAGS_height);
- image_builder.add_cols(FLAGS_width);
+ image_builder.add_rows(absl::GetFlag(FLAGS_height));
+ image_builder.add_cols(absl::GetFlag(FLAGS_width));
{
aos::ScopedNotRealtime nrt;
image_builder.add_monotonic_timestamp_ns(
diff --git a/frc971/orin/argus_monitor.cc b/frc971/orin/argus_monitor.cc
index 13130cc..c145c87 100644
--- a/frc971/orin/argus_monitor.cc
+++ b/frc971/orin/argus_monitor.cc
@@ -2,7 +2,7 @@
#include <iostream>
-#include "gflags/gflags.h"
+#include "absl/flags/flag.h"
#include "aos/aos_cli_utils.h"
#include "aos/configuration.h"
@@ -10,13 +10,13 @@
#include "aos/json_to_flatbuffer.h"
#include "aos/realtime.h"
-DEFINE_int32(priority, -1, "If set, the RT priority to run at.");
-DEFINE_double(max_jitter, 10.00,
- "The max time in seconds between messages before considering the "
- "camera processes dead.");
-DEFINE_double(grace_period, 10.00,
- "The grace period at startup before enforcing that messages must "
- "flow from the camera processes.");
+ABSL_FLAG(int32_t, priority, -1, "If set, the RT priority to run at.");
+ABSL_FLAG(double, max_jitter, 10.00,
+ "The max time in seconds between messages before considering the "
+ "camera processes dead.");
+ABSL_FLAG(double, grace_period, 10.00,
+ "The grace period at startup before enforcing that messages must "
+ "flow from the camera processes.");
namespace aos {
@@ -38,7 +38,8 @@
timer_handle_->Schedule(
event_loop->monotonic_now() +
std::chrono::duration_cast<std::chrono::nanoseconds>(
- std::chrono::duration<double>(FLAGS_grace_period)),
+ std::chrono::duration<double>(
+ absl::GetFlag(FLAGS_grace_period))),
std::chrono::milliseconds(1000));
});
}
@@ -52,12 +53,13 @@
void RunHealthCheck(aos::EventLoop *event_loop) {
if (last_time_ + std::chrono::duration_cast<std::chrono::nanoseconds>(
- std::chrono::duration<double>(FLAGS_max_jitter)) <
+ std::chrono::duration<double>(
+ absl::GetFlag(FLAGS_max_jitter))) <
event_loop->monotonic_now()) {
// Restart camera services
LOG(INFO) << "Restarting camera services";
LOG(INFO) << "Channel " << channel_name_ << " has not received a message "
- << FLAGS_max_jitter << " seconds";
+ << absl::GetFlag(FLAGS_max_jitter) << " seconds";
CHECK_EQ(std::system("aos_starter stop argus_camera0"), 0);
CHECK_EQ(std::system("aos_starter stop argus_camera1"), 0);
CHECK_EQ(std::system("sudo systemctl restart nvargus-daemon.service"), 0);
@@ -102,8 +104,9 @@
std::make_unique<aos::State>(&(cli_info.event_loop.value()), channel));
}
- if (FLAGS_priority > 0) {
- cli_info.event_loop->SetRuntimeRealtimePriority(FLAGS_priority);
+ if (absl::GetFlag(FLAGS_priority) > 0) {
+ cli_info.event_loop->SetRuntimeRealtimePriority(
+ absl::GetFlag(FLAGS_priority));
}
cli_info.event_loop->Run();
diff --git a/frc971/orin/cuda.cc b/frc971/orin/cuda.cc
index 6bcc79c..cd68a6c 100644
--- a/frc971/orin/cuda.cc
+++ b/frc971/orin/cuda.cc
@@ -1,10 +1,10 @@
#include "frc971/orin/cuda.h"
-#include "gflags/gflags.h"
-#include "glog/logging.h"
+#include "absl/flags/flag.h"
+#include "absl/log/check.h"
-DEFINE_bool(
- sync, false,
+ABSL_FLAG(
+ bool, sync, false,
"If true, force synchronization after each step to isolate errors better.");
namespace frc971::apriltag {
@@ -17,11 +17,11 @@
}
void MaybeCheckAndSynchronize() {
- if (FLAGS_sync) CheckAndSynchronize();
+ if (absl::GetFlag(FLAGS_sync)) CheckAndSynchronize();
}
void MaybeCheckAndSynchronize(std::string_view message) {
- if (FLAGS_sync) CheckAndSynchronize(message);
+ if (absl::GetFlag(FLAGS_sync)) CheckAndSynchronize(message);
}
} // namespace frc971::apriltag
diff --git a/frc971/orin/cuda.h b/frc971/orin/cuda.h
index 0e44fb4..293fc84 100644
--- a/frc971/orin/cuda.h
+++ b/frc971/orin/cuda.h
@@ -4,7 +4,8 @@
#include <chrono>
#include <span>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "cuda_runtime.h"
#include "device_launch_parameters.h"
diff --git a/frc971/orin/cuda_april_tag_test.cc b/frc971/orin/cuda_april_tag_test.cc
index 638bf6a..c3cd160 100644
--- a/frc971/orin/cuda_april_tag_test.cc
+++ b/frc971/orin/cuda_april_tag_test.cc
@@ -2,7 +2,10 @@
#include <random>
#include <string>
-#include "glog/logging.h"
+#include "absl/flags/declare.h"
+#include "absl/flags/flag.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "gtest/gtest.h"
#include "opencv2/imgproc.hpp"
#include "third_party/apriltag/apriltag.h"
@@ -20,14 +23,14 @@
#include "frc971/orin/apriltag.h"
#include "frc971/vision/vision_generated.h"
-DEFINE_int32(pixel_border, 10,
- "Size of image border within which to reject detected corners");
-DEFINE_double(min_decision_margin, 50.0,
- "Minimum decision margin (confidence) for an apriltag detection");
+ABSL_FLAG(int32_t, pixel_border, 10,
+ "Size of image border within which to reject detected corners");
+ABSL_FLAG(double, min_decision_margin, 50.0,
+ "Minimum decision margin (confidence) for an apriltag detection");
-DEFINE_bool(debug, false, "If true, write debug images.");
+ABSL_FLAG(bool, debug, false, "If true, write debug images.");
-DECLARE_int32(debug_blob_index);
+ABSL_DECLARE_FLAG(int32_t, debug_blob_index);
// Get access to the intermediates of aprilrobotics.
extern "C" {
@@ -240,7 +243,7 @@
tag_detector->nthreads = 6;
tag_detector->wp = workerpool_create(tag_detector->nthreads);
tag_detector->qtp.min_white_black_diff = 5;
- tag_detector->debug = FLAGS_debug;
+ tag_detector->debug = absl::GetFlag(FLAGS_debug);
return tag_detector;
}
@@ -386,7 +389,7 @@
apriltag_detection_t *det;
zarray_get(aprilrobotics_detections_, i, &det);
- if (det->decision_margin > FLAGS_min_decision_margin) {
+ if (det->decision_margin > absl::GetFlag(FLAGS_min_decision_margin)) {
LOG(INFO) << "Found tag number " << det->id
<< " hamming: " << det->hamming
<< " margin: " << det->decision_margin;
@@ -1313,7 +1316,8 @@
VLOG(1) << "Inspecting blob of size " << group.size() << " global start "
<< accumulated_size;
for (size_t i = 0; i < group.size(); i++) {
- if (group[i].blob_index() == (size_t)FLAGS_debug_blob_index) {
+ if (group[i].blob_index() ==
+ (size_t)absl::GetFlag(FLAGS_debug_blob_index)) {
LOG(INFO) << "For idx " << i << " global " << accumulated_size + i
<< "(" << group[i].x() << ", " << group[i].y()
<< "), cuda: " << line_fit_points_cuda[accumulated_size + i]
@@ -1339,7 +1343,8 @@
}
for (size_t i = 0; i < group.size(); i++) {
- if (group[i].blob_index() == (size_t)FLAGS_debug_blob_index) {
+ if (group[i].blob_index() ==
+ (size_t)absl::GetFlag(FLAGS_debug_blob_index)) {
LOG(INFO) << " Cuda error[" << i << "] -> "
<< errors_device[accumulated_size + i] << ", filtered "
<< filtered_errors_device[i + accumulated_size];
@@ -1508,8 +1513,10 @@
<< before_cuda << " vs " << us_cuda << " vs " << after_cuda;
CHECK_EQ(peaks_device[accumulated_size + i].filtered_point_index,
accumulated_size + i);
- CHECK_NEAR(peaks_device[accumulated_size + i].error,
- -filtered_errors_device[accumulated_size + i], 1e-3);
+ CHECK_LE(peaks_device[accumulated_size + i].error,
+ -filtered_errors_device[accumulated_size + i] + 1e-3);
+ CHECK_GE(peaks_device[accumulated_size + i].error,
+ -filtered_errors_device[accumulated_size + i] - 1e-3);
if (is_peak_cuda) {
CHECK_EQ(peaks_device[accumulated_size + i].blob_index,
group[0].blob_index())
@@ -1683,7 +1690,7 @@
zarray_t *cluster;
zarray_get(clusters, i, &cluster);
- if (i == FLAGS_debug_blob_index) {
+ if (i == absl::GetFlag(FLAGS_debug_blob_index)) {
LOG(INFO) << "cuda points for blob " << i << " are";
for (size_t j = 0; j < sorted_blobs[i].size(); ++j) {
LOG(INFO) << " blob[" << j << "]: (" << sorted_blobs[i][j].x()
@@ -1715,10 +1722,15 @@
QuadCorners cuda_corner = *quad_iterator;
for (size_t point = 0; point < 4; ++point) {
- CHECK_NEAR(quad_result.p[point][0], cuda_corner.corners[point][0],
- 1e-3);
- CHECK_NEAR(quad_result.p[point][1], cuda_corner.corners[point][1],
- 1e-3);
+ constexpr double kEpsilon = 1e-3;
+ CHECK_LE(quad_result.p[point][0],
+ cuda_corner.corners[point][0] + kEpsilon);
+ CHECK_GE(quad_result.p[point][0],
+ cuda_corner.corners[point][0] - kEpsilon);
+ CHECK_LE(quad_result.p[point][1],
+ cuda_corner.corners[point][1] + kEpsilon);
+ CHECK_GE(quad_result.p[point][1],
+ cuda_corner.corners[point][1] - kEpsilon);
}
}
}
@@ -1755,7 +1767,8 @@
zarray_get(aprilrobotics_detections, i, &aprilrobotics_detection);
zarray_get(gpu_detections, i, &gpu_detection);
- bool valid = gpu_detection->decision_margin > FLAGS_min_decision_margin;
+ bool valid = gpu_detection->decision_margin >
+ absl::GetFlag(FLAGS_min_decision_margin);
LOG(INFO) << "Found GPU " << (valid ? "valid" : "invalid")
<< " tag number " << gpu_detection->id
@@ -1774,8 +1787,8 @@
zarray_get(aprilrobotics_detections, i, &aprilrobotics_detection);
zarray_get(gpu_detections, i, &gpu_detection);
- const bool valid =
- gpu_detection->decision_margin > FLAGS_min_decision_margin;
+ const bool valid = gpu_detection->decision_margin >
+ absl::GetFlag(FLAGS_min_decision_margin);
// TODO(austin): Crank down the thresholds and figure out why these
// deviate. It should be the same function for both at this point.
@@ -2151,7 +2164,7 @@
cuda_detector.DetectCPU(color_image.clone());
}
cuda_detector.Check(color_image.clone());
- if (FLAGS_debug) {
+ if (absl::GetFlag(FLAGS_debug)) {
cuda_detector.WriteDebug(color_image);
}
}
@@ -2175,7 +2188,7 @@
cuda_detector.DetectGPU(color_image.clone());
cuda_detector.DetectCPU(color_image.clone());
cuda_detector.Check(color_image.clone());
- if (FLAGS_debug) {
+ if (absl::GetFlag(FLAGS_debug)) {
cuda_detector.WriteDebug(color_image);
}
}
@@ -2289,7 +2302,7 @@
cuda_detector.DetectGPU(color_image.clone());
cuda_detector.DetectCPU(color_image.clone());
cuda_detector.Check(color_image.clone());
- if (FLAGS_debug) {
+ if (absl::GetFlag(FLAGS_debug)) {
cuda_detector.WriteDebug(color_image);
}
}
@@ -2314,7 +2327,7 @@
cuda_detector.DetectGPU(color_image.clone());
cuda_detector.DetectCPU(color_image.clone());
cuda_detector.Check(color_image.clone());
- if (FLAGS_debug) {
+ if (absl::GetFlag(FLAGS_debug)) {
cuda_detector.WriteDebug(color_image);
}
}
diff --git a/frc971/orin/gpu_apriltag.cc b/frc971/orin/gpu_apriltag.cc
index 425e45f..83ae3ee 100644
--- a/frc971/orin/gpu_apriltag.cc
+++ b/frc971/orin/gpu_apriltag.cc
@@ -2,6 +2,7 @@
#include <chrono>
+#include "absl/flags/flag.h"
#include "third_party/apriltag/apriltag.h"
#include "third_party/apriltag/apriltag_pose.h"
#include "third_party/apriltag/tag16h5.h"
@@ -18,18 +19,18 @@
#include "frc971/vision/charuco_lib.h"
#include "frc971/vision/vision_util_lib.h"
-DEFINE_bool(debug, false, "If true, write debug images.");
-DEFINE_double(
- max_expected_distortion, 0.314,
+ABSL_FLAG(bool, debug, false, "If true, write debug images.");
+ABSL_FLAG(
+ double, max_expected_distortion, 0.314,
"Maximum expected value for unscaled distortion factors. Will scale "
"distortion factors so that this value (and a higher distortion) maps to "
"1.0.");
-DEFINE_double(min_decision_margin, 50.0,
- "Minimum decision margin (confidence) for an apriltag detection");
-DEFINE_int32(pixel_border, 150,
- "Size of image border within which to reject detected corners");
-DEFINE_uint64(pose_estimation_iterations, 50,
- "Number of iterations for apriltag pose estimation.");
+ABSL_FLAG(double, min_decision_margin, 50.0,
+ "Minimum decision margin (confidence) for an apriltag detection");
+ABSL_FLAG(int32_t, pixel_border, 150,
+ "Size of image border within which to reject detected corners");
+ABSL_FLAG(uint64_t, pose_estimation_iterations, 50,
+ "Number of iterations for apriltag pose estimation.");
namespace frc971::apriltag {
@@ -111,7 +112,7 @@
tag_detector->nthreads = 6;
tag_detector->wp = workerpool_create(tag_detector->nthreads);
tag_detector->qtp.min_white_black_diff = 5;
- tag_detector->debug = FLAGS_debug;
+ tag_detector->debug = absl::GetFlag(FLAGS_debug);
return tag_detector;
}
@@ -169,7 +170,8 @@
double distortion_factor =
avg_distance /
cv::norm(cv::Point2d(image_size_.width, image_size_.height));
- return std::min(distortion_factor / FLAGS_max_expected_distortion, 1.0);
+ return std::min(
+ distortion_factor / absl::GetFlag(FLAGS_max_expected_distortion), 1.0);
}
std::vector<cv::Point2f> ApriltagDetector::MakeCornerVector(
@@ -195,7 +197,7 @@
gpu_detector_.Detect(color_image.data);
image_size_ = color_image.size();
cv::Mat image_copy;
- if (FLAGS_visualize) {
+ if (absl::GetFlag(FLAGS_visualize)) {
// TODO: Need to figure out how to extract displayable color image from this
image_copy = color_image.clone();
}
@@ -204,10 +206,10 @@
aos::monotonic_clock::time_point end_time = aos::monotonic_clock::now();
- const uint32_t min_x = FLAGS_pixel_border;
- const uint32_t max_x = color_image.cols - FLAGS_pixel_border;
- const uint32_t min_y = FLAGS_pixel_border;
- const uint32_t max_y = color_image.rows - FLAGS_pixel_border;
+ const uint32_t min_x = absl::GetFlag(FLAGS_pixel_border);
+ const uint32_t max_x = color_image.cols - absl::GetFlag(FLAGS_pixel_border);
+ const uint32_t min_y = absl::GetFlag(FLAGS_pixel_border);
+ const uint32_t max_y = color_image.rows - absl::GetFlag(FLAGS_pixel_border);
// Define variables for storing / visualizing the output
std::vector<Detection> results;
@@ -219,7 +221,8 @@
zarray_get(detections, i, &gpu_detection);
- bool valid = gpu_detection->decision_margin > FLAGS_min_decision_margin;
+ bool valid = gpu_detection->decision_margin >
+ absl::GetFlag(FLAGS_min_decision_margin);
if (valid) {
// Reject tags that are too close to the boundary, since they often
@@ -303,9 +306,9 @@
apriltag_pose_t pose_2;
double pose_error_1;
double pose_error_2;
- estimate_tag_pose_orthogonal_iteration(&info, &pose_error_1, &pose_1,
- &pose_error_2, &pose_2,
- FLAGS_pose_estimation_iterations);
+ estimate_tag_pose_orthogonal_iteration(
+ &info, &pose_error_1, &pose_1, &pose_error_2, &pose_2,
+ absl::GetFlag(FLAGS_pose_estimation_iterations));
const aos::monotonic_clock::time_point after_pose_estimation =
aos::monotonic_clock::now();
@@ -351,7 +354,7 @@
.distortion_factor = distortion_factor,
.pose_error_ratio = pose_error_ratio});
- if (FLAGS_visualize) {
+ if (absl::GetFlag(FLAGS_visualize)) {
// Draw raw (distorted) corner points in green
cv::line(image_copy, orig_corner_points[0], orig_corner_points[1],
cv::Scalar(0, 255, 0), 2);
@@ -381,7 +384,7 @@
}
}
- if (FLAGS_visualize) {
+ if (absl::GetFlag(FLAGS_visualize)) {
// Display the result
// Rotate by 180 degrees to make it upright
// TODO: Make this an option?
@@ -422,7 +425,7 @@
end_time = aos::monotonic_clock::now();
- if (FLAGS_debug) {
+ if (absl::GetFlag(FLAGS_debug)) {
timeprofile_display(tag_detector_->tp);
}
diff --git a/frc971/orin/hardware_monitor.cc b/frc971/orin/hardware_monitor.cc
index e1c785b..cc019fd 100644
--- a/frc971/orin/hardware_monitor.cc
+++ b/frc971/orin/hardware_monitor.cc
@@ -1,16 +1,17 @@
#include <dirent.h>
#include <sys/statvfs.h>
+#include "absl/flags/flag.h"
#include "absl/strings/numbers.h"
#include "absl/strings/str_format.h"
-#include "gflags/gflags.h"
#include "aos/events/shm_event_loop.h"
#include "aos/init.h"
#include "frc971/orin/hardware_stats_generated.h"
-DEFINE_string(config, "aos_config.json", "File path of aos configuration");
-DEFINE_bool(log_voltages, false, "If true, log voltages too.");
+ABSL_FLAG(std::string, config, "aos_config.json",
+ "File path of aos configuration");
+ABSL_FLAG(bool, log_voltages, false, "If true, log voltages too.");
namespace frc971::orin {
namespace {
@@ -102,7 +103,7 @@
flatbuffers::Offset<
flatbuffers::Vector<flatbuffers::Offset<ElectricalReading>>>
electrical_readings_offset;
- if (FLAGS_log_voltages) {
+ if (absl::GetFlag(FLAGS_log_voltages)) {
std::vector<flatbuffers::Offset<ElectricalReading>> electrical_readings;
// Iterate through INA3221 electrical reading channels
for (int channel = 1; channel <= 3; channel++) {
@@ -182,7 +183,7 @@
aos::InitGoogle(&argc, &argv);
aos::FlatbufferDetachedBuffer<aos::Configuration> config =
- aos::configuration::ReadConfig(FLAGS_config);
+ aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
aos::ShmEventLoop shm_event_loop(&config.message());
diff --git a/frc971/orin/labeling_allegretti_2019_BKE.cc b/frc971/orin/labeling_allegretti_2019_BKE.cc
index 2806199..0ec1664 100644
--- a/frc971/orin/labeling_allegretti_2019_BKE.cc
+++ b/frc971/orin/labeling_allegretti_2019_BKE.cc
@@ -19,7 +19,8 @@
#include "frc971/orin/labeling_allegretti_2019_BKE.h"
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "cuda_runtime.h"
#include "device_launch_parameters.h"
diff --git a/frc971/orin/localizer_logger.cc b/frc971/orin/localizer_logger.cc
index ec8d3ac..c571bd7 100644
--- a/frc971/orin/localizer_logger.cc
+++ b/frc971/orin/localizer_logger.cc
@@ -1,8 +1,10 @@
#include <sys/resource.h>
#include <sys/time.h>
-#include "gflags/gflags.h"
-#include "glog/logging.h"
+#include "absl/flags/flag.h"
+#include "absl/flags/usage.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/configuration.h"
#include "aos/events/logging/log_writer.h"
@@ -11,15 +13,15 @@
#include "aos/init.h"
#include "aos/logging/log_namer.h"
-DEFINE_string(config, "aos_config.json", "Config file to use.");
+ABSL_FLAG(std::string, config, "aos_config.json", "Config file to use.");
-DEFINE_double(rotate_every, 30.0,
- "If set, rotate the logger after this many seconds");
+ABSL_FLAG(double, rotate_every, 30.0,
+ "If set, rotate the logger after this many seconds");
-DECLARE_int32(flush_size);
+ABSL_DECLARE_FLAG(int32_t, flush_size);
int main(int argc, char *argv[]) {
- gflags::SetUsageMessage(
+ absl::SetProgramUsageMessage(
"This program provides a simple logger binary that logs all SHMEM data "
"directly to a file specified at the command line. It does not manage "
"filenames, so it will just crash if you attempt to overwrite an "
@@ -28,7 +30,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());
@@ -40,8 +42,8 @@
log_namer->set_extension(aos::logger::SnappyDecoder::kExtension);
log_namer->set_encoder_factory([](size_t max_message_size) {
- return std::make_unique<aos::logger::SnappyEncoder>(max_message_size,
- FLAGS_flush_size);
+ return std::make_unique<aos::logger::SnappyEncoder>(
+ max_message_size, absl::GetFlag(FLAGS_flush_size));
});
aos::monotonic_clock::time_point last_rotation_time =
@@ -53,11 +55,11 @@
return (channel->max_size() * channel->frequency()) < 10e6;
});
- if (FLAGS_rotate_every != 0.0) {
+ if (absl::GetFlag(FLAGS_rotate_every) != 0.0) {
logger.set_on_logged_period(
[&logger, &last_rotation_time](aos::monotonic_clock::time_point t) {
- if (t > last_rotation_time +
- std::chrono::duration<double>(FLAGS_rotate_every)) {
+ if (t > last_rotation_time + std::chrono::duration<double>(
+ absl::GetFlag(FLAGS_rotate_every))) {
logger.Rotate();
last_rotation_time = t;
}
diff --git a/frc971/solvers/BUILD b/frc971/solvers/BUILD
index 1a8ba9b..35924eb 100644
--- a/frc971/solvers/BUILD
+++ b/frc971/solvers/BUILD
@@ -4,7 +4,8 @@
target_compatible_with = ["@platforms//os:linux"],
visibility = ["//visibility:public"],
deps = [
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
"@com_google_absl//absl/strings",
"@org_tuxfamily_eigen//:eigen",
],
@@ -29,7 +30,8 @@
target_compatible_with = ["@platforms//os:linux"],
visibility = ["//visibility:public"],
deps = [
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
"@com_google_absl//absl/strings",
"@org_tuxfamily_eigen//:eigen",
],
diff --git a/frc971/solvers/convex.h b/frc971/solvers/convex.h
index d8989d8..4a7575d 100644
--- a/frc971/solvers/convex.h
+++ b/frc971/solvers/convex.h
@@ -6,8 +6,9 @@
#include <iomanip>
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "absl/strings/str_join.h"
-#include "glog/logging.h"
#include <Eigen/Dense>
namespace frc971::solvers {
diff --git a/frc971/solvers/sparse_convex.cc b/frc971/solvers/sparse_convex.cc
index 714b21c..646d7cf 100644
--- a/frc971/solvers/sparse_convex.cc
+++ b/frc971/solvers/sparse_convex.cc
@@ -1,7 +1,8 @@
#include "frc971/solvers/sparse_convex.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "absl/strings/str_join.h"
-#include "glog/logging.h"
#include <Eigen/Sparse>
#include <Eigen/SparseLU>
diff --git a/frc971/solvers/sparse_convex.h b/frc971/solvers/sparse_convex.h
index 074f2f3..dafbcd2 100644
--- a/frc971/solvers/sparse_convex.h
+++ b/frc971/solvers/sparse_convex.h
@@ -6,7 +6,8 @@
#include <iomanip>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include <Eigen/Sparse>
namespace frc971::solvers {
diff --git a/frc971/vision/BUILD b/frc971/vision/BUILD
index 14e3d41..48a8fb1 100644
--- a/frc971/vision/BUILD
+++ b/frc971/vision/BUILD
@@ -53,8 +53,9 @@
"//aos/logging:log_namer",
"//aos/util:filesystem_fbs",
"//frc971/input:joystick_state_fbs",
- "@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",
],
)
@@ -150,8 +151,9 @@
"//aos/events:event_loop",
"//aos/scoped:scoped_fd",
"//aos/util:threaded_consumer",
- "@com_github_google_glog//:glog",
"@com_google_absl//absl/base",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
)
@@ -175,7 +177,8 @@
"//frc971/vision:vision_fbs",
"//third_party:opencv",
"@com_github_foxglove_schemas//:schemas",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
"@com_google_absl//absl/strings:str_format",
"@com_google_absl//absl/types:span",
"@org_tuxfamily_eigen//:eigen",
@@ -270,7 +273,8 @@
deps = [
"//aos/util:math",
"//third_party:opencv",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
)
@@ -313,7 +317,8 @@
"//aos:init",
"//frc971/vision:visualize_robot",
"//third_party:opencv",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
"@com_google_ceres_solver//:ceres",
"@org_tuxfamily_eigen//:eigen",
],
@@ -329,7 +334,8 @@
deps = [
"//aos/scoped:scoped_fd",
"//aos/util:file",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
"@com_google_absl//absl/strings",
],
)
@@ -433,7 +439,8 @@
deps = [
"//frc971/vision:calibration_fbs",
"//third_party:opencv",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
"@com_google_absl//absl/strings:str_format",
],
)
@@ -445,7 +452,8 @@
deps = [
"//aos/testing:googletest",
"//frc971/vision:vision_util_lib",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
)
diff --git a/frc971/vision/calibration_accumulator.cc b/frc971/vision/calibration_accumulator.cc
index bbf51ee..9b1fa97 100644
--- a/frc971/vision/calibration_accumulator.cc
+++ b/frc971/vision/calibration_accumulator.cc
@@ -5,6 +5,7 @@
#include <limits>
#include "Eigen/Dense"
+#include "absl/flags/flag.h"
#include "external/com_github_foxglove_schemas/CompressedImage_schema.h"
#include "external/com_github_foxglove_schemas/ImageAnnotations_schema.h"
#include <opencv2/highgui/highgui.hpp>
@@ -16,11 +17,11 @@
#include "frc971/vision/charuco_lib.h"
#include "frc971/wpilib/imu_batch_generated.h"
-DEFINE_bool(display_undistorted, false,
- "If true, display the undistorted image.");
-DEFINE_string(save_path, "", "Where to store annotated images");
-DEFINE_bool(save_valid_only, false,
- "If true, only save images with valid pose estimates");
+ABSL_FLAG(bool, display_undistorted, false,
+ "If true, display the undistorted image.");
+ABSL_FLAG(std::string, save_path, "", "Where to store annotated images");
+ABSL_FLAG(bool, save_valid_only, false,
+ "If true, only save images with valid pose estimates");
namespace frc971::vision {
using aos::distributed_clock;
@@ -232,8 +233,8 @@
<< "\nT:" << tvecs_eigen[0].transpose().format(HeavyFmt);
}
- if (FLAGS_visualize) {
- if (FLAGS_display_undistorted) {
+ if (absl::GetFlag(FLAGS_visualize)) {
+ if (absl::GetFlag(FLAGS_display_undistorted)) {
const cv::Size image_size(rgb_image.cols, rgb_image.rows);
cv::Mat undistorted_rgb_image(image_size, CV_8UC3);
cv::undistort(rgb_image, undistorted_rgb_image,
@@ -247,11 +248,11 @@
cv::waitKey(1);
}
- if (FLAGS_save_path != "") {
- if (!FLAGS_save_valid_only || valid) {
+ if (absl::GetFlag(FLAGS_save_path) != "") {
+ if (!absl::GetFlag(FLAGS_save_valid_only) || valid) {
static int img_count = 0;
std::string image_name = absl::StrFormat("/img_%06d.png", img_count);
- std::string path = FLAGS_save_path + image_name;
+ std::string path = absl::GetFlag(FLAGS_save_path) + image_name;
VLOG(2) << "Saving image to " << path;
cv::imwrite(path, rgb_image);
img_count++;
diff --git a/frc971/vision/ceres/BUILD b/frc971/vision/ceres/BUILD
index f2cb96b..d2671c8 100644
--- a/frc971/vision/ceres/BUILD
+++ b/frc971/vision/ceres/BUILD
@@ -15,7 +15,7 @@
target_compatible_with = ["@platforms//os:linux"],
visibility = ["//visibility:public"],
deps = [
- "@com_github_gflags_gflags//:gflags",
+ "@com_google_absl//absl/flags:flag",
"@com_google_ceres_solver//:ceres",
"@org_tuxfamily_eigen//:eigen",
],
diff --git a/frc971/vision/ceres/read_g2o.h b/frc971/vision/ceres/read_g2o.h
index c427939..b10ac22 100644
--- a/frc971/vision/ceres/read_g2o.h
+++ b/frc971/vision/ceres/read_g2o.h
@@ -36,7 +36,8 @@
#include <fstream>
#include <string>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
namespace ceres::examples {
diff --git a/frc971/vision/charuco_lib.cc b/frc971/vision/charuco_lib.cc
index 71c2ff6..dc4cb18 100644
--- a/frc971/vision/charuco_lib.cc
+++ b/frc971/vision/charuco_lib.cc
@@ -4,7 +4,10 @@
#include <functional>
#include <string_view>
-#include "glog/logging.h"
+#include "absl/flags/declare.h"
+#include "absl/flags/flag.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include <opencv2/core/eigen.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/imgproc.hpp>
@@ -15,28 +18,30 @@
#include "frc971/control_loops/quaternion_utils.h"
#include "frc971/vision/vision_generated.h"
-DEFINE_string(board_template_path, "",
- "If specified, write an image to the specified path for the "
- "charuco board pattern.");
-DEFINE_bool(coarse_pattern, true, "If true, use coarse arucos; else, use fine");
-DEFINE_uint32(gray_threshold, 0,
- "If > 0, threshold image based on this grayscale value");
-DEFINE_bool(large_board, true, "If true, use the large calibration board.");
-DEFINE_uint32(
- min_charucos, 10,
+ABSL_FLAG(std::string, board_template_path, "",
+ "If specified, write an image to the specified path for the "
+ "charuco board pattern.");
+ABSL_FLAG(bool, coarse_pattern, true,
+ "If true, use coarse arucos; else, use fine");
+ABSL_FLAG(uint32_t, gray_threshold, 0,
+ "If > 0, threshold image based on this grayscale value");
+ABSL_FLAG(bool, large_board, true, "If true, use the large calibration board.");
+ABSL_FLAG(
+ uint32_t, min_charucos, 10,
"The mininum number of aruco targets in charuco board required to match.");
-DEFINE_uint32(min_id, 0, "Minimum valid charuco id");
-DEFINE_uint32(max_diamonds, 0,
- "Maximum number of diamonds to see. Set to 0 for no limit");
-DEFINE_uint32(max_id, 15, "Maximum valid charuco id");
-DEFINE_bool(visualize, false, "Whether to visualize the resulting data.");
-DEFINE_bool(
- draw_axes, false,
+ABSL_FLAG(uint32_t, min_id, 0, "Minimum valid charuco id");
+ABSL_FLAG(uint32_t, max_diamonds, 0,
+ "Maximum number of diamonds to see. Set to 0 for no limit");
+ABSL_FLAG(uint32_t, max_id, 15, "Maximum valid charuco id");
+ABSL_FLAG(bool, visualize, false, "Whether to visualize the resulting data.");
+ABSL_FLAG(
+ bool, draw_axes, false,
"Whether to draw axes on the resulting data-- warning, may cause crashes.");
-DEFINE_uint32(disable_delay, 100, "Time after an issue to disable tracing at.");
+ABSL_FLAG(uint32_t, disable_delay, 100,
+ "Time after an issue to disable tracing at.");
-DECLARE_bool(enable_ftrace);
+ABSL_DECLARE_FLAG(bool, enable_ftrace);
namespace frc971::vision {
namespace chrono = std::chrono;
@@ -121,13 +126,14 @@
const double age_double =
std::chrono::duration_cast<std::chrono::duration<double>>(age).count();
if (age > max_age_) {
- if (FLAGS_enable_ftrace) {
+ if (absl::GetFlag(FLAGS_enable_ftrace)) {
ftrace_.FormatMessage("Too late receiving image, age: %f\n",
age_double);
- if (FLAGS_disable_delay > 0) {
+ if (absl::GetFlag(FLAGS_disable_delay) > 0) {
if (!disabling_) {
- timer_fn_->Schedule(event_loop_->monotonic_now() +
- chrono::milliseconds(FLAGS_disable_delay));
+ timer_fn_->Schedule(
+ event_loop_->monotonic_now() +
+ chrono::milliseconds(absl::GetFlag(FLAGS_disable_delay)));
disabling_ = true;
}
} else {
@@ -175,28 +181,32 @@
if (target_type_ == TargetType::kCharuco ||
target_type_ == TargetType::kAruco) {
dictionary_ = cv::aruco::getPredefinedDictionary(
- FLAGS_large_board ? cv::aruco::DICT_5X5_250 : cv::aruco::DICT_6X6_250);
+ absl::GetFlag(FLAGS_large_board) ? cv::aruco::DICT_5X5_250
+ : cv::aruco::DICT_6X6_250);
if (target_type_ == TargetType::kCharuco) {
- LOG(INFO) << "Using " << (FLAGS_large_board ? "large" : "small")
+ LOG(INFO) << "Using "
+ << (absl::GetFlag(FLAGS_large_board) ? "large" : "small")
<< " charuco board with "
- << (FLAGS_coarse_pattern ? "coarse" : "fine") << " pattern";
- board_ =
- (FLAGS_large_board
- ? (FLAGS_coarse_pattern ? cv::aruco::CharucoBoard::create(
- 12, 9, 0.06, 0.04666, dictionary_)
- : cv::aruco::CharucoBoard::create(
- 25, 18, 0.03, 0.0233, dictionary_))
- : (FLAGS_coarse_pattern ? cv::aruco::CharucoBoard::create(
- 7, 5, 0.04, 0.025, dictionary_)
- // TODO(jim): Need to figure out what
- // size is for small board, fine pattern
- : cv::aruco::CharucoBoard::create(
- 7, 5, 0.03, 0.0233, dictionary_)));
- if (!FLAGS_board_template_path.empty()) {
+ << (absl::GetFlag(FLAGS_coarse_pattern) ? "coarse" : "fine")
+ << " pattern";
+ board_ = (absl::GetFlag(FLAGS_large_board)
+ ? (absl::GetFlag(FLAGS_coarse_pattern)
+ ? cv::aruco::CharucoBoard::create(
+ 12, 9, 0.06, 0.04666, dictionary_)
+ : cv::aruco::CharucoBoard::create(
+ 25, 18, 0.03, 0.0233, dictionary_))
+ : (absl::GetFlag(FLAGS_coarse_pattern)
+ ? cv::aruco::CharucoBoard::create(7, 5, 0.04, 0.025,
+ dictionary_)
+ // TODO(jim): Need to figure out what
+ // size is for small board, fine pattern
+ : cv::aruco::CharucoBoard::create(7, 5, 0.03, 0.0233,
+ dictionary_)));
+ if (!absl::GetFlag(FLAGS_board_template_path).empty()) {
cv::Mat board_image;
board_->draw(cv::Size(600, 500), board_image, 10, 1);
- cv::imwrite(FLAGS_board_template_path, board_image);
+ cv::imwrite(absl::GetFlag(FLAGS_board_template_path), board_image);
}
}
} else if (target_type_ == TargetType::kCharucoDiamond) {
@@ -244,7 +254,7 @@
// TODO<Jim>: Either track this down or reimplement drawAxes
if (result.z() < 0.01) {
LOG(INFO) << "Skipping, due to z value too small: " << result.z();
- } else if (FLAGS_draw_axes == true) {
+ } else if (absl::GetFlag(FLAGS_draw_axes) == true) {
result /= result.z();
if (target_type_ == TargetType::kCharuco ||
target_type_ == TargetType::kAprilTag) {
@@ -353,12 +363,13 @@
.count();
// Have found this useful if there is blurry / noisy images
- if (FLAGS_gray_threshold > 0) {
+ if (absl::GetFlag(FLAGS_gray_threshold) > 0) {
cv::Mat gray;
cv::cvtColor(rgb_image, gray, cv::COLOR_BGR2GRAY);
cv::Mat thresh;
- cv::threshold(gray, thresh, FLAGS_gray_threshold, 255, cv::THRESH_BINARY);
+ cv::threshold(gray, thresh, absl::GetFlag(FLAGS_gray_threshold), 255,
+ cv::THRESH_BINARY);
cv::cvtColor(thresh, rgb_image, cv::COLOR_GRAY2RGB);
}
@@ -382,7 +393,7 @@
std::vector<cv::Point2f> charuco_corners;
// If enough aruco markers detected for the Charuco board
- if (marker_ids.size() >= FLAGS_min_charucos) {
+ if (marker_ids.size() >= absl::GetFlag(FLAGS_min_charucos)) {
// Run everything twice, once with the calibration, and once
// without. This lets us both collect data to calibrate the
// intrinsics of the camera (to determine the intrinsics from
@@ -403,7 +414,7 @@
charuco_corners_with_calibration, charuco_ids_with_calibration,
calibration_.CameraIntrinsics(), calibration_.CameraDistCoeffs());
- if (charuco_ids.size() >= FLAGS_min_charucos) {
+ if (charuco_ids.size() >= absl::GetFlag(FLAGS_min_charucos)) {
cv::aruco::drawDetectedCornersCharuco(
rgb_image, charuco_corners, charuco_ids, cv::Scalar(255, 0, 0));
@@ -432,12 +443,14 @@
}
} else {
VLOG(2) << "Age: " << age_double << ", not enough charuco IDs, got "
- << charuco_ids.size() << ", needed " << FLAGS_min_charucos;
+ << charuco_ids.size() << ", needed "
+ << absl::GetFlag(FLAGS_min_charucos);
}
} else {
VLOG(2) << "Age: " << age_double
<< ", not enough marker IDs for charuco board, got "
- << marker_ids.size() << ", needed " << FLAGS_min_charucos;
+ << marker_ids.size() << ", needed "
+ << absl::GetFlag(FLAGS_min_charucos);
}
} else if (target_type_ == TargetType::kAruco ||
target_type_ == TargetType::kAprilTag) {
@@ -466,14 +479,15 @@
// Should be at least one, and no more than FLAGS_max_diamonds.
// Different calibration routines will require different values for this
if (diamond_ids.size() > 0 &&
- (FLAGS_max_diamonds == 0 ||
- diamond_ids.size() <= FLAGS_max_diamonds)) {
+ (absl::GetFlag(FLAGS_max_diamonds) == 0 ||
+ diamond_ids.size() <= absl::GetFlag(FLAGS_max_diamonds))) {
// TODO<Jim>: Could probably make this check more general than
// requiring range of ids
bool all_valid_ids = true;
for (uint i = 0; i < 4; i++) {
uint id = diamond_ids[0][i];
- if ((id < FLAGS_min_id) || (id > FLAGS_max_id)) {
+ if ((id < absl::GetFlag(FLAGS_min_id)) ||
+ (id > absl::GetFlag(FLAGS_max_id))) {
all_valid_ids = false;
LOG(INFO) << "Got invalid charuco id: " << id;
}
@@ -505,7 +519,8 @@
} else {
VLOG(2) << "Found too many number of diamond markers, which likely "
"means false positives were detected: "
- << diamond_ids.size() << " > " << FLAGS_max_diamonds;
+ << diamond_ids.size() << " > "
+ << absl::GetFlag(FLAGS_max_diamonds);
}
}
} else {
diff --git a/frc971/vision/charuco_lib.h b/frc971/vision/charuco_lib.h
index aac25ee..e53d129 100644
--- a/frc971/vision/charuco_lib.h
+++ b/frc971/vision/charuco_lib.h
@@ -15,7 +15,7 @@
#include "aos/network/message_bridge_server_generated.h"
#include "frc971/vision/calibration_generated.h"
-DECLARE_bool(visualize);
+ABSL_DECLARE_FLAG(bool, visualize);
namespace frc971::vision {
diff --git a/frc971/vision/foxglove_image_converter.cc b/frc971/vision/foxglove_image_converter.cc
index c004ac0..04f6030 100644
--- a/frc971/vision/foxglove_image_converter.cc
+++ b/frc971/vision/foxglove_image_converter.cc
@@ -1,20 +1,23 @@
+#include "absl/flags/flag.h"
+
#include "aos/events/shm_event_loop.h"
#include "aos/init.h"
#include "frc971/vision/foxglove_image_converter_lib.h"
-DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
-DEFINE_string(channel, "/camera", "Input/Output channel to use.");
+ABSL_FLAG(std::string, config, "aos_config.json",
+ "Path to the config file to use.");
+ABSL_FLAG(std::string, channel, "/camera", "Input/Output channel to use.");
int main(int argc, char *argv[]) {
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::FoxgloveImageConverter converter(
- &event_loop, FLAGS_channel, FLAGS_channel,
+ &event_loop, absl::GetFlag(FLAGS_channel), absl::GetFlag(FLAGS_channel),
frc971::vision::ImageCompression::kJpeg);
event_loop.Run();
diff --git a/frc971/vision/foxglove_image_converter_lib.cc b/frc971/vision/foxglove_image_converter_lib.cc
index 649f1bb..e6ebc4d 100644
--- a/frc971/vision/foxglove_image_converter_lib.cc
+++ b/frc971/vision/foxglove_image_converter_lib.cc
@@ -1,13 +1,14 @@
#include "frc971/vision/foxglove_image_converter_lib.h"
+#include "absl/flags/flag.h"
#include <opencv2/imgcodecs.hpp>
#include <opencv2/imgproc.hpp>
-DEFINE_int32(jpeg_quality, 60,
- "Compression quality of JPEGs, 0-100; lower numbers mean lower "
- "quality and resulting image sizes.");
-DEFINE_uint32(max_period_ms, 100,
- "Fastest period at which to convert images, to limit CPU usage.");
+ABSL_FLAG(int32_t, jpeg_quality, 60,
+ "Compression quality of JPEGs, 0-100; lower numbers mean lower "
+ "quality and resulting image sizes.");
+ABSL_FLAG(uint32_t, max_period_ms, 100,
+ "Fastest period at which to convert images, to limit CPU usage.");
namespace frc971::vision {
std::string_view ExtensionForCompression(ImageCompression compression) {
@@ -26,8 +27,9 @@
// imencode doesn't let us pass in anything other than an std::vector, and
// performance isn't yet a big enough issue to try to avoid the copy.
std::vector<uint8_t> buffer;
- CHECK(cv::imencode(absl::StrCat(".", format), image, buffer,
- {cv::IMWRITE_JPEG_QUALITY, FLAGS_jpeg_quality}));
+ CHECK(cv::imencode(
+ absl::StrCat(".", format), image, buffer,
+ {cv::IMWRITE_JPEG_QUALITY, absl::GetFlag(FLAGS_jpeg_quality)}));
const flatbuffers::Offset<flatbuffers::Vector<uint8_t>> data_offset =
fbb->CreateVector(buffer);
const struct timespec timestamp_t = aos::time::to_timespec(eof);
@@ -52,7 +54,7 @@
[this, compression](const cv::Mat image,
const aos::monotonic_clock::time_point eof) {
if (event_loop_->monotonic_now() >
- (std::chrono::milliseconds(FLAGS_max_period_ms) +
+ (std::chrono::milliseconds(absl::GetFlag(FLAGS_max_period_ms)) +
sender_.monotonic_sent_time())) {
auto builder = sender_.MakeBuilder();
builder.CheckOk(builder.Send(
diff --git a/frc971/vision/foxglove_image_converter_test.cc b/frc971/vision/foxglove_image_converter_test.cc
index c9c7d66..3059ad2 100644
--- a/frc971/vision/foxglove_image_converter_test.cc
+++ b/frc971/vision/foxglove_image_converter_test.cc
@@ -1,3 +1,5 @@
+#include "absl/flags/declare.h"
+#include "absl/flags/flag.h"
#include "gtest/gtest.h"
#include "aos/events/simulated_event_loop.h"
@@ -6,7 +8,7 @@
#include "aos/testing/tmpdir.h"
#include "frc971/vision/foxglove_image_converter_lib.h"
-DECLARE_int32(jpeg_quality);
+ABSL_DECLARE_FLAG(int32_t, jpeg_quality);
namespace frc971::vision {
std::ostream &operator<<(std::ostream &os, ImageCompression compression) {
@@ -34,7 +36,7 @@
// Because our test image for comparison was generated with a JPEG quality
// of 95, we need to use that for the test to work. This also protects the
// tests against future changes to the default JPEG quality.
- FLAGS_jpeg_quality = 95;
+ absl::SetFlag(&FLAGS_jpeg_quality, 95);
test_event_loop_->OnRun(
[this]() { image_sender_.CheckOk(image_sender_.Send(camera_image_)); });
test_event_loop_->MakeWatcher(
diff --git a/frc971/vision/geometry.h b/frc971/vision/geometry.h
index 3285446..f1495bc 100644
--- a/frc971/vision/geometry.h
+++ b/frc971/vision/geometry.h
@@ -3,7 +3,8 @@
#include <optional>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "opencv2/core/types.hpp"
#include "aos/util/math.h"
diff --git a/frc971/vision/geometry_test.cc b/frc971/vision/geometry_test.cc
index f34594c..070de12 100644
--- a/frc971/vision/geometry_test.cc
+++ b/frc971/vision/geometry_test.cc
@@ -2,7 +2,8 @@
#include <cmath>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "gtest/gtest.h"
#include "aos/util/math.h"
diff --git a/frc971/vision/image_logger.cc b/frc971/vision/image_logger.cc
index 2984824..cb8fc4e 100644
--- a/frc971/vision/image_logger.cc
+++ b/frc971/vision/image_logger.cc
@@ -1,8 +1,10 @@
#include <sys/resource.h>
#include <sys/time.h>
-#include "gflags/gflags.h"
-#include "glog/logging.h"
+#include "absl/flags/flag.h"
+#include "absl/flags/usage.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/configuration.h"
#include "aos/events/logging/log_writer.h"
@@ -12,16 +14,16 @@
#include "aos/util/filesystem_generated.h"
#include "frc971/input/joystick_state_generated.h"
-DEFINE_string(config, "aos_config.json", "Config file to use.");
+ABSL_FLAG(std::string, config, "aos_config.json", "Config file to use.");
-DEFINE_double(rotate_every, 0.0,
- "If set, rotate the logger after this many seconds");
-DECLARE_int32(flush_size);
-DEFINE_double(disabled_time, 5.0,
- "Continue logging if disabled for this amount of time or less");
-DEFINE_bool(direct, false,
- "If true, write using O_DIRECT and write 512 byte aligned blocks "
- "whenever possible.");
+ABSL_FLAG(double, rotate_every, 0.0,
+ "If set, rotate the logger after this many seconds");
+ABSL_DECLARE_FLAG(int32_t, flush_size);
+ABSL_FLAG(double, disabled_time, 5.0,
+ "Continue logging if disabled for this amount of time or less");
+ABSL_FLAG(bool, direct, false,
+ "If true, write using O_DIRECT and write 512 byte aligned blocks "
+ "whenever possible.");
std::unique_ptr<aos::logger::MultiNodeFilesLogNamer> MakeLogNamer(
aos::EventLoop *event_loop) {
@@ -33,19 +35,20 @@
}
return std::make_unique<aos::logger::MultiNodeFilesLogNamer>(
- event_loop, std::make_unique<aos::logger::RenamableFileBackend>(
- absl::StrCat(log_name.value(), "/"), FLAGS_direct));
+ event_loop,
+ std::make_unique<aos::logger::RenamableFileBackend>(
+ absl::StrCat(log_name.value(), "/"), absl::GetFlag(FLAGS_direct)));
}
int main(int argc, char *argv[]) {
- gflags::SetUsageMessage(
+ absl::SetProgramUsageMessage(
"This program provides a simple logger binary that logs all SHMEM data "
"directly to a file specified at the command line when the robot is "
"enabled and for a bit of time after.");
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());
@@ -60,11 +63,12 @@
event_loop.monotonic_now();
aos::logger::Logger logger(&event_loop);
- if (FLAGS_rotate_every != 0.0) {
+ if (absl::GetFlag(FLAGS_rotate_every) != 0.0) {
logger.set_on_logged_period([&](aos::monotonic_clock::time_point) {
const auto now = event_loop.monotonic_now();
- if (logging && now > last_rotation_time + std::chrono::duration<double>(
- FLAGS_rotate_every)) {
+ if (logging &&
+ now > last_rotation_time + std::chrono::duration<double>(
+ absl::GetFlag(FLAGS_rotate_every))) {
logger.Rotate();
last_rotation_time = now;
}
@@ -105,8 +109,9 @@
const bool should_be_logging =
(enabled ||
- timestamp < last_disable_time + std::chrono::duration<double>(
- FLAGS_disabled_time)) &&
+ timestamp <
+ last_disable_time + std::chrono::duration<double>(
+ absl::GetFlag(FLAGS_disabled_time))) &&
enough_space;
if (!logging && should_be_logging) {
diff --git a/frc971/vision/image_replay.cc b/frc971/vision/image_replay.cc
index 3b75c92..f4b3842 100644
--- a/frc971/vision/image_replay.cc
+++ b/frc971/vision/image_replay.cc
@@ -1,4 +1,4 @@
-#include "gflags/gflags.h"
+#include "absl/flags/flag.h"
#include "opencv2/highgui.hpp"
#include "opencv2/imgproc.hpp"
@@ -10,8 +10,8 @@
#include "aos/logging/log_message_generated.h"
#include "frc971/vision/vision_generated.h"
-DEFINE_string(node, "orin1", "The node to view the log from");
-DEFINE_string(channel, "/camera0", "The channel to view the log from");
+ABSL_FLAG(std::string, node, "orin1", "The node to view the log from");
+ABSL_FLAG(std::string, channel, "/camera0", "The channel to view the log from");
int main(int argc, char **argv) {
aos::InitGoogle(&argc, &argv);
@@ -23,11 +23,12 @@
aos::SimulatedEventLoopFactory factory(reader.configuration());
reader.Register(&factory);
- aos::NodeEventLoopFactory *node = factory.GetNodeEventLoopFactory(FLAGS_node);
+ aos::NodeEventLoopFactory *node =
+ factory.GetNodeEventLoopFactory(absl::GetFlag(FLAGS_node));
std::unique_ptr<aos::EventLoop> image_loop = node->MakeEventLoop("image");
image_loop->MakeWatcher(
- "/" + FLAGS_node + "/" + FLAGS_channel,
+ "/" + absl::GetFlag(FLAGS_node) + "/" + absl::GetFlag(FLAGS_channel),
[](const frc971::vision::CameraImage &msg) {
cv::Mat color_image(cv::Size(msg.cols(), msg.rows()), CV_8UC2,
(void *)msg.data()->data());
diff --git a/frc971/vision/intrinsics_calibration.cc b/frc971/vision/intrinsics_calibration.cc
index e0ec38c..eb5605b 100644
--- a/frc971/vision/intrinsics_calibration.cc
+++ b/frc971/vision/intrinsics_calibration.cc
@@ -1,6 +1,7 @@
#include <cmath>
#include <regex>
+#include "absl/flags/flag.h"
#include "absl/strings/str_format.h"
#include <opencv2/calib3d.hpp>
#include <opencv2/highgui/highgui.hpp>
@@ -14,32 +15,35 @@
#include "frc971/vision/intrinsics_calibration_lib.h"
// TODO: Would be nice to remove this, but it depends on year-by-year Constants
-DEFINE_string(base_intrinsics, "",
- "Intrinsics to use for estimating board pose prior to solving "
- "for the new intrinsics.");
-DEFINE_string(calibration_folder, ".", "Folder to place calibration files.");
-DEFINE_string(camera_id, "", "Camera ID in format YY-NN-- year and number.");
-DEFINE_string(channel, "/camera", "Camera channel to use");
-DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
-DEFINE_string(cpu_name, "", "Pi/Orin name to calibrate.");
-DEFINE_bool(display_undistorted, false,
- "If true, display the undistorted image.");
+ABSL_FLAG(std::string, base_intrinsics, "",
+ "Intrinsics to use for estimating board pose prior to solving "
+ "for the new intrinsics.");
+ABSL_FLAG(std::string, calibration_folder, ".",
+ "Folder to place calibration files.");
+ABSL_FLAG(std::string, camera_id, "",
+ "Camera ID in format YY-NN-- year and number.");
+ABSL_FLAG(std::string, channel, "/camera", "Camera channel to use");
+ABSL_FLAG(std::string, config, "aos_config.json",
+ "Path to the config file to use.");
+ABSL_FLAG(std::string, cpu_name, "", "Pi/Orin name to calibrate.");
+ABSL_FLAG(bool, display_undistorted, false,
+ "If true, display the undistorted image.");
namespace frc971::vision {
namespace {
void Main() {
aos::FlatbufferDetachedBuffer<aos::Configuration> config =
- aos::configuration::ReadConfig(FLAGS_config);
+ aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
aos::ShmEventLoop event_loop(&config.message());
- std::string hostname = FLAGS_cpu_name;
+ std::string hostname = absl::GetFlag(FLAGS_cpu_name);
if (hostname == "") {
hostname = aos::network::GetHostname();
LOG(INFO) << "Using pi/orin name from hostname as " << hostname;
}
- CHECK(!FLAGS_base_intrinsics.empty())
+ CHECK(!absl::GetFlag(FLAGS_base_intrinsics).empty())
<< "Need a base intrinsics json to use to auto-capture images when the "
"camera moves.";
std::unique_ptr<aos::ExitHandle> exit_handle = event_loop.MakeExitHandle();
@@ -54,18 +58,19 @@
std::string camera_name = absl::StrCat(
"/", aos::network::ParsePiOrOrin(hostname).value(),
std::to_string(aos::network::ParsePiOrOrinNumber(hostname).value()),
- FLAGS_channel);
+ absl::GetFlag(FLAGS_channel));
// THIS IS A HACK FOR 2024, since we call Orin2 "Imu"
if (aos::network::ParsePiOrOrin(hostname).value() == "orin" &&
aos::network::ParsePiOrOrinNumber(hostname).value() == 2) {
LOG(INFO) << "\nHACK for 2024: Renaming orin2 to imu\n";
- camera_name = absl::StrCat("/imu", FLAGS_channel);
+ camera_name = absl::StrCat("/imu", absl::GetFlag(FLAGS_channel));
}
- IntrinsicsCalibration extractor(&event_loop, hostname, camera_name,
- FLAGS_camera_id, FLAGS_base_intrinsics,
- FLAGS_display_undistorted,
- FLAGS_calibration_folder, exit_handle.get());
+ IntrinsicsCalibration extractor(
+ &event_loop, hostname, camera_name, absl::GetFlag(FLAGS_camera_id),
+ absl::GetFlag(FLAGS_base_intrinsics),
+ absl::GetFlag(FLAGS_display_undistorted),
+ absl::GetFlag(FLAGS_calibration_folder), exit_handle.get());
event_loop.Run();
diff --git a/frc971/vision/intrinsics_calibration_lib.cc b/frc971/vision/intrinsics_calibration_lib.cc
index 5584ed7..47e6929 100644
--- a/frc971/vision/intrinsics_calibration_lib.cc
+++ b/frc971/vision/intrinsics_calibration_lib.cc
@@ -1,6 +1,9 @@
#include "frc971/vision/intrinsics_calibration_lib.h"
-DECLARE_bool(visualize);
+#include "absl/flags/declare.h"
+#include "absl/flags/flag.h"
+
+ABSL_DECLARE_FLAG(bool, visualize);
namespace frc971::vision {
@@ -49,13 +52,13 @@
calibration_folder_(calibration_folder),
exit_handle_(exit_handle),
exit_collection_(false) {
- if (!FLAGS_visualize) {
+ if (!absl::GetFlag(FLAGS_visualize)) {
// The only way to exit into the calibration routines is by hitting "q"
// while visualization is running. The event_loop doesn't pause enough
// to handle ctrl-c exit requests
LOG(INFO) << "Setting visualize to true, since currently the intrinsics "
"only works this way";
- FLAGS_visualize = true;
+ absl::SetFlag(&FLAGS_visualize, true);
}
LOG(INFO) << "Hostname is: " << hostname_ << " and camera channel is "
<< camera_channel_;
@@ -73,7 +76,7 @@
std::vector<std::vector<cv::Point2f>> charuco_corners, bool valid,
std::vector<Eigen::Vector3d> rvecs_eigen,
std::vector<Eigen::Vector3d> tvecs_eigen) {
- if (FLAGS_visualize) {
+ if (absl::GetFlag(FLAGS_visualize)) {
// Reduce resolution displayed on remote viewer to prevent lag
cv::resize(rgb_image, rgb_image,
cv::Size(rgb_image.cols / 2, rgb_image.rows / 2));
diff --git a/frc971/vision/media_device.cc b/frc971/vision/media_device.cc
index 46f3419..c0f0ec4 100644
--- a/frc971/vision/media_device.cc
+++ b/frc971/vision/media_device.cc
@@ -13,9 +13,10 @@
#include <string_view>
#include <vector>
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "absl/strings/str_cat.h"
#include "absl/strings/str_split.h"
-#include "glog/logging.h"
#include "aos/scoped/scoped_fd.h"
#include "aos/util/file.h"
diff --git a/frc971/vision/media_device.h b/frc971/vision/media_device.h
index 31d0882..424a363 100644
--- a/frc971/vision/media_device.h
+++ b/frc971/vision/media_device.h
@@ -12,7 +12,8 @@
#include <string_view>
#include <vector>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/scoped/scoped_fd.h"
diff --git a/frc971/vision/modify_extrinsics.cc b/frc971/vision/modify_extrinsics.cc
index d021744..355f790 100644
--- a/frc971/vision/modify_extrinsics.cc
+++ b/frc971/vision/modify_extrinsics.cc
@@ -4,6 +4,7 @@
#include "Eigen/Dense"
#include "Eigen/Geometry"
+#include "absl/flags/flag.h"
#include "absl/strings/str_format.h"
#include "aos/configuration.h"
@@ -23,28 +24,30 @@
// By default, writes to /tmp, but will write to calib_files folder if
// full path is given and calibration_folder is blank
-DEFINE_string(orig_calib_file, "",
- "Intrinsics to use for estimating board pose prior to solving "
- "for the new intrinsics.");
-DEFINE_string(calibration_folder, "/tmp", "Folder to place calibration files.");
-DEFINE_string(node_name, "",
- "Node name to use, e.g. orin1, imu; unchanged if blank");
-DEFINE_int32(team_number, -1, "Team number to use; unchanged if -1");
-DEFINE_int32(camera_number, -1, "Camera number to use; unchanged if -1");
+ABSL_FLAG(std::string, orig_calib_file, "",
+ "Intrinsics to use for estimating board pose prior to solving "
+ "for the new intrinsics.");
+ABSL_FLAG(std::string, calibration_folder, "/tmp",
+ "Folder to place calibration files.");
+ABSL_FLAG(std::string, node_name, "",
+ "Node name to use, e.g. orin1, imu; unchanged if blank");
+ABSL_FLAG(int32_t, team_number, -1, "Team number to use; unchanged if -1");
+ABSL_FLAG(int32_t, camera_number, -1, "Camera number to use; unchanged if -1");
-DEFINE_bool(set_extrinsics, true, "Set to false to ignore extrinsic data");
-DEFINE_bool(use_inches, true,
- "Whether to use inches as units (meters if false)");
-DEFINE_bool(use_degrees, true,
- "Whether to use degrees as units (radians if false)");
-DEFINE_double(camera_x, 0.0, "x location of camera");
-DEFINE_double(camera_y, 0.0, "y location of camera");
-DEFINE_double(camera_z, 0.0, "z location of camera");
+ABSL_FLAG(bool, set_extrinsics, true, "Set to false to ignore extrinsic data");
+ABSL_FLAG(bool, use_inches, true,
+ "Whether to use inches as units (meters if false)");
+ABSL_FLAG(bool, use_degrees, true,
+ "Whether to use degrees as units (radians if false)");
+ABSL_FLAG(double, camera_x, 0.0, "x location of camera");
+ABSL_FLAG(double, camera_y, 0.0, "y location of camera");
+ABSL_FLAG(double, camera_z, 0.0, "z location of camera");
// Don't currently allow for roll of cameras
-DEFINE_double(camera_yaw, 0.0, "yaw of camera about robot z axis");
-DEFINE_double(camera_pitch, 0.0, "pitch of camera relative to robot y axis");
+ABSL_FLAG(double, camera_yaw, 0.0, "yaw of camera about robot z axis");
+ABSL_FLAG(double, camera_pitch, 0.0,
+ "pitch of camera relative to robot y axis");
// TODO: This could be done by setting the pixel size and using the intrinsics
-DEFINE_double(focal_length, 0.002, "Focal length in meters");
+ABSL_FLAG(double, focal_length, 0.002, "Focal length in meters");
namespace frc971::vision {
namespace {
@@ -74,30 +77,34 @@
// If we're told to set the extrinsics, clear old and add in new
flatbuffers::Offset<calibration::TransformationMatrix>
fixed_extrinsics_offset;
- if (FLAGS_set_extrinsics) {
+ if (absl::GetFlag(FLAGS_set_extrinsics)) {
cal_copy.mutable_message()->clear_fixed_extrinsics();
Eigen::Affine3d extrinsic_matrix;
// Convert to metric
- double translation_scale = (FLAGS_use_inches ? 0.0254 : 1.0);
- Eigen::Translation3d translation(FLAGS_camera_x * translation_scale,
- FLAGS_camera_y * translation_scale,
- FLAGS_camera_z * translation_scale);
+ double translation_scale = (absl::GetFlag(FLAGS_use_inches) ? 0.0254 : 1.0);
+ Eigen::Translation3d translation(
+ absl::GetFlag(FLAGS_camera_x) * translation_scale,
+ absl::GetFlag(FLAGS_camera_y) * translation_scale,
+ absl::GetFlag(FLAGS_camera_z) * translation_scale);
// convert to radians
- double angle_scale = (FLAGS_use_degrees ? M_PI / 180.0 : 1.0);
+ double angle_scale =
+ (absl::GetFlag(FLAGS_use_degrees) ? M_PI / 180.0 : 1.0);
// The rotation that takes robot coordinates (x forward, z up) to camera
// coordiantes (z forward, x right)
Eigen::Quaterniond R_robo_cam =
Eigen::AngleAxisd(-M_PI / 2.0, Eigen::Vector3d::UnitZ()) *
Eigen::AngleAxisd(-M_PI / 2.0, Eigen::Vector3d::UnitX());
- Eigen::AngleAxisd pitchAngle(FLAGS_camera_pitch * angle_scale,
- Eigen::Vector3d::UnitY());
- Eigen::AngleAxisd yawAngle(FLAGS_camera_yaw * angle_scale,
+ Eigen::AngleAxisd pitchAngle(
+ absl::GetFlag(FLAGS_camera_pitch) * angle_scale,
+ Eigen::Vector3d::UnitY());
+ Eigen::AngleAxisd yawAngle(absl::GetFlag(FLAGS_camera_yaw) * angle_scale,
Eigen::Vector3d::UnitZ());
Eigen::Quaterniond rotation = yawAngle * pitchAngle * R_robo_cam;
Eigen::Vector3d focal_length_offset =
- (rotation * Eigen::Translation3d(0.0, 0.0, FLAGS_focal_length))
+ (rotation *
+ Eigen::Translation3d(0.0, 0.0, absl::GetFlag(FLAGS_focal_length)))
.translation();
translation = translation * Eigen::Translation3d(focal_length_offset);
@@ -113,7 +120,7 @@
calibration::CameraCalibration::Builder camera_calibration_builder(fbb);
camera_calibration_builder.add_node_name(node_name_offset);
camera_calibration_builder.add_team_number(team_number);
- if (FLAGS_set_extrinsics) {
+ if (absl::GetFlag(FLAGS_set_extrinsics)) {
camera_calibration_builder.add_fixed_extrinsics(fixed_extrinsics_offset);
}
camera_calibration_builder.add_camera_number(camera_number);
@@ -136,15 +143,15 @@
orig_calib_filename);
// Populate the new variables from command-line or from base_calibration
- std::string node_name =
- (FLAGS_node_name == "" ? base_calibration.message().node_name()->str()
- : FLAGS_node_name);
- int team_number =
- (FLAGS_team_number == -1 ? base_calibration.message().team_number()
- : FLAGS_team_number);
- int camera_number =
- (FLAGS_camera_number == -1 ? base_calibration.message().camera_number()
- : FLAGS_camera_number);
+ std::string node_name = (absl::GetFlag(FLAGS_node_name) == ""
+ ? base_calibration.message().node_name()->str()
+ : absl::GetFlag(FLAGS_node_name));
+ int team_number = (absl::GetFlag(FLAGS_team_number) == -1
+ ? base_calibration.message().team_number()
+ : absl::GetFlag(FLAGS_team_number));
+ int camera_number = (absl::GetFlag(FLAGS_camera_number) == -1
+ ? base_calibration.message().camera_number()
+ : absl::GetFlag(FLAGS_camera_number));
aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
new_calibration = BuildCalibration(&base_calibration.message(), node_name,
camera_number, team_number);
@@ -158,9 +165,9 @@
std::string camera_id = base_calibration.message().camera_id()->str();
const std::string dirname =
- (FLAGS_calibration_folder == ""
+ (absl::GetFlag(FLAGS_calibration_folder) == ""
? std::filesystem::path(orig_calib_filename).parent_path().string()
- : FLAGS_calibration_folder);
+ : absl::GetFlag(FLAGS_calibration_folder));
const std::string new_calib_filename = frc971::vision::CalibrationFilename(
dirname, node_name.c_str(), team_number, camera_number, camera_id.c_str(),
time_ss.str());
diff --git a/frc971/vision/target_mapper.cc b/frc971/vision/target_mapper.cc
index f245f37..36f0a29 100644
--- a/frc971/vision/target_mapper.cc
+++ b/frc971/vision/target_mapper.cc
@@ -6,25 +6,26 @@
#include "frc971/vision/ceres/pose_graph_3d_error_term.h"
#include "frc971/vision/geometry.h"
-DEFINE_uint64(max_num_iterations, 100,
- "Maximum number of iterations for the ceres solver");
-DEFINE_double(distortion_noise_scalar, 1.0,
- "Scale the target pose distortion factor by this when computing "
- "the noise.");
-DEFINE_int32(
- frozen_target_id, 1,
+ABSL_FLAG(uint64_t, max_num_iterations, 100,
+ "Maximum number of iterations for the ceres solver");
+ABSL_FLAG(double, distortion_noise_scalar, 1.0,
+ "Scale the target pose distortion factor by this when computing "
+ "the noise.");
+ABSL_FLAG(
+ int32_t, frozen_target_id, 1,
"Freeze the pose of this target so the map can have one fixed point.");
-DEFINE_int32(min_target_id, 1, "Minimum target id to solve for");
-DEFINE_int32(max_target_id, 8, "Maximum target id to solve for");
-DEFINE_bool(visualize_solver, false, "If true, visualize the solving process.");
+ABSL_FLAG(int32_t, min_target_id, 1, "Minimum target id to solve for");
+ABSL_FLAG(int32_t, max_target_id, 8, "Maximum target id to solve for");
+ABSL_FLAG(bool, visualize_solver, false,
+ "If true, visualize the solving process.");
// This does seem like a strict threshold for a constaint to be considered an
// outlier, but most inliers were very close together and this is what worked
// best for map solving.
-DEFINE_double(outlier_std_devs, 1.0,
- "Number of standard deviations above average error needed for a "
- "constraint to be considered an outlier and get removed.");
-DEFINE_bool(do_map_fitting, false,
- "Whether to do a final fit of the solved map to the original map");
+ABSL_FLAG(double, outlier_std_devs, 1.0,
+ "Number of standard deviations above average error needed for a "
+ "constraint to be considered an outlier and get removed.");
+ABSL_FLAG(bool, do_map_fitting, false,
+ "Whether to do a final fit of the solved map to the original map");
namespace frc971::vision {
Eigen::Affine3d PoseUtils::Pose3dToAffine3d(
@@ -192,14 +193,16 @@
Q_vision(kOrientation3, kOrientation3) = std::pow(0.02, 2);
// Add uncertainty for the 2 vision measurements (1 at start and 1 at end)
- P += Q_vision * std::pow(detection_start.distance_from_camera *
- (1.0 + FLAGS_distortion_noise_scalar *
- detection_start.distortion_factor),
- 2);
- P += Q_vision * std::pow(detection_end.distance_from_camera *
- (1.0 + FLAGS_distortion_noise_scalar *
- detection_end.distortion_factor),
- 2);
+ P += Q_vision *
+ std::pow(detection_start.distance_from_camera *
+ (1.0 + absl::GetFlag(FLAGS_distortion_noise_scalar) *
+ detection_start.distortion_factor),
+ 2);
+ P += Q_vision *
+ std::pow(detection_end.distance_from_camera *
+ (1.0 + absl::GetFlag(FLAGS_distortion_noise_scalar) *
+ detection_end.distortion_factor),
+ 2);
}
return P.inverse();
@@ -381,16 +384,17 @@
// algorithm has internal damping which mitigates this issue, but it is
// better to properly constrain the gauge freedom. This can be done by
// setting one of the poses as constant so the optimizer cannot change it.
- CHECK_NE(poses->count(FLAGS_frozen_target_id), 0ul)
- << "Got no poses for frozen target id " << FLAGS_frozen_target_id;
- CHECK_GE(FLAGS_frozen_target_id, min_constraint_id)
- << "target to freeze index " << FLAGS_frozen_target_id
+ CHECK_NE(poses->count(absl::GetFlag(FLAGS_frozen_target_id)), 0ul)
+ << "Got no poses for frozen target id "
+ << absl::GetFlag(FLAGS_frozen_target_id);
+ CHECK_GE(absl::GetFlag(FLAGS_frozen_target_id), min_constraint_id)
+ << "target to freeze index " << absl::GetFlag(FLAGS_frozen_target_id)
<< " must be in range of constraints, > " << min_constraint_id;
- CHECK_LE(FLAGS_frozen_target_id, max_constraint_id)
- << "target to freeze index " << FLAGS_frozen_target_id
+ CHECK_LE(absl::GetFlag(FLAGS_frozen_target_id), max_constraint_id)
+ << "target to freeze index " << absl::GetFlag(FLAGS_frozen_target_id)
<< " must be in range of constraints, < " << max_constraint_id;
ceres::examples::MapOfPoses::iterator pose_start_iter =
- poses->find(FLAGS_frozen_target_id);
+ poses->find(absl::GetFlag(FLAGS_frozen_target_id));
CHECK(pose_start_iter != poses->end()) << "There are no poses.";
problem->SetParameterBlockConstant(pose_start_iter->second.p.data());
problem->SetParameterBlockConstant(pose_start_iter->second.q.coeffs().data());
@@ -401,7 +405,8 @@
// Set up robot visualization.
vis_robot_.ClearImage();
- const size_t num_targets = FLAGS_max_target_id - FLAGS_min_target_id;
+ const size_t num_targets =
+ absl::GetFlag(FLAGS_max_target_id) - absl::GetFlag(FLAGS_min_target_id);
// Translation and rotation error for each target
const size_t num_residuals = num_targets * 6;
// Set up the only cost function (also known as residual). This uses
@@ -470,7 +475,7 @@
CHECK(problem != nullptr);
ceres::Solver::Options options;
- options.max_num_iterations = FLAGS_max_num_iterations;
+ options.max_num_iterations = absl::GetFlag(FLAGS_max_num_iterations);
options.linear_solver_type = ceres::SPARSE_NORMAL_CHOLESKY;
options.minimizer_progress_to_stdout = false;
@@ -489,7 +494,7 @@
&target_pose_problem_1);
CHECK(SolveOptimizationProblem(&target_pose_problem_1))
<< "The target pose solve 1 was not successful, exiting.";
- if (FLAGS_visualize_solver) {
+ if (absl::GetFlag(FLAGS_visualize_solver)) {
LOG(INFO) << "Displaying constraint graph before removing outliers";
DisplayConstraintGraph();
DisplaySolvedVsInitial();
@@ -503,13 +508,13 @@
&target_pose_problem_2);
CHECK(SolveOptimizationProblem(&target_pose_problem_2))
<< "The target pose solve 2 was not successful, exiting.";
- if (FLAGS_visualize_solver) {
+ if (absl::GetFlag(FLAGS_visualize_solver)) {
LOG(INFO) << "Displaying constraint graph before removing outliers";
DisplayConstraintGraph();
DisplaySolvedVsInitial();
}
- if (FLAGS_do_map_fitting) {
+ if (absl::GetFlag(FLAGS_do_map_fitting)) {
LOG(INFO) << "Solving the overall map's best alignment to the previous map";
ceres::Problem map_fitting_problem(
{.loss_function_ownership = ceres::DO_NOT_TAKE_OWNERSHIP});
@@ -523,14 +528,15 @@
LOG(INFO) << "H_frozen_actual: "
<< PoseUtils::Affine3dToPose3d(H_frozen_actual);
- auto H_world_frozen =
- PoseUtils::Pose3dToAffine3d(target_poses_[FLAGS_frozen_target_id]);
+ auto H_world_frozen = PoseUtils::Pose3dToAffine3d(
+ target_poses_[absl::GetFlag(FLAGS_frozen_target_id)]);
auto H_world_frozenactual = H_world_frozen * H_frozen_actual;
// Offset the solved poses to become the actual ones
for (auto &[id, pose] : target_poses_) {
// Don't offset targets we didn't solve for
- if (id < FLAGS_min_target_id || id > FLAGS_max_target_id) {
+ if (id < absl::GetFlag(FLAGS_min_target_id) ||
+ id > absl::GetFlag(FLAGS_max_target_id)) {
continue;
}
@@ -553,10 +559,10 @@
aos::util::WriteStringToFileOrDie(output_path, map_json);
}
- for (TargetId id_start = FLAGS_min_target_id; id_start < FLAGS_max_target_id;
- id_start++) {
- for (TargetId id_end = id_start + 1; id_end <= FLAGS_max_target_id;
- id_end++) {
+ for (TargetId id_start = absl::GetFlag(FLAGS_min_target_id);
+ id_start < absl::GetFlag(FLAGS_max_target_id); id_start++) {
+ for (TargetId id_end = id_start + 1;
+ id_end <= absl::GetFlag(FLAGS_max_target_id); id_end++) {
auto H_start_end =
PoseUtils::Pose3dToAffine3d(target_poses_.at(id_start)).inverse() *
PoseUtils::Pose3dToAffine3d(target_poses_.at(id_end));
@@ -622,17 +628,19 @@
<< PoseUtils::Affine3dToPose3d(ScalarAffineToDouble(H_frozen_actual));
Affine3s H_world_frozen =
- PoseUtils::Pose3dToAffine3d(target_poses_.at(FLAGS_frozen_target_id))
+ PoseUtils::Pose3dToAffine3d(
+ target_poses_.at(absl::GetFlag(FLAGS_frozen_target_id)))
.cast<S>();
Affine3s H_world_frozenactual = H_world_frozen * H_frozen_actual;
size_t residual_index = 0;
- if (FLAGS_visualize_solver) {
+ if (absl::GetFlag(FLAGS_visualize_solver)) {
vis_robot_.ClearImage();
}
for (const auto &[id, solved_pose] : target_poses_) {
- if (id < FLAGS_min_target_id || id > FLAGS_max_target_id) {
+ if (id < absl::GetFlag(FLAGS_min_target_id) ||
+ id > absl::GetFlag(FLAGS_max_target_id)) {
continue;
}
@@ -669,7 +677,7 @@
residual[residual_index++] =
kRotationScalar * R_ideal_actual.angle() * R_ideal_actual.axis().z();
- if (FLAGS_visualize_solver) {
+ if (absl::GetFlag(FLAGS_visualize_solver)) {
LOG(INFO) << std::to_string(id) + std::string("-est") << " at "
<< ScalarAffineToDouble(H_world_actual).matrix();
vis_robot_.DrawFrameAxes(ScalarAffineToDouble(H_world_actual),
@@ -679,7 +687,7 @@
std::to_string(id), cv::Scalar(255, 255, 255));
}
}
- if (FLAGS_visualize_solver) {
+ if (absl::GetFlag(FLAGS_visualize_solver)) {
cv::imshow("Target maps", vis_robot_.image_);
cv::waitKey(0);
}
@@ -763,12 +771,12 @@
// Remove constraints with errors significantly above
// the average
if (err.distance > stats_with_outliers_.avg_err.distance +
- FLAGS_outlier_std_devs *
+ absl::GetFlag(FLAGS_outlier_std_devs) *
stats_with_outliers_.std_dev.distance) {
return true;
}
if (err.angle > stats_with_outliers_.avg_err.angle +
- FLAGS_outlier_std_devs *
+ absl::GetFlag(FLAGS_outlier_std_devs) *
stats_with_outliers_.std_dev.angle) {
return true;
}
@@ -812,14 +820,15 @@
LOG(INFO) << "Dumping target constraints to " << path;
std::ofstream fout(path.data());
for (const auto &constraint : target_constraints_) {
- fout << constraint << std::endl;
+ fout << absl::StrCat("", constraint) << std::endl;
}
fout.flush();
fout.close();
}
void TargetMapper::PrintDiffs() const {
- for (int id = FLAGS_min_target_id; id <= FLAGS_max_target_id; id++) {
+ for (int id = absl::GetFlag(FLAGS_min_target_id);
+ id <= absl::GetFlag(FLAGS_max_target_id); id++) {
Eigen::Affine3d H_world_ideal =
PoseUtils::Pose3dToAffine3d(ideal_target_poses_.at(id));
Eigen::Affine3d H_world_solved =
@@ -839,20 +848,3 @@
}
} // namespace frc971::vision
-
-std::ostream &operator<<(std::ostream &os, ceres::examples::Pose3d pose) {
- auto rpy = frc971::vision::PoseUtils::QuaternionToEulerAngles(pose.q);
- os << absl::StrFormat(
- "{x: %.3f, y: %.3f, z: %.3f, roll: %.3f, pitch: "
- "%.3f, yaw: %.3f}",
- pose.p(0), pose.p(1), pose.p(2), rpy(0), rpy(1), rpy(2));
- return os;
-}
-
-std::ostream &operator<<(std::ostream &os,
- ceres::examples::Constraint3d constraint) {
- os << absl::StrFormat("{id_begin: %d, id_end: %d, pose: ",
- constraint.id_begin, constraint.id_end)
- << constraint.t_be << "}";
- return os;
-}
diff --git a/frc971/vision/target_mapper.h b/frc971/vision/target_mapper.h
index d1d122e..cae1c69 100644
--- a/frc971/vision/target_mapper.h
+++ b/frc971/vision/target_mapper.h
@@ -3,6 +3,7 @@
#include <unordered_map>
+#include "absl/strings/str_format.h"
#include "ceres/ceres.h"
#include "aos/events/simulated_event_loop.h"
@@ -215,8 +216,23 @@
} // namespace frc971::vision
-std::ostream &operator<<(std::ostream &os, ceres::examples::Pose3d pose);
-std::ostream &operator<<(std::ostream &os,
- ceres::examples::Constraint3d constraint);
+namespace ceres::examples {
+template <typename Sink>
+void AbslStringify(Sink &sink, ceres::examples::Pose3d pose) {
+ auto rpy = frc971::vision::PoseUtils::QuaternionToEulerAngles(pose.q);
+ absl::Format(&sink,
+ "{x: %.3f, y: %.3f, z: %.3f, roll: %.3f, pitch: "
+ "%.3f, yaw: %.3f}",
+ pose.p(0), pose.p(1), pose.p(2), rpy(0), rpy(1), rpy(2));
+}
+
+template <typename Sink>
+void AbslStringify(Sink &sink, ceres::examples::Constraint3d constraint) {
+ absl::Format(&sink, "{id_begin: %d, id_end: %d, pose: ", constraint.id_begin,
+ constraint.id_end);
+ AbslStringify(sink, constraint.t_be);
+ sink.Append("}");
+}
+} // namespace ceres::examples
#endif // FRC971_VISION_TARGET_MAPPER_H_
diff --git a/frc971/vision/target_mapper_test.cc b/frc971/vision/target_mapper_test.cc
index 8c6d37d..4e9db6f 100644
--- a/frc971/vision/target_mapper_test.cc
+++ b/frc971/vision/target_mapper_test.cc
@@ -2,7 +2,10 @@
#include <random>
-#include "glog/logging.h"
+#include "absl/flags/declare.h"
+#include "absl/flags/flag.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "gtest/gtest.h"
#include "aos/events/simulated_event_loop.h"
@@ -10,8 +13,8 @@
#include "aos/testing/random_seed.h"
#include "aos/util/math.h"
-DECLARE_int32(min_target_id);
-DECLARE_int32(max_target_id);
+ABSL_DECLARE_FLAG(int32_t, min_target_id);
+ABSL_DECLARE_FLAG(int32_t, max_target_id);
namespace frc971::vision {
@@ -342,8 +345,8 @@
}
TEST(TargetMapperTest, TwoTargetsOneConstraint) {
- FLAGS_min_target_id = 0;
- FLAGS_max_target_id = 1;
+ absl::SetFlag(&FLAGS_min_target_id, 0);
+ absl::SetFlag(&FLAGS_max_target_id, 1);
ceres::examples::MapOfPoses target_poses;
target_poses[0] = Make2dPose(5.0, 0.0, M_PI);
@@ -368,8 +371,8 @@
}
TEST(TargetMapperTest, TwoTargetsTwoConstraints) {
- FLAGS_min_target_id = 0;
- FLAGS_max_target_id = 1;
+ absl::SetFlag(&FLAGS_min_target_id, 0);
+ absl::SetFlag(&FLAGS_max_target_id, 1);
ceres::examples::MapOfPoses target_poses;
target_poses[0] = Make2dPose(5.0, 0.0, M_PI);
@@ -400,8 +403,8 @@
}
TEST(TargetMapperTest, TwoTargetsOneNoisyConstraint) {
- FLAGS_min_target_id = 0;
- FLAGS_max_target_id = 1;
+ absl::SetFlag(&FLAGS_min_target_id, 0);
+ absl::SetFlag(&FLAGS_max_target_id, 1);
ceres::examples::MapOfPoses target_poses;
target_poses[0] = Make2dPose(5.0, 0.0, M_PI);
@@ -486,8 +489,8 @@
// when freeing memory. For some reason this segfault occurs only in this test,
// but when running the test with gdb it doesn't occur...
TEST_F(ChargedUpTargetMapperTest, DISABLED_FieldCircleMotion) {
- FLAGS_min_target_id = 1;
- FLAGS_max_target_id = 8;
+ absl::SetFlag(&FLAGS_min_target_id, 1);
+ absl::SetFlag(&FLAGS_max_target_id, 8);
// Read target map
auto target_map_fbs = aos::JsonFileToFlatbuffer<TargetMap>(
diff --git a/frc971/vision/v4l2_reader.cc b/frc971/vision/v4l2_reader.cc
index 2d67c9c..e333dc5 100644
--- a/frc971/vision/v4l2_reader.cc
+++ b/frc971/vision/v4l2_reader.cc
@@ -6,8 +6,10 @@
#include <sys/stat.h>
#include <sys/types.h>
-DEFINE_bool(ignore_timestamps, false,
- "Don't require timestamps on images. Used to allow webcams");
+#include "absl/flags/flag.h"
+
+ABSL_FLAG(bool, ignore_timestamps, false,
+ "Don't require timestamps on images. Used to allow webcams");
namespace frc971::vision {
@@ -233,7 +235,7 @@
CHECK_EQ(ImageSize(), buffer.length);
}
CHECK(buffer.flags & V4L2_BUF_FLAG_TIMESTAMP_MONOTONIC);
- if (!FLAGS_ignore_timestamps) {
+ if (!absl::GetFlag(FLAGS_ignore_timestamps)) {
// Require that we have good timestamp on images
CHECK_EQ(buffer.flags & V4L2_BUF_FLAG_TSTAMP_SRC_MASK,
static_cast<uint32_t>(V4L2_BUF_FLAG_TSTAMP_SRC_EOF));
diff --git a/frc971/vision/v4l2_reader.h b/frc971/vision/v4l2_reader.h
index 4906d8e..01634e2 100644
--- a/frc971/vision/v4l2_reader.h
+++ b/frc971/vision/v4l2_reader.h
@@ -4,8 +4,8 @@
#include <array>
#include <string>
+#include "absl/log/check.h"
#include "absl/types/span.h"
-#include "glog/logging.h"
#include "aos/containers/ring_buffer.h"
#include "aos/events/epoll.h"
diff --git a/frc971/vision/vision_util_lib.cc b/frc971/vision/vision_util_lib.cc
index 45aa199..089f3ac 100644
--- a/frc971/vision/vision_util_lib.cc
+++ b/frc971/vision/vision_util_lib.cc
@@ -1,7 +1,8 @@
#include "frc971/vision/vision_util_lib.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "absl/strings/str_format.h"
-#include "glog/logging.h"
namespace frc971::vision {
diff --git a/frc971/vision/visualize_robot.cc b/frc971/vision/visualize_robot.cc
index d13668e..52a7695 100644
--- a/frc971/vision/visualize_robot.cc
+++ b/frc971/vision/visualize_robot.cc
@@ -1,6 +1,7 @@
#include "frc971/vision/visualize_robot.h"
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include <opencv2/calib3d.hpp>
#include <opencv2/core/eigen.hpp>
#include <opencv2/highgui/highgui.hpp>
diff --git a/frc971/vision/visualize_robot_sample.cc b/frc971/vision/visualize_robot_sample.cc
index ad1d6b6..6e15f2f 100644
--- a/frc971/vision/visualize_robot_sample.cc
+++ b/frc971/vision/visualize_robot_sample.cc
@@ -1,7 +1,8 @@
#include <math.h>
#include "Eigen/Dense"
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include <opencv2/aruco.hpp>
#include <opencv2/aruco/charuco.hpp>
#include <opencv2/calib3d.hpp>
diff --git a/frc971/wpilib/ADIS16470.cc b/frc971/wpilib/ADIS16470.cc
index 0b3d45c..f5e2a57 100644
--- a/frc971/wpilib/ADIS16470.cc
+++ b/frc971/wpilib/ADIS16470.cc
@@ -2,7 +2,8 @@
#include <cinttypes>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/containers/sized_array.h"
#include "aos/time/time.h"
diff --git a/frc971/wpilib/BUILD b/frc971/wpilib/BUILD
index 461eb4a..cfbf18e 100644
--- a/frc971/wpilib/BUILD
+++ b/frc971/wpilib/BUILD
@@ -314,7 +314,8 @@
"//aos/events:event_loop",
"//aos/time",
"//third_party:wpilib",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
"@com_google_absl//absl/types:span",
],
)
@@ -432,7 +433,8 @@
"//aos/time",
"//aos/util:compiler_memory_barrier",
"//third_party:wpilib",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
)
@@ -506,7 +508,8 @@
"//aos/logging",
"//frc971/control_loops/drivetrain:drivetrain_can_position_fbs",
"//third_party:phoenix6",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
)
@@ -571,6 +574,6 @@
"//aos:init",
"//aos/events:shm_event_loop",
"//frc971/input:joystick_state_fbs",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/flags:flag",
],
)
diff --git a/frc971/wpilib/ahal/DigitalGlitchFilter.cc b/frc971/wpilib/ahal/DigitalGlitchFilter.cc
index 2b48fc9..811ee8d 100644
--- a/frc971/wpilib/ahal/DigitalGlitchFilter.cc
+++ b/frc971/wpilib/ahal/DigitalGlitchFilter.cc
@@ -10,7 +10,8 @@
#include <algorithm>
#include <array>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "frc971/wpilib/ahal/Counter.h"
#include "frc971/wpilib/ahal/Encoder.h"
diff --git a/frc971/wpilib/ahal/InterruptableSensorBase.cc b/frc971/wpilib/ahal/InterruptableSensorBase.cc
index 06ee513..4f2d877 100644
--- a/frc971/wpilib/ahal/InterruptableSensorBase.cc
+++ b/frc971/wpilib/ahal/InterruptableSensorBase.cc
@@ -7,7 +7,8 @@
#include "frc971/wpilib/ahal/InterruptableSensorBase.h"
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "frc971/wpilib/ahal/WPIErrors.h"
#include "hal/HAL.h"
diff --git a/frc971/wpilib/ahal/PWM.cc b/frc971/wpilib/ahal/PWM.cc
index 72219aa..3ff75d1 100644
--- a/frc971/wpilib/ahal/PWM.cc
+++ b/frc971/wpilib/ahal/PWM.cc
@@ -9,7 +9,8 @@
#include <sstream>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "frc971/wpilib/ahal/PWM.h"
#include "frc971/wpilib/ahal/WPIErrors.h"
diff --git a/frc971/wpilib/ahal/WPIErrors.h b/frc971/wpilib/ahal/WPIErrors.h
index 601e65a..8a81e1a 100644
--- a/frc971/wpilib/ahal/WPIErrors.h
+++ b/frc971/wpilib/ahal/WPIErrors.h
@@ -9,7 +9,8 @@
#include <cstdint>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#ifdef WPI_ERRORS_DEFINE_STRINGS
#define S(label, offset, message) \
diff --git a/frc971/wpilib/dma.cc b/frc971/wpilib/dma.cc
index 2d40aa9..9e716d1 100644
--- a/frc971/wpilib/dma.cc
+++ b/frc971/wpilib/dma.cc
@@ -4,7 +4,8 @@
#include <cstring>
#include <type_traits>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "frc971/wpilib/ahal/AnalogInput.h"
#include "frc971/wpilib/ahal/DigitalSource.h"
diff --git a/frc971/wpilib/fpga_time_conversion.h b/frc971/wpilib/fpga_time_conversion.h
index c279089..af80321 100644
--- a/frc971/wpilib/fpga_time_conversion.h
+++ b/frc971/wpilib/fpga_time_conversion.h
@@ -4,7 +4,8 @@
#include <chrono>
#include <optional>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/time/time.h"
#include "hal/cpp/fpga_clock.h"
diff --git a/frc971/wpilib/joystick_republish.cc b/frc971/wpilib/joystick_republish.cc
index ae6f340..9ea6a1a 100644
--- a/frc971/wpilib/joystick_republish.cc
+++ b/frc971/wpilib/joystick_republish.cc
@@ -1,7 +1,7 @@
#include <sys/resource.h>
#include <sys/time.h>
-#include "glog/logging.h"
+#include "absl/flags/flag.h"
#include "aos/configuration.h"
#include "aos/events/shm_event_loop.h"
@@ -9,13 +9,13 @@
#include "aos/init.h"
#include "frc971/input/joystick_state_generated.h"
-DEFINE_string(config, "aos_config.json", "Config file to use.");
+ABSL_FLAG(std::string, config, "aos_config.json", "Config file to use.");
int main(int argc, char *argv[]) {
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());
aos::Sender<aos::JoystickState> sender(
diff --git a/frc971/wpilib/sensor_reader.cc b/frc971/wpilib/sensor_reader.cc
index 1c8c5d3..3efe122 100644
--- a/frc971/wpilib/sensor_reader.cc
+++ b/frc971/wpilib/sensor_reader.cc
@@ -4,6 +4,8 @@
#include <cinttypes>
+#include "absl/flags/flag.h"
+
#include "aos/init.h"
#include "aos/logging/logging.h"
#include "aos/realtime.h"
@@ -14,8 +16,8 @@
#include "frc971/wpilib/wpilib_interface.h"
#include "hal/PWM.h"
-DEFINE_int32(pwm_offset, 5050 / 2,
- "Offset of reading the sensors from the start of the PWM cycle");
+ABSL_FLAG(int32_t, pwm_offset, 5050 / 2,
+ "Offset of reading the sensors from the start of the PWM cycle");
namespace frc971::wpilib {
@@ -164,11 +166,12 @@
}
last_tick_timepoint +=
- ((monotonic_now - chrono::microseconds(FLAGS_pwm_offset) -
+ ((monotonic_now -
+ chrono::microseconds(absl::GetFlag(FLAGS_pwm_offset)) -
last_tick_timepoint) /
period_) *
period_ +
- chrono::microseconds(FLAGS_pwm_offset);
+ chrono::microseconds(absl::GetFlag(FLAGS_pwm_offset));
VLOG(1) << "Now " << monotonic_now << " tick " << last_tick_timepoint;
// If it's over 1/2 of a period back in time, that's wrong. Move it
// forwards to now.
diff --git a/frc971/wpilib/talonfx.h b/frc971/wpilib/talonfx.h
index 1f64b5b..dd75328 100644
--- a/frc971/wpilib/talonfx.h
+++ b/frc971/wpilib/talonfx.h
@@ -5,8 +5,9 @@
#include <cinttypes>
#include <vector>
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "ctre/phoenix6/TalonFX.hpp"
-#include "glog/logging.h"
#include "aos/commonmath.h"
#include "aos/init.h"
diff --git a/frc971/zeroing/BUILD b/frc971/zeroing/BUILD
index 81ed998..0884baa 100644
--- a/frc971/zeroing/BUILD
+++ b/frc971/zeroing/BUILD
@@ -14,7 +14,8 @@
],
target_compatible_with = ["@platforms//os:linux"],
deps = [
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
"@org_tuxfamily_eigen//:eigen",
],
)
@@ -46,7 +47,8 @@
"//frc971/control_loops:control_loops_fbs",
"//frc971/control_loops/drivetrain:drivetrain_status_fbs",
"//frc971/wpilib:imu_fbs",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
"@org_tuxfamily_eigen//:eigen",
],
)
@@ -79,7 +81,8 @@
"//aos/logging",
"//frc971:constants",
"//frc971/control_loops:control_loops_fbs",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
)
@@ -108,7 +111,8 @@
"//aos/logging",
"//frc971:constants",
"//frc971/control_loops:control_loops_fbs",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
),
cc_test(
diff --git a/frc971/zeroing/absolute_and_absolute_encoder.cc b/frc971/zeroing/absolute_and_absolute_encoder.cc
index b9ba33d..dab814b 100644
--- a/frc971/zeroing/absolute_and_absolute_encoder.cc
+++ b/frc971/zeroing/absolute_and_absolute_encoder.cc
@@ -3,7 +3,8 @@
#include <cmath>
#include <numeric>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/logging/logging.h"
#include "frc971/zeroing/wrap.h"
diff --git a/frc971/zeroing/absolute_and_absolute_encoder_test.cc b/frc971/zeroing/absolute_and_absolute_encoder_test.cc
index 08ab924..a6e47ca 100644
--- a/frc971/zeroing/absolute_and_absolute_encoder_test.cc
+++ b/frc971/zeroing/absolute_and_absolute_encoder_test.cc
@@ -1,6 +1,7 @@
#include "frc971/zeroing/absolute_and_absolute_encoder.h"
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "gmock/gmock.h"
#include "gtest/gtest.h"
diff --git a/frc971/zeroing/absolute_encoder.cc b/frc971/zeroing/absolute_encoder.cc
index f5e3e3d..c2a795f 100644
--- a/frc971/zeroing/absolute_encoder.cc
+++ b/frc971/zeroing/absolute_encoder.cc
@@ -3,7 +3,8 @@
#include <cmath>
#include <numeric>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/containers/error_list.h"
#include "frc971/zeroing/wrap.h"
diff --git a/frc971/zeroing/averager.h b/frc971/zeroing/averager.h
index 370533f..6e4b888 100644
--- a/frc971/zeroing/averager.h
+++ b/frc971/zeroing/averager.h
@@ -6,7 +6,8 @@
#include <cstdint>
#include "Eigen/Dense"
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
namespace frc971::zeroing {
diff --git a/frc971/zeroing/continuous_absolute_encoder.cc b/frc971/zeroing/continuous_absolute_encoder.cc
index ebaf101..3381833 100644
--- a/frc971/zeroing/continuous_absolute_encoder.cc
+++ b/frc971/zeroing/continuous_absolute_encoder.cc
@@ -3,7 +3,8 @@
#include <cmath>
#include <numeric>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/containers/error_list.h"
#include "frc971/zeroing/wrap.h"
diff --git a/frc971/zeroing/hall_effect_and_position.cc b/frc971/zeroing/hall_effect_and_position.cc
index 99454e4..31d0675 100644
--- a/frc971/zeroing/hall_effect_and_position.cc
+++ b/frc971/zeroing/hall_effect_and_position.cc
@@ -4,7 +4,8 @@
#include <cmath>
#include <limits>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
namespace frc971::zeroing {
diff --git a/frc971/zeroing/pot_and_absolute_encoder.cc b/frc971/zeroing/pot_and_absolute_encoder.cc
index bef6f2d..15f283e 100644
--- a/frc971/zeroing/pot_and_absolute_encoder.cc
+++ b/frc971/zeroing/pot_and_absolute_encoder.cc
@@ -3,7 +3,8 @@
#include <cmath>
#include <numeric>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/containers/error_list.h"
#include "frc971/zeroing/wrap.h"
diff --git a/frc971/zeroing/pot_and_index.cc b/frc971/zeroing/pot_and_index.cc
index fb82f22..6a63415 100644
--- a/frc971/zeroing/pot_and_index.cc
+++ b/frc971/zeroing/pot_and_index.cc
@@ -2,7 +2,8 @@
#include <cmath>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
namespace frc971::zeroing {
diff --git a/frc971/zeroing/pulse_index.cc b/frc971/zeroing/pulse_index.cc
index 6e9a502..30da4a9 100644
--- a/frc971/zeroing/pulse_index.cc
+++ b/frc971/zeroing/pulse_index.cc
@@ -3,7 +3,8 @@
#include <cmath>
#include <limits>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
namespace frc971::zeroing {