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/y2023/BUILD b/y2023/BUILD
index e3d9a2e..bd20085 100644
--- a/y2023/BUILD
+++ b/y2023/BUILD
@@ -260,8 +260,9 @@
"//y2023/control_loops/superstructure/arm:arm_constants",
"//y2023/control_loops/superstructure/roll:roll_plants",
"//y2023/control_loops/superstructure/wrist:wrist_plants",
- "@com_github_google_glog//:glog",
"@com_google_absl//absl/base",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
)
@@ -352,7 +353,8 @@
"//aos:init",
"//aos/events:shm_event_loop",
"//frc971/input:joystick_state_fbs",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
)
diff --git a/y2023/autonomous/autonomous_actor.cc b/y2023/autonomous/autonomous_actor.cc
index a23f693..4583c6c 100644
--- a/y2023/autonomous/autonomous_actor.cc
+++ b/y2023/autonomous/autonomous_actor.cc
@@ -4,6 +4,8 @@
#include <cinttypes>
#include <cmath>
+#include "absl/flags/flag.h"
+
#include "aos/logging/logging.h"
#include "aos/util/math.h"
#include "frc971/control_loops/drivetrain/localizer_generated.h"
@@ -12,10 +14,11 @@
#include "y2023/control_loops/drivetrain/drivetrain_base.h"
#include "y2023/control_loops/superstructure/arm/generated_graph.h"
-DEFINE_bool(spline_auto, false, "Run simple test S-spline auto mode.");
-DEFINE_bool(charged_up, true, "If true run charged up autonomous mode");
-DEFINE_bool(charged_up_cable, false, "If true run cable side autonomous mode");
-DEFINE_bool(do_balance, true, "If true run the balance.");
+ABSL_FLAG(bool, spline_auto, false, "Run simple test S-spline auto mode.");
+ABSL_FLAG(bool, charged_up, true, "If true run charged up autonomous mode");
+ABSL_FLAG(bool, charged_up_cable, false,
+ "If true run cable side autonomous mode");
+ABSL_FLAG(bool, do_balance, true, "If true run the balance.");
namespace y2023::autonomous {
@@ -56,14 +59,14 @@
points_(control_loops::superstructure::arm::PointList()) {}
void AutonomousActor::Replan() {
- if (FLAGS_spline_auto) {
+ if (absl::GetFlag(FLAGS_spline_auto)) {
test_spline_ =
PlanSpline(std::bind(&AutonomousSplines::TestSpline, &auto_splines_,
std::placeholders::_1, alliance_),
SplineDirection::kForward);
starting_position_ = test_spline_->starting_position();
- } else if (FLAGS_charged_up) {
+ } else if (absl::GetFlag(FLAGS_charged_up)) {
AOS_LOG(INFO, "Charged up replanning!");
charged_up_splines_ = {
PlanSpline(std::bind(&AutonomousSplines::Spline1, &auto_splines_,
@@ -81,7 +84,7 @@
starting_position_ = charged_up_splines_.value()[0].starting_position();
CHECK(starting_position_);
- } else if (FLAGS_charged_up_cable) {
+ } else if (absl::GetFlag(FLAGS_charged_up_cable)) {
charged_up_cable_splines_ = {
PlanSpline(std::bind(&AutonomousSplines::SplineCable1, &auto_splines_,
std::placeholders::_1, alliance_),
@@ -121,11 +124,11 @@
AOS_LOG(INFO, "Aborting autonomous due to invalid alliance selection.");
return false;
}
- if (FLAGS_spline_auto) {
+ if (absl::GetFlag(FLAGS_spline_auto)) {
SplineAuto();
- } else if (FLAGS_charged_up) {
+ } else if (absl::GetFlag(FLAGS_charged_up)) {
ChargedUp();
- } else if (FLAGS_charged_up_cable) {
+ } else if (absl::GetFlag(FLAGS_charged_up_cable)) {
ChargedUpCableSide();
} else {
AOS_LOG(WARNING, "No auto mode selected.");
@@ -300,7 +303,7 @@
INFO, "Done backing up %lf s\n",
aos::time::DurationInSeconds(aos::monotonic_clock::now() - start_time));
- if (!FLAGS_do_balance) {
+ if (!absl::GetFlag(FLAGS_do_balance)) {
StopSpitting();
return;
}
diff --git a/y2023/constants.cc b/y2023/constants.cc
index 0b89ef0..1f537b7 100644
--- a/y2023/constants.cc
+++ b/y2023/constants.cc
@@ -8,7 +8,8 @@
#endif
#include "absl/base/call_once.h"
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/mutex/mutex.h"
#include "aos/network/team_number.h"
diff --git a/y2023/constants/constants_sender.cc b/y2023/constants/constants_sender.cc
index 757a374..5485a6e 100644
--- a/y2023/constants/constants_sender.cc
+++ b/y2023/constants/constants_sender.cc
@@ -1,5 +1,4 @@
-#include "gflags/gflags.h"
-#include "glog/logging.h"
+#include "absl/flags/flag.h"
#include "aos/configuration.h"
#include "aos/events/shm_event_loop.h"
@@ -9,16 +8,17 @@
#include "y2023/constants/constants_generated.h"
#include "y2023/constants/constants_list_generated.h"
-DEFINE_string(config, "aos_config.json", "Path to the AOS config.");
-DEFINE_string(constants_path, "constants.json", "Path to the constant file");
+ABSL_FLAG(std::string, config, "aos_config.json", "Path to the AOS config.");
+ABSL_FLAG(std::string, constants_path, "constants.json",
+ "Path to the constant file");
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<y2023::Constants, y2023::ConstantsList>
- constants_sender(&event_loop, FLAGS_constants_path);
+ constants_sender(&event_loop, absl::GetFlag(FLAGS_constants_path));
// Don't need to call Run().
return 0;
}
diff --git a/y2023/control_loops/drivetrain/trajectory_generator_main.cc b/y2023/control_loops/drivetrain/trajectory_generator_main.cc
index 03731e8..4908582 100644
--- a/y2023/control_loops/drivetrain/trajectory_generator_main.cc
+++ b/y2023/control_loops/drivetrain/trajectory_generator_main.cc
@@ -1,6 +1,8 @@
#include <sys/resource.h>
#include <sys/time.h>
+#include "absl/flags/flag.h"
+
#include "aos/events/shm_event_loop.h"
#include "aos/init.h"
#include "frc971/control_loops/drivetrain/trajectory_generator.h"
@@ -8,8 +10,8 @@
using ::frc971::control_loops::drivetrain::TrajectoryGenerator;
-DEFINE_bool(skip_renicing, false,
- "If true, skip renicing the trajectory generator.");
+ABSL_FLAG(bool, skip_renicing, false,
+ "If true, skip renicing the trajectory generator.");
int main(int argc, char *argv[]) {
::aos::InitGoogle(&argc, &argv);
@@ -22,7 +24,7 @@
&event_loop, ::y2023::control_loops::drivetrain::GetDrivetrainConfig());
event_loop.OnRun([]() {
- if (FLAGS_skip_renicing) {
+ if (absl::GetFlag(FLAGS_skip_renicing)) {
LOG(WARNING) << "Ignoring request to renice to -20 due to "
"--skip_renicing.";
} else {
diff --git a/y2023/control_loops/superstructure/arm/BUILD b/y2023/control_loops/superstructure/arm/BUILD
index a54f72c..c8ecaff 100644
--- a/y2023/control_loops/superstructure/arm/BUILD
+++ b/y2023/control_loops/superstructure/arm/BUILD
@@ -171,7 +171,7 @@
"//frc971/control_loops:fixed_quadrature",
"//frc971/control_loops/double_jointed_arm:ekf",
"//y2023/control_loops/superstructure/roll:roll_plants",
- "@com_github_gflags_gflags//:gflags",
+ "@com_google_absl//absl/flags:flag",
"@org_tuxfamily_eigen//:eigen",
],
)
diff --git a/y2023/control_loops/superstructure/arm/arm_design.cc b/y2023/control_loops/superstructure/arm/arm_design.cc
index 8c5664e..07439d6 100644
--- a/y2023/control_loops/superstructure/arm/arm_design.cc
+++ b/y2023/control_loops/superstructure/arm/arm_design.cc
@@ -1,3 +1,5 @@
+#include "absl/flags/flag.h"
+
#include "aos/analysis/in_process_plotter.h"
#include "aos/init.h"
#include "frc971/control_loops/dlqr.h"
@@ -5,17 +7,17 @@
#include "frc971/control_loops/jacobian.h"
#include "y2023/control_loops/superstructure/arm/arm_constants.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");
-DEFINE_double(fx, 0.0, "X force");
-DEFINE_double(fy, 0.0, "y force");
+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");
+ABSL_FLAG(double, fx, 0.0, "X force");
+ABSL_FLAG(double, fy, 0.0, "y force");
-DEFINE_double(start0, 0.0, "starting position on proximal");
-DEFINE_double(start1, 0.0, "starting position on distal");
-DEFINE_double(goal0, 0.0, "goal position on proximal");
-DEFINE_double(goal1, 0.0, "goal position on distal");
+ABSL_FLAG(double, start0, 0.0, "starting position on proximal");
+ABSL_FLAG(double, start1, 0.0, "starting position on distal");
+ABSL_FLAG(double, goal0, 0.0, "goal position on proximal");
+ABSL_FLAG(double, goal1, 0.0, "goal position on distal");
namespace y2023::control_loops::superstructure::arm {
@@ -26,14 +28,14 @@
::Eigen::Matrix<double, 4, 1> X = ::Eigen::Matrix<double, 4, 1>::Zero();
::Eigen::Matrix<double, 4, 1> goal = ::Eigen::Matrix<double, 4, 1>::Zero();
- goal(0, 0) = FLAGS_goal0;
+ goal(0, 0) = absl::GetFlag(FLAGS_goal0);
goal(1, 0) = 0;
- goal(2, 0) = FLAGS_goal1;
+ goal(2, 0) = absl::GetFlag(FLAGS_goal1);
goal(3, 0) = 0;
- X(0, 0) = FLAGS_start0;
+ X(0, 0) = absl::GetFlag(FLAGS_start0);
X(1, 0) = 0;
- X(2, 0) = FLAGS_start1;
+ X(2, 0) = absl::GetFlag(FLAGS_start1);
X(3, 0) = 0;
::Eigen::Matrix<double, 2, 1> U = ::Eigen::Matrix<double, 2, 1>::Zero();
@@ -52,10 +54,10 @@
std::vector<double> torque0;
std::vector<double> torque1;
- const double kProximalPosLQR = FLAGS_lqr_proximal_pos;
- const double kProximalVelLQR = FLAGS_lqr_proximal_vel;
- const double kDistalPosLQR = FLAGS_lqr_distal_pos;
- const double kDistalVelLQR = FLAGS_lqr_distal_vel;
+ const double kProximalPosLQR = absl::GetFlag(FLAGS_lqr_proximal_pos);
+ const double kProximalVelLQR = absl::GetFlag(FLAGS_lqr_proximal_vel);
+ const double kDistalPosLQR = absl::GetFlag(FLAGS_lqr_distal_pos);
+ const double kDistalVelLQR = absl::GetFlag(FLAGS_lqr_distal_vel);
const ::Eigen::DiagonalMatrix<double, 4> Q =
(::Eigen::DiagonalMatrix<double, 4>().diagonal()
<< 1.0 / ::std::pow(kProximalPosLQR, 2),
@@ -74,8 +76,9 @@
{
const ::Eigen::Matrix<double, 2, 1> torque =
dynamics
- .TorqueFromForce(X,
- ::Eigen::Matrix<double, 2, 1>(FLAGS_fx, FLAGS_fy))
+ .TorqueFromForce(
+ X, ::Eigen::Matrix<double, 2, 1>(absl::GetFlag(FLAGS_fx),
+ absl::GetFlag(FLAGS_fy)))
.transpose();
LOG(INFO) << "Torque (N m): " << torque.transpose();
const ::Eigen::Matrix<double, 2, 1> current =
diff --git a/y2023/control_loops/superstructure/arm/arm_trajectory_gen.cc b/y2023/control_loops/superstructure/arm/arm_trajectory_gen.cc
index 699cfcf..7116f92 100644
--- a/y2023/control_loops/superstructure/arm/arm_trajectory_gen.cc
+++ b/y2023/control_loops/superstructure/arm/arm_trajectory_gen.cc
@@ -1,8 +1,9 @@
#include <iostream>
#include <memory>
-#include "gflags/gflags.h"
-#include "glog/logging.h"
+#include "absl/flags/flag.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/events/shm_event_loop.h"
#include "aos/flatbuffers.h"
@@ -24,7 +25,7 @@
using y2023::control_loops::superstructure::arm::Path;
using y2023::control_loops::superstructure::arm::Trajectory;
-DEFINE_string(output, "", "Defines the location of the output file");
+ABSL_FLAG(std::string, output, "", "Defines the location of the output file");
int main(int argc, char **argv) {
aos::InitGoogle(&argc, &argv);
@@ -193,5 +194,5 @@
fbb.Release());
// This writes to a binary file so we can cache the optimization results
- aos::WriteFlatbufferToFile(FLAGS_output, detatched_buffer);
+ aos::WriteFlatbufferToFile(absl::GetFlag(FLAGS_output), detatched_buffer);
}
diff --git a/y2023/control_loops/superstructure/arm/trajectory.cc b/y2023/control_loops/superstructure/arm/trajectory.cc
index be339e4..f7ae5f9 100644
--- a/y2023/control_loops/superstructure/arm/trajectory.cc
+++ b/y2023/control_loops/superstructure/arm/trajectory.cc
@@ -1,7 +1,7 @@
#include "y2023/control_loops/superstructure/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"
@@ -10,10 +10,10 @@
#include "frc971/control_loops/runge_kutta.h"
#include "y2023/control_loops/superstructure/arm/arm_trajectories_generated.h"
-DEFINE_double(lqr_proximal_pos, 0.5, "Position LQR gain");
-DEFINE_double(lqr_proximal_vel, 5, "Velocity LQR gain");
-DEFINE_double(lqr_distal_pos, 0.5, "Position LQR gain");
-DEFINE_double(lqr_distal_vel, 5, "Velocity LQR gain");
+ABSL_FLAG(double, lqr_proximal_pos, 0.5, "Position LQR gain");
+ABSL_FLAG(double, lqr_proximal_vel, 5, "Velocity LQR gain");
+ABSL_FLAG(double, lqr_distal_pos, 0.5, "Position LQR gain");
+ABSL_FLAG(double, lqr_distal_vel, 5, "Velocity LQR gain");
namespace y2023::control_loops::superstructure::arm {
@@ -714,10 +714,10 @@
::Eigen::Matrix<double, 2, 6> TrajectoryFollower::ArmK_at_state(
const Eigen::Ref<const ::Eigen::Matrix<double, 6, 1>> arm_X,
const Eigen::Ref<const ::Eigen::Matrix<double, 2, 1>> arm_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/y2023/control_loops/superstructure/arm/trajectory_plot.cc b/y2023/control_loops/superstructure/arm/trajectory_plot.cc
index 8488d72..d2b6b59 100644
--- a/y2023/control_loops/superstructure/arm/trajectory_plot.cc
+++ b/y2023/control_loops/superstructure/arm/trajectory_plot.cc
@@ -1,4 +1,4 @@
-#include "gflags/gflags.h"
+#include "absl/flags/flag.h"
#include "aos/analysis/in_process_plotter.h"
#include "aos/init.h"
@@ -12,16 +12,16 @@
#include "y2023/control_loops/superstructure/roll/integral_hybrid_roll_plant.h"
#include "y2023/control_loops/superstructure/roll/integral_roll_plant.h"
-DEFINE_bool(forwards, true, "If true, run the forwards simulation.");
-DEFINE_bool(plot, true, "If true, plot");
-DEFINE_bool(plot_thetas, true, "If true, plot the angles");
+ABSL_FLAG(bool, forwards, true, "If true, run the forwards simulation.");
+ABSL_FLAG(bool, plot, true, "If true, plot");
+ABSL_FLAG(bool, plot_thetas, true, "If true, plot the angles");
-DEFINE_double(alpha0_max, 15.0, "Max acceleration on joint 0.");
-DEFINE_double(alpha1_max, 10.0, "Max acceleration on joint 1.");
-DEFINE_double(alpha2_max, 90.0, "Max acceleration on joint 2.");
-DEFINE_double(vmax_plan, 9.5, "Max voltage to plan.");
-DEFINE_double(vmax_battery, 12.0, "Max battery voltage.");
-DEFINE_double(time, 2.0, "Simulation time.");
+ABSL_FLAG(double, alpha0_max, 15.0, "Max acceleration on joint 0.");
+ABSL_FLAG(double, alpha1_max, 10.0, "Max acceleration on joint 1.");
+ABSL_FLAG(double, alpha2_max, 90.0, "Max acceleration on joint 2.");
+ABSL_FLAG(double, vmax_plan, 9.5, "Max voltage to plan.");
+ABSL_FLAG(double, vmax_battery, 12.0, "Max battery voltage.");
+ABSL_FLAG(double, time, 2.0, "Simulation time.");
namespace y2023::control_loops::superstructure::arm {
using frc971::control_loops::MatrixGaussianQuadrature5;
@@ -55,16 +55,17 @@
constexpr double sim_dt = 0.00505;
- LOG(INFO) << "Planning with kAlpha0Max=" << FLAGS_alpha0_max
- << ", kAlpha1Max=" << FLAGS_alpha1_max
- << ", kAlpha2Max=" << FLAGS_alpha2_max;
+ LOG(INFO) << "Planning with kAlpha0Max=" << absl::GetFlag(FLAGS_alpha0_max)
+ << ", kAlpha1Max=" << absl::GetFlag(FLAGS_alpha1_max)
+ << ", kAlpha2Max=" << absl::GetFlag(FLAGS_alpha2_max);
const ::Eigen::DiagonalMatrix<double, 3> alpha_unitizer(
(::Eigen::DiagonalMatrix<double, 3>().diagonal()
- << (1.0 / FLAGS_alpha0_max),
- (1.0 / FLAGS_alpha1_max), (1.0 / FLAGS_alpha2_max))
+ << (1.0 / absl::GetFlag(FLAGS_alpha0_max)),
+ (1.0 / absl::GetFlag(FLAGS_alpha1_max)),
+ (1.0 / absl::GetFlag(FLAGS_alpha2_max)))
.finished());
- trajectory.OptimizeTrajectory(alpha_unitizer, FLAGS_vmax_plan);
+ trajectory.OptimizeTrajectory(alpha_unitizer, absl::GetFlag(FLAGS_vmax_plan));
const ::std::vector<double> distance_array = trajectory.DistanceArray();
@@ -301,7 +302,7 @@
::std::cout << "Really stabilized P: " << arm_ekf.P_converged()
<< ::std::endl;
- while (t < FLAGS_time) {
+ while (t < absl::GetFlag(FLAGS_time)) {
t_array.push_back(t);
arm_ekf.Correct(
(::Eigen::Matrix<double, 2, 1>() << arm_X(0), arm_X(2)).finished(),
@@ -314,7 +315,8 @@
follower.Update(
(Eigen::Matrix<double, 9, 1>() << arm_ekf.X_hat(), roll.X_hat())
.finished(),
- disabled, sim_dt, FLAGS_vmax_plan, FLAGS_vmax_battery);
+ disabled, sim_dt, absl::GetFlag(FLAGS_vmax_plan),
+ absl::GetFlag(FLAGS_vmax_battery));
const ::Eigen::Matrix<double, 3, 1> theta_t =
trajectory.ThetaT(follower.goal()(0));
@@ -395,7 +397,7 @@
t += sim_dt;
}
- if (FLAGS_plot) {
+ if (absl::GetFlag(FLAGS_plot)) {
aos::analysis::Plotter plotter;
plotter.AddFigure();
@@ -488,7 +490,7 @@
plotter.AddLine(t_array, torque2_hat_t_array, "torque2_hat");
plotter.Publish();
- if (FLAGS_plot_thetas) {
+ if (absl::GetFlag(FLAGS_plot_thetas)) {
plotter.AddFigure();
plotter.Title("Angles");
plotter.AddLine(t_array, theta0_goal_t_array, "theta0_t_goal");
diff --git a/y2023/control_loops/superstructure/superstructure.cc b/y2023/control_loops/superstructure/superstructure.cc
index bfb7a9d..60881f2 100644
--- a/y2023/control_loops/superstructure/superstructure.cc
+++ b/y2023/control_loops/superstructure/superstructure.cc
@@ -7,8 +7,8 @@
#include "frc971/zeroing/wrap.h"
#include "y2023/control_loops/superstructure/arm/arm_trajectories_generated.h"
-DEFINE_bool(ignore_distance, false,
- "If true, ignore distance when shooting and obay joystick_reader");
+ABSL_FLAG(bool, ignore_distance, false,
+ "If true, ignore distance when shooting and obay joystick_reader");
namespace y2023::control_loops::superstructure {
diff --git a/y2023/control_loops/superstructure/superstructure_lib_test.cc b/y2023/control_loops/superstructure/superstructure_lib_test.cc
index 5973eee..cc6e3ae 100644
--- a/y2023/control_loops/superstructure/superstructure_lib_test.cc
+++ b/y2023/control_loops/superstructure/superstructure_lib_test.cc
@@ -15,8 +15,8 @@
#include "y2023/control_loops/superstructure/roll/integral_roll_plant.h"
#include "y2023/control_loops/superstructure/superstructure.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 y2023::control_loops::superstructure::testing {
namespace {
@@ -320,11 +320,11 @@
SetEnabled(true);
- if (!FLAGS_output_folder.empty()) {
- unlink(FLAGS_output_folder.c_str());
+ if (!absl::GetFlag(FLAGS_output_folder).empty()) {
+ unlink(absl::GetFlag(FLAGS_output_folder).c_str());
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));
}
}
diff --git a/y2023/control_loops/superstructure/superstructure_main.cc b/y2023/control_loops/superstructure/superstructure_main.cc
index 4a044b6..bc20e44 100644
--- a/y2023/control_loops/superstructure/superstructure_main.cc
+++ b/y2023/control_loops/superstructure/superstructure_main.cc
@@ -1,9 +1,11 @@
+#include "absl/flags/flag.h"
+
#include "aos/events/shm_event_loop.h"
#include "aos/init.h"
#include "y2023/control_loops/superstructure/superstructure.h"
-DEFINE_string(arm_trajectories, "arm_trajectories_generated.bfbs",
- "The path to the generated arm trajectories bfbs file.");
+ABSL_FLAG(std::string, arm_trajectories, "arm_trajectories_generated.bfbs",
+ "The path to the generated arm trajectories bfbs file.");
using y2023::control_loops::superstructure::Superstructure;
using y2023::control_loops::superstructure::arm::ArmTrajectories;
@@ -20,7 +22,7 @@
auto trajectories =
y2023::control_loops::superstructure::Superstructure::GetArmTrajectories(
- FLAGS_arm_trajectories);
+ absl::GetFlag(FLAGS_arm_trajectories));
std::shared_ptr<const y2023::constants::Values> values =
std::make_shared<const y2023::constants::Values>(
diff --git a/y2023/control_loops/superstructure/superstructure_replay.cc b/y2023/control_loops/superstructure/superstructure_replay.cc
index 6f23ec2..1f13aeb 100644
--- a/y2023/control_loops/superstructure/superstructure_replay.cc
+++ b/y2023/control_loops/superstructure/superstructure_replay.cc
@@ -3,7 +3,7 @@
// replayed, so that it can then be run through the plotting tool or analyzed
// in some other way. The original superstructure status data will be on the
// /original/superstructure channel.
-#include "gflags/gflags.h"
+#include "absl/flags/flag.h"
#include "aos/events/logging/log_reader.h"
#include "aos/events/logging/log_writer.h"
@@ -15,16 +15,16 @@
#include "y2023/constants.h"
#include "y2023/control_loops/superstructure/superstructure.h"
-DEFINE_int32(team, 971, "Team number to use for logfile replay.");
-DEFINE_string(output_folder, "/tmp/superstructure_replay/",
- "Logs all channels to the provided logfile.");
-DEFINE_string(arm_trajectories, "arm/arm_trajectories_generated.bfbs",
- "The path to the generated arm trajectories bfbs file.");
+ABSL_FLAG(int32_t, team, 971, "Team number to use for logfile replay.");
+ABSL_FLAG(std::string, output_folder, "/tmp/superstructure_replay/",
+ "Logs all channels to the provided logfile.");
+ABSL_FLAG(std::string, arm_trajectories, "arm/arm_trajectories_generated.bfbs",
+ "The path to the generated arm trajectories bfbs file.");
int main(int argc, char **argv) {
aos::InitGoogle(&argc, &argv);
- aos::network::OverrideTeamNumber(FLAGS_team);
+ aos::network::OverrideTeamNumber(absl::GetFlag(FLAGS_team));
// open logfiles
aos::logger::LogReader reader(
@@ -42,15 +42,15 @@
aos::NodeEventLoopFactory *roborio =
factory.GetNodeEventLoopFactory("roborio");
- unlink(FLAGS_output_folder.c_str());
+ unlink(absl::GetFlag(FLAGS_output_folder).c_str());
std::unique_ptr<aos::EventLoop> logger_event_loop =
roborio->MakeEventLoop("logger");
auto logger = std::make_unique<aos::logger::Logger>(logger_event_loop.get());
- logger->StartLoggingOnRun(FLAGS_output_folder);
+ logger->StartLoggingOnRun(absl::GetFlag(FLAGS_output_folder));
auto trajectories =
y2023::control_loops::superstructure::Superstructure::GetArmTrajectories(
- FLAGS_arm_trajectories);
+ absl::GetFlag(FLAGS_arm_trajectories));
roborio->OnStartup([roborio, &trajectories]() {
roborio->AlwaysStart<y2023::control_loops::superstructure::Superstructure>(
diff --git a/y2023/joystick_republish.cc b/y2023/joystick_republish.cc
index ae6f340..9ea6a1a 100644
--- a/y2023/joystick_republish.cc
+++ b/y2023/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/y2023/localizer/localizer.cc b/y2023/localizer/localizer.cc
index a00ebe6..586ffb6 100644
--- a/y2023/localizer/localizer.cc
+++ b/y2023/localizer/localizer.cc
@@ -1,6 +1,6 @@
#include "y2023/localizer/localizer.h"
-#include "gflags/gflags.h"
+#include "absl/flags/flag.h"
#include "aos/containers/sized_array.h"
#include "frc971/control_loops/drivetrain/localizer_generated.h"
@@ -8,28 +8,27 @@
#include "frc971/vision/target_map_utils.h"
#include "y2023/constants.h"
-DEFINE_double(max_pose_error, 1e-6,
- "Throw out target poses with a higher pose error than this");
-DEFINE_double(
- max_pose_error_ratio, 0.4,
- "Throw out target poses with a higher pose error ratio than this");
-DEFINE_double(distortion_noise_scalar, 1.0,
- "Scale the target pose distortion factor by this when computing "
- "the noise.");
-DEFINE_double(
- max_implied_yaw_error, 3.0,
+ABSL_FLAG(double, max_pose_error, 1e-6,
+ "Throw out target poses with a higher pose error than this");
+ABSL_FLAG(double, max_pose_error_ratio, 0.4,
+ "Throw out target poses with a higher pose error ratio than this");
+ABSL_FLAG(double, distortion_noise_scalar, 1.0,
+ "Scale the target pose distortion factor by this when computing "
+ "the noise.");
+ABSL_FLAG(
+ double, max_implied_yaw_error, 3.0,
"Reject target poses that imply a robot yaw of more than this many degrees "
"off from our estimate.");
-DEFINE_double(
- max_implied_teleop_yaw_error, 30.0,
+ABSL_FLAG(
+ double, max_implied_teleop_yaw_error, 30.0,
"Reject target poses that imply a robot yaw of more than this many degrees "
"off from our estimate.");
-DEFINE_double(max_distance_to_target, 5.0,
- "Reject target poses that have a 3d distance of more than this "
- "many meters.");
-DEFINE_double(max_auto_image_robot_speed, 2.0,
- "Reject target poses when the robot is travelling faster than "
- "this speed in auto.");
+ABSL_FLAG(double, max_distance_to_target, 5.0,
+ "Reject target poses that have a 3d distance of more than this "
+ "many meters.");
+ABSL_FLAG(double, max_auto_image_robot_speed, 2.0,
+ "Reject target poses when the robot is travelling faster than "
+ "this speed in auto.");
namespace y2023::localizer {
namespace {
@@ -348,8 +347,9 @@
Eigen::Matrix<double, 3, 1> noises(1.0, 1.0, 0.5);
noises /= 4.0;
// Scale noise by the distortion factor for this detection
- noises *= (1.0 + FLAGS_distortion_noise_scalar * target.distortion_factor() *
- std::exp(distance_to_target));
+ noises *=
+ (1.0 + absl::GetFlag(FLAGS_distortion_noise_scalar) *
+ target.distortion_factor() * std::exp(distance_to_target));
Eigen::Matrix3d R = Eigen::Matrix3d::Zero();
R.diagonal() = noises.cwiseAbs2();
@@ -365,12 +365,13 @@
if (!state_at_capture.has_value()) {
VLOG(1) << "Rejecting image due to being too old.";
return RejectImage(camera_index, RejectionReason::IMAGE_TOO_OLD, &builder);
- } else if (target.pose_error() > FLAGS_max_pose_error) {
+ } else if (target.pose_error() > absl::GetFlag(FLAGS_max_pose_error)) {
VLOG(1) << "Rejecting target due to high pose error "
<< target.pose_error();
return RejectImage(camera_index, RejectionReason::HIGH_POSE_ERROR,
&builder);
- } else if (target.pose_error_ratio() > FLAGS_max_pose_error_ratio) {
+ } else if (target.pose_error_ratio() >
+ absl::GetFlag(FLAGS_max_pose_error_ratio)) {
VLOG(1) << "Rejecting target due to high pose error ratio "
<< target.pose_error_ratio();
return RejectImage(camera_index, RejectionReason::HIGH_POSE_ERROR_RATIO,
@@ -386,17 +387,19 @@
state_at_capture.value()(StateIdx::kRightVelocity)) /
2.0;
const double yaw_threshold =
- (utils_.MaybeInAutonomous() ? FLAGS_max_implied_yaw_error
- : FLAGS_max_implied_teleop_yaw_error) *
+ (utils_.MaybeInAutonomous()
+ ? absl::GetFlag(FLAGS_max_implied_yaw_error)
+ : absl::GetFlag(FLAGS_max_implied_teleop_yaw_error)) *
kDegToRad;
if (utils_.MaybeInAutonomous() &&
- (std::abs(robot_speed) > FLAGS_max_auto_image_robot_speed)) {
+ (std::abs(robot_speed) >
+ absl::GetFlag(FLAGS_max_auto_image_robot_speed))) {
return RejectImage(camera_index, RejectionReason::ROBOT_TOO_FAST, &builder);
} else if (std::abs(aos::math::NormalizeAngle(
camera_implied_theta - theta_at_capture)) > yaw_threshold) {
return RejectImage(camera_index, RejectionReason::HIGH_IMPLIED_YAW_ERROR,
&builder);
- } else if (distance_to_target > FLAGS_max_distance_to_target) {
+ } else if (distance_to_target > absl::GetFlag(FLAGS_max_distance_to_target)) {
return RejectImage(camera_index, RejectionReason::HIGH_DISTANCE_TO_TARGET,
&builder);
}
diff --git a/y2023/localizer/localizer_main.cc b/y2023/localizer/localizer_main.cc
index 98f0e81..40b3ee5 100644
--- a/y2023/localizer/localizer_main.cc
+++ b/y2023/localizer/localizer_main.cc
@@ -1,16 +1,19 @@
+#include "absl/flags/flag.h"
+
#include "aos/events/shm_event_loop.h"
#include "aos/init.h"
#include "frc971/constants/constants_sender_lib.h"
#include "y2023/control_loops/drivetrain/drivetrain_base.h"
#include "y2023/localizer/localizer.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.");
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));
frc971::constants::WaitForConstants<y2023::Constants>(&config.message());
diff --git a/y2023/localizer/localizer_replay.cc b/y2023/localizer/localizer_replay.cc
index 859b77e..55b81b1 100644
--- a/y2023/localizer/localizer_replay.cc
+++ b/y2023/localizer/localizer_replay.cc
@@ -1,4 +1,4 @@
-#include "gflags/gflags.h"
+#include "absl/flags/flag.h"
#include "aos/configuration.h"
#include "aos/events/logging/log_reader.h"
@@ -11,19 +11,19 @@
#include "y2023/control_loops/drivetrain/drivetrain_base.h"
#include "y2023/localizer/localizer.h"
-DEFINE_string(config, "y2023/aos_config.json",
- "Name of the config file to replay using.");
-DEFINE_int32(team, 9971, "Team number to use for logfile replay.");
-DEFINE_string(output_folder, "/tmp/replayed",
- "Name of the folder to write replayed logs to.");
+ABSL_FLAG(std::string, config, "y2023/aos_config.json",
+ "Name of the config file to replay using.");
+ABSL_FLAG(int32_t, team, 9971, "Team number to use for logfile replay.");
+ABSL_FLAG(std::string, output_folder, "/tmp/replayed",
+ "Name of the folder to write replayed logs to.");
int main(int argc, char **argv) {
aos::InitGoogle(&argc, &argv);
- aos::network::OverrideTeamNumber(FLAGS_team);
+ aos::network::OverrideTeamNumber(absl::GetFlag(FLAGS_team));
const aos::FlatbufferDetachedBuffer<aos::Configuration> config =
- aos::configuration::ReadConfig(FLAGS_config);
+ aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
// sort logfiles
const std::vector<aos::logger::LogFile> logfiles =
@@ -50,7 +50,7 @@
const std::vector<std::string> nodes_to_log = {"imu"};
std::vector<std::unique_ptr<aos::util::LoggerState>> loggers =
aos::util::MakeLoggersForNodes(reader.event_loop_factory(), nodes_to_log,
- FLAGS_output_folder);
+ absl::GetFlag(FLAGS_output_folder));
const aos::Node *node = nullptr;
if (aos::configuration::MultiNode(reader.configuration())) {
diff --git a/y2023/localizer/localizer_test.cc b/y2023/localizer/localizer_test.cc
index c47e46e..79454ab 100644
--- a/y2023/localizer/localizer_test.cc
+++ b/y2023/localizer/localizer_test.cc
@@ -1,5 +1,8 @@
#include "y2023/localizer/localizer.h"
+#include "absl/flags/declare.h"
+#include "absl/flags/flag.h"
+#include "absl/flags/reflection.h"
#include "gtest/gtest.h"
#include "aos/events/logging/log_writer.h"
@@ -13,9 +16,9 @@
#include "y2023/control_loops/drivetrain/drivetrain_base.h"
#include "y2023/localizer/status_generated.h"
-DEFINE_string(output_folder, "",
- "If set, logs all channels to the provided logfile.");
-DECLARE_double(max_distance_to_target);
+ABSL_FLAG(std::string, output_folder, "",
+ "If set, logs all channels to the provided logfile.");
+ABSL_DECLARE_FLAG(double, max_distance_to_target);
namespace y2023::localizer::testing {
@@ -74,7 +77,7 @@
->MakeFetcher<frc971::controls::LocalizerOutput>("/localizer")),
status_fetcher_(
imu_test_event_loop_->MakeFetcher<Status>("/localizer")) {
- FLAGS_max_distance_to_target = 100.0;
+ absl::SetFlag(&FLAGS_max_distance_to_target, 100.0);
{
aos::TimerHandler *timer = roborio_test_event_loop_->AddTimer([this]() {
{
@@ -191,11 +194,11 @@
CHECK(status_fetcher_.Fetch());
CHECK(status_fetcher_->imu()->zeroed());
- if (!FLAGS_output_folder.empty()) {
+ if (!absl::GetFlag(FLAGS_output_folder).empty()) {
logger_event_loop_ =
event_loop_factory_.MakeEventLoop("logger", imu_node_);
logger_ = std::make_unique<aos::logger::Logger>(logger_event_loop_.get());
- logger_->StartLoggingOnRun(FLAGS_output_folder);
+ logger_->StartLoggingOnRun(absl::GetFlag(FLAGS_output_folder));
}
}
@@ -280,7 +283,7 @@
double pose_error_ratio_ = 0.1;
double implied_yaw_error_ = 0.0;
- gflags::FlagSaver flag_saver_;
+ absl::FlagSaver flag_saver_;
};
// Test a simple scenario with no errors where the robot should just drive
diff --git a/y2023/localizer/map_expander.cc b/y2023/localizer/map_expander.cc
index 32efcd8..9582c6b 100644
--- a/y2023/localizer/map_expander.cc
+++ b/y2023/localizer/map_expander.cc
@@ -1,24 +1,25 @@
-#include "gflags/gflags.h"
+#include "absl/flags/flag.h"
#include "aos/init.h"
#include "aos/util/file.h"
#include "y2023/localizer/map_expander_lib.h"
-DEFINE_string(target_map, "y2023/vision/maps/target_map.json",
- "Path to the target map JSON file.");
-DEFINE_string(relative_map, "y2023/constants/relative_scoring_map.json",
- "Path to the relative scoring map JSON file.");
-DEFINE_string(output, "y2023/constants/scoring_map.json",
- "Path to the output scoring map JSON file.");
+ABSL_FLAG(std::string, target_map, "y2023/vision/maps/target_map.json",
+ "Path to the target map JSON file.");
+ABSL_FLAG(std::string, relative_map,
+ "y2023/constants/relative_scoring_map.json",
+ "Path to the relative scoring map JSON file.");
+ABSL_FLAG(std::string, output, "y2023/constants/scoring_map.json",
+ "Path to the output scoring map JSON file.");
int main(int argc, char *argv[]) {
aos::InitGoogle(&argc, &argv);
aos::FlatbufferDetachedBuffer<y2023::localizer::ScoringMap> map =
y2023::localizer::ExpandMap(
- aos::util::ReadFileToStringOrDie(FLAGS_relative_map),
- aos::util::ReadFileToStringOrDie(FLAGS_target_map));
+ aos::util::ReadFileToStringOrDie(absl::GetFlag(FLAGS_relative_map)),
+ aos::util::ReadFileToStringOrDie(absl::GetFlag(FLAGS_target_map)));
aos::util::WriteStringToFileOrDie(
- FLAGS_output,
+ absl::GetFlag(FLAGS_output),
aos::FlatbufferToJson(map, {.multi_line = true, .max_multi_line = true}));
return EXIT_SUCCESS;
}
diff --git a/y2023/rockpi/imu_main.cc b/y2023/rockpi/imu_main.cc
index d53b3fb..ed8bcb1 100644
--- a/y2023/rockpi/imu_main.cc
+++ b/y2023/rockpi/imu_main.cc
@@ -1,16 +1,19 @@
+#include "absl/flags/flag.h"
+
#include "aos/events/shm_event_loop.h"
#include "aos/init.h"
#include "aos/realtime.h"
#include "frc971/imu_reader/imu.h"
#include "y2023/constants.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.");
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::imu::Imu imu(&event_loop,
diff --git a/y2023/vision/BUILD b/y2023/vision/BUILD
index 25f4d87..f415b6a 100644
--- a/y2023/vision/BUILD
+++ b/y2023/vision/BUILD
@@ -123,7 +123,8 @@
deps = [
"//third_party:opencv",
"//y2023/constants:constants_fbs",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
)
@@ -357,8 +358,9 @@
"//aos/events/logging:log_writer",
"//aos/logging:log_namer",
"//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",
],
)
@@ -368,8 +370,9 @@
hdrs = ["yolov5.h"],
deps = [
"//third_party:opencv",
- "@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",
"@com_google_absl//absl/types:span",
] + cpu_select({
"amd64": [
@@ -426,8 +429,9 @@
"//aos/events:simulated_event_loop",
"//aos/events/logging:log_reader",
"//frc971/vision:vision_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",
],
)
diff --git a/y2023/vision/april_detection_test.cc b/y2023/vision/april_detection_test.cc
index 71e34cb..9f4f8b7 100644
--- a/y2023/vision/april_detection_test.cc
+++ b/y2023/vision/april_detection_test.cc
@@ -1,6 +1,7 @@
#include <string>
-#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/y2023/vision/aprilrobotics.cc b/y2023/vision/aprilrobotics.cc
index 342e046..db9a4f2 100644
--- a/y2023/vision/aprilrobotics.cc
+++ b/y2023/vision/aprilrobotics.cc
@@ -1,24 +1,25 @@
#include "y2023/vision/aprilrobotics.h"
+#include "absl/flags/flag.h"
#include <opencv2/highgui.hpp>
#include "y2023/vision/vision_util.h"
-DEFINE_bool(
- debug, false,
+ABSL_FLAG(
+ bool, debug, false,
"If true, dump a ton of debug and crash on the first valid detection.");
-DEFINE_double(min_decision_margin, 50.0,
- "Minimum decision margin (confidence) for an apriltag detection");
-DEFINE_int32(pixel_border, 10,
- "Size of image border within which to reject detected corners");
-DEFINE_double(
- max_expected_distortion, 0.314,
+ABSL_FLAG(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, 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_uint64(pose_estimation_iterations, 50,
- "Number of iterations for apriltag pose estimation.");
+ABSL_FLAG(uint64_t, pose_estimation_iterations, 50,
+ "Number of iterations for apriltag pose estimation.");
namespace y2023::vision {
@@ -56,7 +57,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);
std::string hostname = aos::network::GetHostname();
@@ -178,7 +179,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> AprilRoboticsDetector::MakeCornerVector(
@@ -210,10 +212,10 @@
.stride = image.cols,
.buf = image.data,
};
- const uint32_t min_x = FLAGS_pixel_border;
- const uint32_t max_x = image.cols - FLAGS_pixel_border;
- const uint32_t min_y = FLAGS_pixel_border;
- const uint32_t max_y = image.rows - FLAGS_pixel_border;
+ const uint32_t min_x = absl::GetFlag(FLAGS_pixel_border);
+ const uint32_t max_x = image.cols - absl::GetFlag(FLAGS_pixel_border);
+ const uint32_t min_y = absl::GetFlag(FLAGS_pixel_border);
+ const uint32_t max_y = image.rows - absl::GetFlag(FLAGS_pixel_border);
ftrace_.FormatMessage("Starting detect\n");
zarray_t *detections = apriltag_detector_detect(tag_detector_, &im);
@@ -228,7 +230,7 @@
apriltag_detection_t *det;
zarray_get(detections, i, &det);
- if (det->decision_margin > FLAGS_min_decision_margin) {
+ if (det->decision_margin > absl::GetFlag(FLAGS_min_decision_margin)) {
if (det->p[0][0] < min_x || det->p[0][0] > max_x ||
det->p[1][0] < min_x || det->p[1][0] > max_x ||
det->p[2][0] < min_x || det->p[2][0] > max_x ||
@@ -274,9 +276,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();
@@ -320,7 +322,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(color_image, orig_corner_points[0], orig_corner_points[1],
cv::Scalar(0, 255, 0), 2);
@@ -349,7 +351,7 @@
rejections_++;
}
}
- if (FLAGS_visualize) {
+ if (absl::GetFlag(FLAGS_visualize)) {
// Display the result
// Rotate by 180 degrees to make it upright
if (flip_image_) {
@@ -368,7 +370,7 @@
const aos::monotonic_clock::time_point end_time = aos::monotonic_clock::now();
- if (FLAGS_debug) {
+ if (absl::GetFlag(FLAGS_debug)) {
timeprofile_display(tag_detector_->tp);
}
diff --git a/y2023/vision/aprilrobotics_main.cc b/y2023/vision/aprilrobotics_main.cc
index 5e5bad7..013730e 100644
--- a/y2023/vision/aprilrobotics_main.cc
+++ b/y2023/vision/aprilrobotics_main.cc
@@ -1,14 +1,17 @@
+#include "absl/flags/flag.h"
+
#include "aos/events/shm_event_loop.h"
#include "aos/init.h"
#include "frc971/constants/constants_sender_lib.h"
#include "y2023/vision/aprilrobotics.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.");
namespace y2023::vision {
void AprilViewerMain() {
aos::FlatbufferDetachedBuffer<aos::Configuration> config =
- aos::configuration::ReadConfig(FLAGS_config);
+ aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
frc971::constants::WaitForConstants<Constants>(&config.message());
diff --git a/y2023/vision/calibrate_extrinsics.cc b/y2023/vision/calibrate_extrinsics.cc
index 59c27e6..8c00d65 100644
--- a/y2023/vision/calibrate_extrinsics.cc
+++ b/y2023/vision/calibrate_extrinsics.cc
@@ -17,19 +17,20 @@
#include "y2023/constants/constants_generated.h"
#include "y2023/vision/vision_util.h"
-DEFINE_string(pi, "pi-7971-2", "Pi name to calibrate.");
-DEFINE_bool(plot, false, "Whether to plot the resulting data.");
-DEFINE_string(target_type, "charuco_diamond",
- "Type of target: aruco|charuco|charuco_diamond");
-DEFINE_string(image_channel, "/camera", "Channel to listen for images on");
-DEFINE_string(output_logs, "/tmp/calibration/",
- "Output folder for visualization logs.");
-DEFINE_string(base_calibration, "",
- "Intrinsics (and optionally extrinsics) to use for extrinsics "
- "calibration.");
-DEFINE_string(output_calibration, "",
- "Output json file to use for the resulting calibration "
- "(intrinsics and extrinsics).");
+ABSL_FLAG(std::string, pi, "pi-7971-2", "Pi name to calibrate.");
+ABSL_FLAG(bool, plot, false, "Whether to plot the resulting data.");
+ABSL_FLAG(std::string, target_type, "charuco_diamond",
+ "Type of target: aruco|charuco|charuco_diamond");
+ABSL_FLAG(std::string, image_channel, "/camera",
+ "Channel to listen for images on");
+ABSL_FLAG(std::string, output_logs, "/tmp/calibration/",
+ "Output folder for visualization logs.");
+ABSL_FLAG(std::string, base_calibration, "",
+ "Intrinsics (and optionally extrinsics) to use for extrinsics "
+ "calibration.");
+ABSL_FLAG(std::string, output_calibration, "",
+ "Output json file to use for the resulting calibration "
+ "(intrinsics and extrinsics).");
namespace frc971::vision {
namespace chrono = std::chrono;
@@ -51,10 +52,11 @@
std::unique_ptr<Calibration> extractor;
void MaybeMakeExtractor() {
if (imu_event_loop && pi_event_loop) {
- TargetType target_type = TargetTypeFromString(FLAGS_target_type);
+ TargetType target_type =
+ TargetTypeFromString(absl::GetFlag(FLAGS_target_type));
std::unique_ptr<aos::EventLoop> constants_event_loop =
factory->MakeEventLoop("constants_fetcher", pi_event_loop->node());
- if (FLAGS_base_calibration.empty()) {
+ if (absl::GetFlag(FLAGS_base_calibration).empty()) {
frc971::constants::ConstantsFetcher<y2023::Constants> constants_fetcher(
constants_event_loop.get());
*intrinsics =
@@ -63,11 +65,12 @@
pi_event_loop->node()->name()->string_view()));
} else {
*intrinsics = aos::JsonFileToFlatbuffer<calibration::CameraCalibration>(
- FLAGS_base_calibration);
+ absl::GetFlag(FLAGS_base_calibration));
}
extractor = std::make_unique<Calibration>(
- factory, pi_event_loop.get(), imu_event_loop.get(), FLAGS_pi,
- &intrinsics->message(), target_type, FLAGS_image_channel, data);
+ factory, pi_event_loop.get(), imu_event_loop.get(),
+ absl::GetFlag(FLAGS_pi), &intrinsics->message(), target_type,
+ absl::GetFlag(FLAGS_image_channel), data);
}
}
};
@@ -75,7 +78,7 @@
void Main(int argc, char **argv) {
CalibrationData data;
std::optional<uint16_t> pi_number =
- aos::network::ParsePiOrOrinNumber(FLAGS_pi);
+ aos::network::ParsePiOrOrinNumber(absl::GetFlag(FLAGS_pi));
CHECK(pi_number);
const std::string pi_name = absl::StrCat("pi", *pi_number);
@@ -122,7 +125,8 @@
factory.MakeEventLoop("logger", pi_node);
accumulator_state.logger = std::make_unique<aos::logger::Logger>(
accumulator_state.logger_event_loop.get());
- accumulator_state.logger->StartLoggingOnRun(FLAGS_output_logs);
+ accumulator_state.logger->StartLoggingOnRun(
+ absl::GetFlag(FLAGS_output_logs));
accumulator_state.MaybeMakeExtractor();
});
@@ -227,8 +231,9 @@
merged_calibration = aos::MergeFlatBuffers(&calibration.message(),
&solved_extrinsics.message());
- if (!FLAGS_output_calibration.empty()) {
- aos::WriteFlatbufferToJson(FLAGS_output_calibration, merged_calibration);
+ if (!absl::GetFlag(FLAGS_output_calibration).empty()) {
+ aos::WriteFlatbufferToJson(absl::GetFlag(FLAGS_output_calibration),
+ merged_calibration);
} else {
LOG(WARNING) << "Calibration filename not provided, so not saving it";
}
@@ -296,12 +301,12 @@
nominal_board_to_world.inverse())
.transpose();
- if (FLAGS_visualize) {
+ if (absl::GetFlag(FLAGS_visualize)) {
LOG(INFO) << "Showing visualization";
Visualize(data, calibration_parameters);
}
- if (FLAGS_plot) {
+ if (absl::GetFlag(FLAGS_plot)) {
Plot(data, calibration_parameters);
}
} // namespace vision
diff --git a/y2023/vision/calibrate_multi_cameras.cc b/y2023/vision/calibrate_multi_cameras.cc
index 48dffb9..8032c764 100644
--- a/y2023/vision/calibrate_multi_cameras.cc
+++ b/y2023/vision/calibrate_multi_cameras.cc
@@ -1,5 +1,7 @@
#include <numeric>
+#include "absl/flags/flag.h"
+
#include "aos/configuration.h"
#include "aos/events/logging/log_reader.h"
#include "aos/events/simulated_event_loop.h"
@@ -26,31 +28,30 @@
#include "y2023/vision/aprilrobotics.h"
#include "y2023/vision/vision_util.h"
-DEFINE_bool(alt_view, false,
- "If true, show visualization from field level, rather than above");
-DEFINE_string(config, "",
- "If set, override the log's config file with this one.");
-DEFINE_string(constants_path, "y2023/constants/constants.json",
- "Path to the constant file");
-DEFINE_double(max_pose_error, 5e-5,
- "Throw out target poses with a higher pose error than this");
-DEFINE_double(
- max_pose_error_ratio, 0.4,
- "Throw out target poses with a higher pose error ratio than this");
-DEFINE_string(output_folder, "/tmp",
- "Directory in which to store the updated calibration files");
-DEFINE_string(target_type, "charuco_diamond",
- "Type of target being used [aruco, charuco, charuco_diamond]");
-DEFINE_int32(team_number, 0,
- "Required: Use the calibration for a node with this team number");
-DEFINE_bool(use_full_logs, false,
- "If true, extract data from logs with images");
-DEFINE_uint64(
- wait_key, 1,
+ABSL_FLAG(bool, alt_view, false,
+ "If true, show visualization from field level, rather than above");
+ABSL_FLAG(std::string, config, "",
+ "If set, override the log's config file with this one.");
+ABSL_FLAG(std::string, constants_path, "y2023/constants/constants.json",
+ "Path to the constant file");
+ABSL_FLAG(double, max_pose_error, 5e-5,
+ "Throw out target poses with a higher pose error than this");
+ABSL_FLAG(double, max_pose_error_ratio, 0.4,
+ "Throw out target poses with a higher pose error ratio than this");
+ABSL_FLAG(std::string, output_folder, "/tmp",
+ "Directory in which to store the updated calibration files");
+ABSL_FLAG(std::string, target_type, "charuco_diamond",
+ "Type of target being used [aruco, charuco, charuco_diamond]");
+ABSL_FLAG(int32_t, team_number, 0,
+ "Required: Use the calibration for a node with this team number");
+ABSL_FLAG(bool, use_full_logs, false,
+ "If true, extract data from logs with images");
+ABSL_FLAG(
+ uint64_t, wait_key, 1,
"Time in ms to wait between images (0 to wait indefinitely until click)");
-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);
// Calibrate extrinsic relationship between cameras using two targets
// seen jointly between cameras. Uses two types of information: 1)
@@ -179,7 +180,7 @@
Eigen::Affine3d H_world_board;
H_world_board = Eigen::Translation3d::Identity() *
Eigen::AngleAxisd(M_PI / 2.0, Eigen::Vector3d::UnitX());
- if (FLAGS_alt_view) {
+ if (absl::GetFlag(FLAGS_alt_view)) {
// Don't rotate -- this is like viewing from the side
H_world_board = Eigen::Translation3d(0.0, 0.0, 3.0);
}
@@ -218,7 +219,7 @@
// Store this observation of the transform between two boards
two_board_extrinsics_list.push_back(boardA_boardB);
- if (FLAGS_visualize) {
+ if (absl::GetFlag(FLAGS_visualize)) {
vis_robot_.DrawFrameAxes(
H_world_board,
std::string("board ") + std::to_string(target_poses[from_index].id),
@@ -264,7 +265,8 @@
// This bit is just for visualization and checking purposes-- use the
// last two-board observation to figure out the current estimate
// between the two cameras
- if (FLAGS_visualize && two_board_extrinsics_list.size() > 0) {
+ if (absl::GetFlag(FLAGS_visualize) &&
+ two_board_extrinsics_list.size() > 0) {
draw_vis = true;
TimestampedPiDetection &last_two_board_ext =
two_board_extrinsics_list[two_board_extrinsics_list.size() - 1];
@@ -309,18 +311,18 @@
}
}
- if (FLAGS_visualize) {
+ if (absl::GetFlag(FLAGS_visualize)) {
if (!rgb_image.empty()) {
std::string image_name = node_name + " Image";
cv::Mat rgb_small;
cv::resize(rgb_image, rgb_small, cv::Size(), 0.5, 0.5);
cv::imshow(image_name, rgb_small);
- cv::waitKey(FLAGS_wait_key);
+ cv::waitKey(absl::GetFlag(FLAGS_wait_key));
}
if (draw_vis) {
cv::imshow("View", vis_robot_.image_);
- cv::waitKey(FLAGS_wait_key);
+ cv::waitKey(absl::GetFlag(FLAGS_wait_key));
vis_robot_.ClearImage();
}
}
@@ -337,21 +339,22 @@
for (const auto *target_pose_fbs : *map.target_poses()) {
// Skip detections with invalid ids
if (static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) <
- FLAGS_min_target_id ||
+ absl::GetFlag(FLAGS_min_target_id) ||
static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) >
- FLAGS_max_target_id) {
+ absl::GetFlag(FLAGS_max_target_id)) {
LOG(INFO) << "Skipping tag with invalid id of " << target_pose_fbs->id();
continue;
}
// Skip detections with high pose errors
- if (target_pose_fbs->pose_error() > FLAGS_max_pose_error) {
+ if (target_pose_fbs->pose_error() > absl::GetFlag(FLAGS_max_pose_error)) {
LOG(INFO) << "Skipping tag " << target_pose_fbs->id()
<< " due to pose error of " << target_pose_fbs->pose_error();
continue;
}
// Skip detections with high pose error ratios
- if (target_pose_fbs->pose_error_ratio() > FLAGS_max_pose_error_ratio) {
+ if (target_pose_fbs->pose_error_ratio() >
+ absl::GetFlag(FLAGS_max_pose_error_ratio)) {
LOG(INFO) << "Skipping tag " << target_pose_fbs->id()
<< " due to pose error ratio of "
<< target_pose_fbs->pose_error_ratio();
@@ -415,9 +418,10 @@
vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength);
std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config =
- (FLAGS_config.empty()
+ (absl::GetFlag(FLAGS_config).empty()
? std::nullopt
- : std::make_optional(aos::configuration::ReadConfig(FLAGS_config)));
+ : std::make_optional(
+ aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config))));
// open logfiles
aos::logger::LogReader reader(
@@ -435,10 +439,11 @@
reader.RemapLoggedChannel("/roborio/constants", "y2023.Constants");
reader.Register();
- SendSimulationConstants(reader.event_loop_factory(), FLAGS_team_number,
- FLAGS_constants_path);
+ SendSimulationConstants(reader.event_loop_factory(),
+ absl::GetFlag(FLAGS_team_number),
+ absl::GetFlag(FLAGS_constants_path));
- VLOG(1) << "Using target type " << FLAGS_target_type;
+ VLOG(1) << "Using target type " << absl::GetFlag(FLAGS_target_type);
std::vector<std::string> node_list;
node_list.push_back("pi1");
node_list.push_back("pi2");
@@ -468,7 +473,7 @@
calibration_list.push_back(calibration);
frc971::vision::TargetType target_type =
- frc971::vision::TargetTypeFromString(FLAGS_target_type);
+ frc971::vision::TargetTypeFromString(absl::GetFlag(FLAGS_target_type));
frc971::vision::CharucoExtractor *charuco_ext =
new frc971::vision::CharucoExtractor(calibration, target_type);
charuco_extractors.emplace_back(charuco_ext);
@@ -482,7 +487,7 @@
VLOG(1) << "Got extrinsics for " << node << " as\n"
<< default_extrinsics.back().matrix();
- if (FLAGS_use_full_logs) {
+ if (absl::GetFlag(FLAGS_use_full_logs)) {
LOG(INFO) << "Set up image callback for node " << node_list[i];
frc971::vision::ImageCallback *image_callback =
new frc971::vision::ImageCallback(
@@ -597,7 +602,7 @@
Eigen::Affine3d H_world_board;
H_world_board = Eigen::Translation3d::Identity() *
Eigen::AngleAxisd(M_PI / 2.0, Eigen::Vector3d::UnitX());
- if (FLAGS_alt_view) {
+ if (absl::GetFlag(FLAGS_alt_view)) {
H_world_board = Eigen::Translation3d(0.0, 0.0, 3.0);
}
@@ -676,11 +681,11 @@
// Assumes node_list name is of form "pi#" to create camera id
const std::string calibration_filename =
- FLAGS_output_folder +
- absl::StrFormat("/calibration_pi-%d-%s_cam-%s_%s.json",
- FLAGS_team_number, node_list[i + 1].substr(2, 3),
- calibration_list[i + 1]->camera_id()->data(),
- time_ss.str());
+ absl::GetFlag(FLAGS_output_folder) +
+ absl::StrFormat(
+ "/calibration_pi-%d-%s_cam-%s_%s.json",
+ absl::GetFlag(FLAGS_team_number), node_list[i + 1].substr(2, 3),
+ calibration_list[i + 1]->camera_id()->data(), time_ss.str());
LOG(INFO) << calibration_filename << " -> "
<< aos::FlatbufferToJson(merged_calibration,
diff --git a/y2023/vision/camera_monitor.cc b/y2023/vision/camera_monitor.cc
index e69fd7c..f5d8841 100644
--- a/y2023/vision/camera_monitor.cc
+++ b/y2023/vision/camera_monitor.cc
@@ -1,14 +1,17 @@
+#include "absl/flags/flag.h"
+
#include "aos/events/shm_event_loop.h"
#include "aos/init.h"
#include "y2023/vision/camera_monitor_lib.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.");
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());
diff --git a/y2023/vision/camera_reader.cc b/y2023/vision/camera_reader.cc
index 668026a..ba3defe 100644
--- a/y2023/vision/camera_reader.cc
+++ b/y2023/vision/camera_reader.cc
@@ -1,6 +1,7 @@
#include <linux/videodev2.h>
#include <sys/ioctl.h>
+#include "absl/flags/flag.h"
#include "absl/strings/str_cat.h"
#include "absl/strings/str_split.h"
@@ -11,16 +12,17 @@
#include "frc971/vision/v4l2_reader.h"
#include "y2023/vision/rkisp1-config.h"
-DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
-DEFINE_bool(lowlight_camera, true, "Switch to use imx462 image sensor.");
-DEFINE_int32(gain, 150, "analogue_gain");
+ABSL_FLAG(std::string, config, "aos_config.json",
+ "Path to the config file to use.");
+ABSL_FLAG(bool, lowlight_camera, true, "Switch to use imx462 image sensor.");
+ABSL_FLAG(int32_t, gain, 150, "analogue_gain");
-DEFINE_double(red, 1.252, "Red gain");
-DEFINE_double(green, 1, "Green gain");
-DEFINE_double(blue, 1.96, "Blue gain");
-DEFINE_double(exposure, 150, "Camera exposure");
-DEFINE_bool(send_downsized_images, false,
- "Whether to send downsized image for driver cam streaming.");
+ABSL_FLAG(double, red, 1.252, "Red gain");
+ABSL_FLAG(double, green, 1, "Green gain");
+ABSL_FLAG(double, blue, 1.96, "Blue gain");
+ABSL_FLAG(double, exposure, 150, "Camera exposure");
+ABSL_FLAG(bool, send_downsized_images, false,
+ "Whether to send downsized image for driver cam streaming.");
namespace y2023::vision {
namespace {
@@ -34,13 +36,15 @@
media_device->Log();
}
- const int kWidth = (FLAGS_lowlight_camera ? 1920 : 1296);
- const int kHeight = (FLAGS_lowlight_camera ? 1080 : 972);
- const int kColorFormat = (FLAGS_lowlight_camera ? MEDIA_BUS_FMT_SRGGB10_1X10
- : MEDIA_BUS_FMT_SBGGR10_1X10);
+ const int kWidth = (absl::GetFlag(FLAGS_lowlight_camera) ? 1920 : 1296);
+ const int kHeight = (absl::GetFlag(FLAGS_lowlight_camera) ? 1080 : 972);
+ const int kColorFormat =
+ (absl::GetFlag(FLAGS_lowlight_camera) ? MEDIA_BUS_FMT_SRGGB10_1X10
+ : MEDIA_BUS_FMT_SBGGR10_1X10);
const std::string_view kCameraDeviceString =
- (FLAGS_lowlight_camera ? "arducam-pivariety 4-000c" : "ov5647 4-0036");
+ (absl::GetFlag(FLAGS_lowlight_camera) ? "arducam-pivariety 4-000c"
+ : "ov5647 4-0036");
// Scale down the selfpath images so we can log at 30 Hz (but still detect
// april tags at a far enough distance)
@@ -106,7 +110,7 @@
media_device->FindLink("rkisp1_isp", 2, "rkisp1_resizer_mainpath", 0));
aos::FlatbufferDetachedBuffer<aos::Configuration> config =
- aos::configuration::ReadConfig(FLAGS_config);
+ aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
aos::ShmEventLoop event_loop(&config.message());
@@ -117,17 +121,17 @@
RockchipV4L2Reader v4l2_reader_selfpath(&event_loop, event_loop.epoll(),
rkisp1_selfpath->device(),
camera->device());
- if (FLAGS_lowlight_camera) {
- v4l2_reader_selfpath.SetGainExt(FLAGS_gain);
+ if (absl::GetFlag(FLAGS_lowlight_camera)) {
+ v4l2_reader_selfpath.SetGainExt(absl::GetFlag(FLAGS_gain));
v4l2_reader_selfpath.SetVerticalBlanking(1000);
- v4l2_reader_selfpath.SetExposure(FLAGS_exposure);
+ v4l2_reader_selfpath.SetExposure(absl::GetFlag(FLAGS_exposure));
} else {
v4l2_reader_selfpath.SetGainExt(1000);
v4l2_reader_selfpath.SetExposure(1000);
}
std::unique_ptr<RockchipV4L2Reader> v4l2_reader_mainpath;
- if (FLAGS_send_downsized_images) {
+ if (absl::GetFlag(FLAGS_send_downsized_images)) {
// Reader for driver cam streaming on logger pi, sending lower res images
v4l2_reader_mainpath = std::make_unique<RockchipV4L2Reader>(
&event_loop, event_loop.epoll(), rkisp1_mainpath->device(),
@@ -171,10 +175,14 @@
configuration.module_cfg_update |= RKISP1_CIF_ISP_MODULE_AWB_GAIN;
- configuration.others.awb_gain_config.gain_red = 256 * FLAGS_red;
- configuration.others.awb_gain_config.gain_green_r = 256 * FLAGS_green;
- configuration.others.awb_gain_config.gain_blue = 256 * FLAGS_blue;
- configuration.others.awb_gain_config.gain_green_b = 256 * FLAGS_green;
+ configuration.others.awb_gain_config.gain_red =
+ 256 * absl::GetFlag(FLAGS_red);
+ configuration.others.awb_gain_config.gain_green_r =
+ 256 * absl::GetFlag(FLAGS_green);
+ configuration.others.awb_gain_config.gain_blue =
+ 256 * absl::GetFlag(FLAGS_blue);
+ configuration.others.awb_gain_config.gain_green_b =
+ 256 * absl::GetFlag(FLAGS_green);
// Enable the AWB gains
configuration.module_en_update |= RKISP1_CIF_ISP_MODULE_AWB_GAIN;
diff --git a/y2023/vision/ccm.cc b/y2023/vision/ccm.cc
index d32cc2f..ecb9552 100644
--- a/y2023/vision/ccm.cc
+++ b/y2023/vision/ccm.cc
@@ -1,4 +1,5 @@
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include <opencv2/calib3d.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/imgproc.hpp>
diff --git a/y2023/vision/foxglove_image_converter.cc b/y2023/vision/foxglove_image_converter.cc
index bfaafc8..3bd0143 100644
--- a/y2023/vision/foxglove_image_converter.cc
+++ b/y2023/vision/foxglove_image_converter.cc
@@ -1,14 +1,17 @@
+#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.");
+ABSL_FLAG(std::string, config, "aos_config.json",
+ "Path to the 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());
diff --git a/y2023/vision/game_pieces_main.cc b/y2023/vision/game_pieces_main.cc
index b4ceff5..ff3ec7c 100644
--- a/y2023/vision/game_pieces_main.cc
+++ b/y2023/vision/game_pieces_main.cc
@@ -1,15 +1,18 @@
+#include "absl/flags/flag.h"
+
#include "aos/events/shm_event_loop.h"
#include "aos/init.h"
#include "y2023/vision/game_pieces.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.");
namespace y2023::vision {
namespace {
void GamePiecesDetectorMain() {
aos::FlatbufferDetachedBuffer<aos::Configuration> config =
- aos::configuration::ReadConfig(FLAGS_config);
+ aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
aos::ShmEventLoop event_loop(&config.message());
GamePiecesDetector game_pieces_detector(&event_loop);
event_loop.Run();
diff --git a/y2023/vision/image_logger.cc b/y2023/vision/image_logger.cc
index 45e25f6..a7c233d 100644
--- a/y2023/vision/image_logger.cc
+++ b/y2023/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"
@@ -11,16 +13,16 @@
#include "aos/logging/log_namer.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) {
@@ -32,19 +34,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());
@@ -56,11 +59,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;
}
@@ -95,7 +99,8 @@
last_rotation_time = event_loop.monotonic_now();
} else if (logging && !enabled &&
(timestamp - last_disable_time) >
- std::chrono::duration<double>(FLAGS_disabled_time)) {
+ std::chrono::duration<double>(
+ absl::GetFlag(FLAGS_disabled_time))) {
// Stop logging if we've been disabled for a non-negligible amount of
// time
LOG(INFO) << "Stopping logging";
diff --git a/y2023/vision/localization_verifier.cc b/y2023/vision/localization_verifier.cc
index 01ef9fe..fd24ffe 100644
--- a/y2023/vision/localization_verifier.cc
+++ b/y2023/vision/localization_verifier.cc
@@ -1,4 +1,6 @@
-#include "glog/logging.h"
+#include "absl/flags/flag.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/init.h"
#include "frc971/constants/constants_sender_lib.h"
@@ -7,12 +9,13 @@
#include "frc971/vision/vision_generated.h"
#include "y2023/localizer/localizer.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_uint64(min_april_id, 1,
- "Minimum april id to consider as part of the field and ignore");
-DEFINE_uint64(max_april_id, 8,
- "Maximum april id to consider as part of the field and ignore");
+ABSL_FLAG(uint64_t, min_april_id, 1,
+ "Minimum april id to consider as part of the field and ignore");
+ABSL_FLAG(uint64_t, max_april_id, 8,
+ "Maximum april id to consider as part of the field and ignore");
// This binary allows us to place extra april tags on the field and verify
// that we can compute their field pose correctly
@@ -43,8 +46,8 @@
for (const auto *target_pose : *detections.target_poses()) {
// Only look at april tags not part of the field
- if (target_pose->id() >= FLAGS_min_april_id &&
- target_pose->id() <= FLAGS_max_april_id) {
+ if (target_pose->id() >= absl::GetFlag(FLAGS_min_april_id) &&
+ target_pose->id() <= absl::GetFlag(FLAGS_max_april_id)) {
continue;
}
@@ -71,7 +74,7 @@
void LocalizationVerifierMain() {
aos::FlatbufferDetachedBuffer<aos::Configuration> config =
- aos::configuration::ReadConfig(FLAGS_config);
+ aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
frc971::constants::WaitForConstants<Constants>(&config.message());
diff --git a/y2023/vision/target_mapping.cc b/y2023/vision/target_mapping.cc
index af4c36c..f33a83a 100644
--- a/y2023/vision/target_mapping.cc
+++ b/y2023/vision/target_mapping.cc
@@ -20,43 +20,43 @@
#include "y2023/vision/aprilrobotics.h"
#include "y2023/vision/vision_util.h"
-DEFINE_string(config, "",
- "If set, override the log's config file with this one.");
-DEFINE_string(constants_path, "y2023/constants/constants.json",
- "Path to the constant file");
-DEFINE_string(dump_constraints_to, "/tmp/mapping_constraints.txt",
- "Write the target constraints to this path");
-DEFINE_string(dump_stats_to, "/tmp/mapping_stats.txt",
- "Write the mapping stats to this path");
-DEFINE_string(field_name, "charged_up",
- "Field name, for the output json filename and flatbuffer field");
-DEFINE_string(json_path, "y2023/vision/maps/target_map.json",
- "Specify path for json with initial pose guesses.");
-DEFINE_double(max_pose_error, 1e-6,
- "Throw out target poses with a higher pose error than this");
-DEFINE_double(
- max_pose_error_ratio, 0.4,
- "Throw out target poses with a higher pose error ratio than this");
-DEFINE_string(mcap_output_path, "", "Log to output.");
-DEFINE_string(output_dir, "y2023/vision/maps",
- "Directory to write solved target map to");
-DEFINE_double(pause_on_distance, 1.0,
- "Pause if two consecutive implied robot positions differ by more "
- "than this many meters");
-DEFINE_string(pi, "pi1", "Pi name to generate mcap log for; defaults to pi1.");
-DEFINE_uint64(skip_to, 1,
- "Start at combined image of this number (1 is the first image)");
-DEFINE_bool(solve, true, "Whether to solve for the field's target map.");
-DEFINE_int32(team_number, 0,
- "Required: Use the calibration for a node with this team number");
-DEFINE_uint64(wait_key, 1,
- "Time in ms to wait between images, if no click (0 to wait "
- "indefinitely until click).");
+ABSL_FLAG(std::string, config, "",
+ "If set, override the log's config file with this one.");
+ABSL_FLAG(std::string, constants_path, "y2023/constants/constants.json",
+ "Path to the constant file");
+ABSL_FLAG(std::string, dump_constraints_to, "/tmp/mapping_constraints.txt",
+ "Write the target constraints to this path");
+ABSL_FLAG(std::string, dump_stats_to, "/tmp/mapping_stats.txt",
+ "Write the mapping stats to this path");
+ABSL_FLAG(std::string, field_name, "charged_up",
+ "Field name, for the output json filename and flatbuffer field");
+ABSL_FLAG(std::string, json_path, "y2023/vision/maps/target_map.json",
+ "Specify path for json with initial pose guesses.");
+ABSL_FLAG(double, max_pose_error, 1e-6,
+ "Throw out target poses with a higher pose error than this");
+ABSL_FLAG(double, max_pose_error_ratio, 0.4,
+ "Throw out target poses with a higher pose error ratio than this");
+ABSL_FLAG(std::string, mcap_output_path, "", "Log to output.");
+ABSL_FLAG(std::string, output_dir, "y2023/vision/maps",
+ "Directory to write solved target map to");
+ABSL_FLAG(double, pause_on_distance, 1.0,
+ "Pause if two consecutive implied robot positions differ by more "
+ "than this many meters");
+ABSL_FLAG(std::string, pi, "pi1",
+ "Pi name to generate mcap log for; defaults to pi1.");
+ABSL_FLAG(uint64_t, skip_to, 1,
+ "Start at combined image of this number (1 is the first image)");
+ABSL_FLAG(bool, solve, true, "Whether to solve for the field's target map.");
+ABSL_FLAG(int32_t, team_number, 0,
+ "Required: Use the calibration for a node with this team number");
+ABSL_FLAG(uint64_t, wait_key, 1,
+ "Time in ms to wait between images, if no click (0 to wait "
+ "indefinitely until click).");
-DECLARE_int32(frozen_target_id);
-DECLARE_int32(min_target_id);
-DECLARE_int32(max_target_id);
-DECLARE_bool(visualize_solver);
+ABSL_DECLARE_FLAG(int32_t, frozen_target_id);
+ABSL_DECLARE_FLAG(int32_t, min_target_id);
+ABSL_DECLARE_FLAG(int32_t, max_target_id);
+ABSL_DECLARE_FLAG(bool, visualize_solver);
namespace y2023::vision {
using frc971::vision::DataAdapter;
@@ -131,8 +131,8 @@
{"pi4", cv::Scalar(255, 165, 0)},
};
-const auto TargetMapperReplay::kFixedTargetMapper =
- TargetMapper(FLAGS_json_path, ceres::examples::VectorOfConstraints{});
+const auto TargetMapperReplay::kFixedTargetMapper = TargetMapper(
+ absl::GetFlag(FLAGS_json_path), ceres::examples::VectorOfConstraints{});
Eigen::Affine3d TargetMapperReplay::CameraToRobotDetection(
Eigen::Affine3d H_camera_target, Eigen::Affine3d extrinsics) {
@@ -164,8 +164,9 @@
reader_->Register();
- SendSimulationConstants(reader_->event_loop_factory(), FLAGS_team_number,
- FLAGS_constants_path);
+ SendSimulationConstants(reader_->event_loop_factory(),
+ absl::GetFlag(FLAGS_team_number),
+ absl::GetFlag(FLAGS_constants_path));
for (size_t i = 1; i < kNumPis; i++) {
std::string node_name = "pi" + std::to_string(i);
@@ -178,23 +179,24 @@
mapping_event_loops_[mapping_event_loops_.size() - 1].get());
}
- if (!FLAGS_mcap_output_path.empty()) {
- LOG(INFO) << "Writing out mcap file to " << FLAGS_mcap_output_path;
- const aos::Node *node =
- aos::configuration::GetNode(reader_->configuration(), FLAGS_pi);
+ if (!absl::GetFlag(FLAGS_mcap_output_path).empty()) {
+ LOG(INFO) << "Writing out mcap file to "
+ << absl::GetFlag(FLAGS_mcap_output_path);
+ const aos::Node *node = aos::configuration::GetNode(
+ reader_->configuration(), absl::GetFlag(FLAGS_pi));
reader_->event_loop_factory()->GetNodeEventLoopFactory(node)->OnStartup(
[this, node]() {
mcap_event_loop_ =
reader_->event_loop_factory()->MakeEventLoop("mcap", node);
relogger_ = std::make_unique<aos::McapLogger>(
- mcap_event_loop_.get(), FLAGS_mcap_output_path,
+ mcap_event_loop_.get(), absl::GetFlag(FLAGS_mcap_output_path),
aos::McapLogger::Serialization::kFlatbuffer,
aos::McapLogger::CanonicalChannelNames::kShortened,
aos::McapLogger::Compression::kLz4);
});
}
- if (FLAGS_visualize_solver) {
+ if (absl::GetFlag(FLAGS_visualize_solver)) {
vis_robot_.ClearImage();
const double kFocalLength = 500.0;
vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength);
@@ -214,21 +216,22 @@
for (const auto *target_pose_fbs : *map.target_poses()) {
// Skip detections with invalid ids
if (static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) <
- FLAGS_min_target_id ||
+ absl::GetFlag(FLAGS_min_target_id) ||
static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) >
- FLAGS_max_target_id) {
+ absl::GetFlag(FLAGS_max_target_id)) {
VLOG(1) << "Skipping tag with invalid id of " << target_pose_fbs->id();
continue;
}
// Skip detections with high pose errors
- if (target_pose_fbs->pose_error() > FLAGS_max_pose_error) {
+ if (target_pose_fbs->pose_error() > absl::GetFlag(FLAGS_max_pose_error)) {
VLOG(1) << "Skipping tag " << target_pose_fbs->id()
<< " due to pose error of " << target_pose_fbs->pose_error();
continue;
}
// Skip detections with high pose error ratios
- if (target_pose_fbs->pose_error_ratio() > FLAGS_max_pose_error_ratio) {
+ if (target_pose_fbs->pose_error_ratio() >
+ absl::GetFlag(FLAGS_max_pose_error_ratio)) {
VLOG(1) << "Skipping tag " << target_pose_fbs->id()
<< " due to pose error ratio of "
<< target_pose_fbs->pose_error_ratio();
@@ -259,7 +262,7 @@
.distortion_factor = distortion_factor,
.id = static_cast<TargetMapper::TargetId>(target_pose.id)});
- if (FLAGS_visualize_solver) {
+ if (absl::GetFlag(FLAGS_visualize_solver)) {
// If we've already drawn this node_name in the current image,
// display the image before clearing and adding the new poses
if (drawn_nodes_.count(node_name) != 0) {
@@ -269,20 +272,21 @@
cv::Point(600, 10), cv::FONT_HERSHEY_PLAIN, 1.0,
cv::Scalar(255, 255, 255));
- if (display_count_ >= FLAGS_skip_to) {
+ if (display_count_ >= absl::GetFlag(FLAGS_skip_to)) {
VLOG(1) << "Showing image for node " << node_name
<< " since we've drawn it already";
cv::imshow("View", vis_robot_.image_);
// Pause if delta_T is too large, but only after first image (to make
// sure the delta's are correct
- if (max_delta_T_world_robot_ > FLAGS_pause_on_distance &&
+ if (max_delta_T_world_robot_ >
+ absl::GetFlag(FLAGS_pause_on_distance) &&
display_count_ > 1) {
LOG(INFO) << "Pausing since the delta between robot estimates is "
<< max_delta_T_world_robot_ << " which is > threshold of "
- << FLAGS_pause_on_distance;
+ << absl::GetFlag(FLAGS_pause_on_distance);
cv::waitKey(0);
} else {
- cv::waitKey(FLAGS_wait_key);
+ cv::waitKey(absl::GetFlag(FLAGS_wait_key));
}
max_delta_T_world_robot_ = 0.0;
} else {
@@ -303,7 +307,8 @@
<< H_world_robot.translation().transpose();
label << "id " << target_pose_fbs->id() << ": err (% of max): "
- << (target_pose_fbs->pose_error() / FLAGS_max_pose_error)
+ << (target_pose_fbs->pose_error() /
+ absl::GetFlag(FLAGS_max_pose_error))
<< " err_ratio: " << target_pose_fbs->pose_error_ratio() << " ";
vis_robot_.DrawRobotOutline(H_world_robot, node_name,
@@ -326,7 +331,7 @@
}
}
- if (FLAGS_visualize_solver) {
+ if (absl::GetFlag(FLAGS_visualize_solver)) {
if (drew) {
// Collect all the labels from a given node, and add the text
size_t pi_number =
@@ -338,13 +343,13 @@
drawn_nodes_.emplace(node_name);
} else if (pi_distributed_time - last_draw_time_ >
std::chrono::milliseconds(30) &&
- display_count_ >= FLAGS_skip_to) {
+ display_count_ >= absl::GetFlag(FLAGS_skip_to)) {
cv::putText(vis_robot_.image_, "No detections", cv::Point(10, 0),
cv::FONT_HERSHEY_PLAIN, 1.0, kPiColors.at(node_name));
// Display and clear the image if we haven't draw in a while
VLOG(1) << "Displaying image due to time lapse";
cv::imshow("View", vis_robot_.image_);
- cv::waitKey(FLAGS_wait_key);
+ cv::waitKey(absl::GetFlag(FLAGS_wait_key));
vis_robot_.ClearImage();
max_delta_T_world_robot_ = 0.0;
drawn_nodes_.clear();
@@ -378,7 +383,7 @@
}
void TargetMapperReplay::MaybeSolve() {
- if (FLAGS_solve) {
+ if (absl::GetFlag(FLAGS_solve)) {
auto target_constraints =
DataAdapter::MatchTargetDetections(timestamped_target_detections_);
@@ -399,14 +404,15 @@
LOG(INFO) << "Solving for locations of tags with "
<< target_constraints.size() << " constraints";
- TargetMapper mapper(FLAGS_json_path, target_constraints);
- mapper.Solve(FLAGS_field_name, FLAGS_output_dir);
+ TargetMapper mapper(absl::GetFlag(FLAGS_json_path), target_constraints);
+ mapper.Solve(absl::GetFlag(FLAGS_field_name),
+ absl::GetFlag(FLAGS_output_dir));
- if (!FLAGS_dump_constraints_to.empty()) {
- mapper.DumpConstraints(FLAGS_dump_constraints_to);
+ if (!absl::GetFlag(FLAGS_dump_constraints_to).empty()) {
+ mapper.DumpConstraints(absl::GetFlag(FLAGS_dump_constraints_to));
}
- if (!FLAGS_dump_stats_to.empty()) {
- mapper.DumpStats(FLAGS_dump_stats_to);
+ if (!absl::GetFlag(FLAGS_dump_stats_to).empty()) {
+ mapper.DumpStats(absl::GetFlag(FLAGS_dump_stats_to));
}
}
}
@@ -415,9 +421,10 @@
std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config =
- (FLAGS_config.empty()
+ (absl::GetFlag(FLAGS_config).empty()
? std::nullopt
- : std::make_optional(aos::configuration::ReadConfig(FLAGS_config)));
+ : std::make_optional(
+ aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config))));
// Open logfiles
aos::logger::LogReader reader(
diff --git a/y2023/vision/video_ripper.cc b/y2023/vision/video_ripper.cc
index 3c93139..ac24d68 100644
--- a/y2023/vision/video_ripper.cc
+++ b/y2023/vision/video_ripper.cc
@@ -2,8 +2,9 @@
#include <cstdlib>
-#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"
@@ -11,14 +12,14 @@
#include "aos/scoped/scoped_fd.h"
#include "frc971/vision/vision_generated.h"
-DEFINE_string(channel, "/camera", "Channel name for the image.");
-DEFINE_int32(width, 1280, "Width of the image");
-DEFINE_int32(height, 720, "Height of the image");
-DEFINE_string(ffmpeg_binary, "external/ffmpeg/ffmpeg",
- "The path to the ffmpeg binary");
-DEFINE_string(output_path, "video_ripper_output.mp4",
- "The path to output the mp4 video");
-DEFINE_bool(flip, true, "If true, rotate the video 180 deg.");
+ABSL_FLAG(std::string, channel, "/camera", "Channel name for the image.");
+ABSL_FLAG(int32_t, width, 1280, "Width of the image");
+ABSL_FLAG(int32_t, height, 720, "Height of the image");
+ABSL_FLAG(std::string, ffmpeg_binary, "external/ffmpeg/ffmpeg",
+ "The path to the ffmpeg binary");
+ABSL_FLAG(std::string, output_path, "video_ripper_output.mp4",
+ "The path to output the mp4 video");
+ABSL_FLAG(bool, flip, true, "If true, rotate the video 180 deg.");
// Replays a log and dumps the contents of /camera frc971.vision.CameraImage
// directly to stdout.
@@ -30,15 +31,16 @@
// Start ffmpeg
std::stringstream command;
- command << FLAGS_ffmpeg_binary;
+ command << absl::GetFlag(FLAGS_ffmpeg_binary);
command << " -framerate 30 -f rawvideo -pix_fmt yuyv422";
- command << " -s " << FLAGS_width << "x" << FLAGS_height;
+ command << " -s " << absl::GetFlag(FLAGS_width) << "x"
+ << absl::GetFlag(FLAGS_height);
command << " -i pipe:";
command << " -c:v libx264 -f mp4";
- if (FLAGS_flip) {
+ if (absl::GetFlag(FLAGS_flip)) {
command << " -vf rotate=PI";
}
- command << " \"" << FLAGS_output_path << "\"";
+ command << " \"" << absl::GetFlag(FLAGS_output_path) << "\"";
FILE *stream = popen(command.str().c_str(), "w");
@@ -61,10 +63,11 @@
event_loop =
reader.event_loop_factory()->MakeEventLoop("video_ripper", node);
event_loop->MakeWatcher(
- FLAGS_channel, [&stream](const frc971::vision::CameraImage &image) {
- CHECK_EQ(FLAGS_width, image.cols())
+ absl::GetFlag(FLAGS_channel),
+ [&stream](const frc971::vision::CameraImage &image) {
+ CHECK_EQ(absl::GetFlag(FLAGS_width), image.cols())
<< "Image width needs to match the images in the logfile";
- CHECK_EQ(FLAGS_height, image.rows())
+ CHECK_EQ(absl::GetFlag(FLAGS_height), image.rows())
<< "Image width needs to match the images in the logfile";
const size_t bytes_written =
diff --git a/y2023/vision/viewer.cc b/y2023/vision/viewer.cc
index 78731e5..83ef483 100644
--- a/y2023/vision/viewer.cc
+++ b/y2023/vision/viewer.cc
@@ -1,3 +1,4 @@
+#include "absl/flags/flag.h"
#include "absl/strings/match.h"
#include <opencv2/calib3d.hpp>
#include <opencv2/highgui/highgui.hpp>
@@ -11,12 +12,13 @@
#include "frc971/vision/vision_generated.h"
#include "y2023/vision/vision_util.h"
-DEFINE_string(capture, "",
- "If set, capture a single image and save it to this filename.");
-DEFINE_string(channel, "/camera", "Channel name for the image.");
-DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
-DEFINE_int32(rate, 100, "Time in milliseconds to wait between images");
-DEFINE_double(scale, 1.0, "Scale factor for images being displayed");
+ABSL_FLAG(std::string, capture, "",
+ "If set, capture a single image and save it to this filename.");
+ABSL_FLAG(std::string, channel, "/camera", "Channel name for the image.");
+ABSL_FLAG(std::string, config, "aos_config.json",
+ "Path to the config file to use.");
+ABSL_FLAG(int32_t, rate, 100, "Time in milliseconds to wait between images");
+ABSL_FLAG(double, scale, 1.0, "Scale factor for images being displayed");
namespace y2023::vision {
namespace {
@@ -41,12 +43,12 @@
cv::Mat bgr_image(cv::Size(image->cols(), image->rows()), CV_8UC3);
cv::cvtColor(image_color_mat, bgr_image, cv::COLOR_YUV2BGR_YUYV);
- if (!FLAGS_capture.empty()) {
- if (absl::EndsWith(FLAGS_capture, ".bfbs")) {
- aos::WriteFlatbufferToFile(FLAGS_capture,
+ if (!absl::GetFlag(FLAGS_capture).empty()) {
+ if (absl::EndsWith(absl::GetFlag(FLAGS_capture), ".bfbs")) {
+ aos::WriteFlatbufferToFile(absl::GetFlag(FLAGS_capture),
image_fetcher->CopyFlatBuffer());
} else {
- cv::imwrite(FLAGS_capture, bgr_image);
+ cv::imwrite(absl::GetFlag(FLAGS_capture), bgr_image);
}
return false;
@@ -54,9 +56,9 @@
cv::Mat undistorted_image;
cv::undistort(bgr_image, undistorted_image, intrinsics, dist_coeffs);
- if (FLAGS_scale != 1.0) {
- cv::resize(undistorted_image, undistorted_image, cv::Size(), FLAGS_scale,
- FLAGS_scale);
+ if (absl::GetFlag(FLAGS_scale) != 1.0) {
+ cv::resize(undistorted_image, undistorted_image, cv::Size(),
+ absl::GetFlag(FLAGS_scale), absl::GetFlag(FLAGS_scale));
}
cv::imshow("Display", undistorted_image);
@@ -76,7 +78,7 @@
void ViewerMain() {
aos::FlatbufferDetachedBuffer<aos::Configuration> config =
- aos::configuration::ReadConfig(FLAGS_config);
+ aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
frc971::constants::WaitForConstants<Constants>(&config.message());
@@ -89,7 +91,7 @@
const cv::Mat dist_coeffs = CameraDistCoeffs(calibration_data);
aos::Fetcher<CameraImage> image_fetcher =
- event_loop.MakeFetcher<CameraImage>(FLAGS_channel);
+ event_loop.MakeFetcher<CameraImage>(absl::GetFlag(FLAGS_channel));
// Run the display loop
event_loop.AddPhasedLoop(
@@ -99,7 +101,7 @@
event_loop.Exit();
};
},
- ::std::chrono::milliseconds(FLAGS_rate));
+ ::std::chrono::milliseconds(absl::GetFlag(FLAGS_rate)));
event_loop.Run();
diff --git a/y2023/vision/vision_util.cc b/y2023/vision/vision_util.cc
index ca5ad89..276341a 100644
--- a/y2023/vision/vision_util.cc
+++ b/y2023/vision/vision_util.cc
@@ -1,6 +1,7 @@
#include "y2023/vision/vision_util.h"
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
namespace y2023::vision {
diff --git a/y2023/vision/yolov5.cc b/y2023/vision/yolov5.cc
index e62b106..f4c2e39 100644
--- a/y2023/vision/yolov5.cc
+++ b/y2023/vision/yolov5.cc
@@ -12,23 +12,23 @@
#include <chrono>
#include <string>
+#include "absl/flags/flag.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "absl/types/span.h"
-#include "gflags/gflags.h"
-#include "glog/logging.h"
#include <opencv2/dnn.hpp>
-DEFINE_double(conf_threshold, 0.9,
- "Threshold value for confidence scores. Detections with a "
- "confidence score below this value will be ignored.");
+ABSL_FLAG(double, conf_threshold, 0.9,
+ "Threshold value for confidence scores. Detections with a "
+ "confidence score below this value will be ignored.");
-DEFINE_double(
- nms_threshold, 0.5,
- "Threshold value for non-maximum suppression. Detections with an "
- "intersection-over-union value below this value will be removed.");
+ABSL_FLAG(double, nms_threshold, 0.5,
+ "Threshold value for non-maximum suppression. Detections with an "
+ "intersection-over-union value below this value will be removed.");
-DEFINE_int32(nthreads, 6, "Number of threads to use during inference.");
+ABSL_FLAG(int32_t, nthreads, 6, "Number of threads to use during inference.");
-DEFINE_bool(visualize_detections, false, "Display inference output");
+ABSL_FLAG(bool, visualize_detections, false, "Display inference output");
namespace y2023::vision {
@@ -134,7 +134,7 @@
input_8_ =
absl::Span(interpreter_->typed_tensor<uint8_t>(input_), tensor_size);
- interpreter_->SetNumThreads(FLAGS_nthreads);
+ interpreter_->SetNumThreads(absl::GetFlag(FLAGS_nthreads));
VLOG(1) << "Load model: Done";
}
@@ -184,7 +184,7 @@
cv::Point class_id;
for (int i = 0; i < rows; i++) {
- if (orig_preds[i][4] > FLAGS_conf_threshold) {
+ if (orig_preds[i][4] > absl::GetFlag(FLAGS_conf_threshold)) {
float x = orig_preds[i][0];
float y = orig_preds[i][1];
float w = orig_preds[i][2];
@@ -200,7 +200,7 @@
cv::minMaxLoc(scores, nullptr, &confidence, nullptr, &class_id);
scores.clear();
- if (confidence > FLAGS_conf_threshold) {
+ if (confidence > absl::GetFlag(FLAGS_conf_threshold)) {
Detection detection{cv::Rect(left, top, width, height), confidence,
class_id.x};
detections->push_back(detection);
@@ -216,8 +216,8 @@
confidences.push_back(d.confidence);
}
- cv::dnn::NMSBoxes(boxes, confidences, FLAGS_conf_threshold,
- FLAGS_nms_threshold, *indices);
+ cv::dnn::NMSBoxes(boxes, confidences, absl::GetFlag(FLAGS_conf_threshold),
+ absl::GetFlag(FLAGS_nms_threshold), *indices);
std::vector<Detection> filtered_detections;
for (size_t i = 0; i < indices->size(); i++) {
@@ -277,7 +277,7 @@
<< std::chrono::duration_cast<std::chrono::milliseconds>(stop - start)
.count();
- if (FLAGS_visualize_detections) {
+ if (absl::GetFlag(FLAGS_visualize_detections)) {
cv::resize(frame, frame, cv::Size(img_width_, img_height_), 0, 0, true);
for (size_t i = 0; i < filtered_detections.size(); i++) {
VLOG(1) << "Bounding Box | X: " << filtered_detections[i].box.x
diff --git a/y2023/wpilib_interface.cc b/y2023/wpilib_interface.cc
index d0d952c..bc14311 100644
--- a/y2023/wpilib_interface.cc
+++ b/y2023/wpilib_interface.cc
@@ -62,9 +62,9 @@
#include "y2023/control_loops/superstructure/superstructure_output_generated.h"
#include "y2023/control_loops/superstructure/superstructure_position_static.h"
-DEFINE_bool(ctre_diag_server, false,
- "If true, enable the diagnostics server for interacting with "
- "devices on the CAN bus using Phoenix Tuner");
+ABSL_FLAG(bool, ctre_diag_server, false,
+ "If true, enable the diagnostics server for interacting with "
+ "devices on the CAN bus using Phoenix Tuner");
using ::aos::monotonic_clock;
using ::frc971::CANConfiguration;
@@ -1002,7 +1002,7 @@
// Thread 5.
// Set up CAN.
- if (!FLAGS_ctre_diag_server) {
+ if (!absl::GetFlag(FLAGS_ctre_diag_server)) {
c_Phoenix_Diagnostics_SetSecondsToStart(-1);
c_Phoenix_Diagnostics_Dispose();
}