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