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/y2024_swerve/BUILD b/y2024_swerve/BUILD
index cbdb79b..acc300d 100644
--- a/y2024_swerve/BUILD
+++ b/y2024_swerve/BUILD
@@ -103,8 +103,9 @@
"//aos/network:team_number",
"//frc971:constants",
"//y2024_swerve/constants:constants_fbs",
- "@com_github_google_glog//:glog",
"@com_google_absl//absl/base",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
)
@@ -114,7 +115,7 @@
deps = [
":swerve_publisher_lib",
"//aos/events:shm_event_loop",
- "@com_github_gflags_gflags//:gflags",
+ "@com_google_absl//absl/flags:flag",
],
)
@@ -126,7 +127,8 @@
"//aos:init",
"//aos/events:event_loop",
"//frc971/control_loops/swerve:swerve_drivetrain_output_fbs",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
)
diff --git a/y2024_swerve/constants.cc b/y2024_swerve/constants.cc
index 4f938a3..676c6b7 100644
--- a/y2024_swerve/constants.cc
+++ b/y2024_swerve/constants.cc
@@ -2,7 +2,8 @@
#include <cstdint>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/network/team_number.h"
diff --git a/y2024_swerve/constants/BUILD b/y2024_swerve/constants/BUILD
index 6de0fb0..416b10c 100644
--- a/y2024_swerve/constants/BUILD
+++ b/y2024_swerve/constants/BUILD
@@ -90,7 +90,8 @@
":constants_list_fbs",
"//aos:init",
"//aos:json_to_flatbuffer",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
)
diff --git a/y2024_swerve/constants/constants_formatter.cc b/y2024_swerve/constants/constants_formatter.cc
index 2ebb9b5..afeb12d 100644
--- a/y2024_swerve/constants/constants_formatter.cc
+++ b/y2024_swerve/constants/constants_formatter.cc
@@ -1,4 +1,5 @@
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/flatbuffers.h"
#include "aos/init.h"
diff --git a/y2024_swerve/constants/constants_sender.cc b/y2024_swerve/constants/constants_sender.cc
index c624572..74f1020 100644
--- a/y2024_swerve/constants/constants_sender.cc
+++ b/y2024_swerve/constants/constants_sender.cc
@@ -1,5 +1,6 @@
-#include "gflags/gflags.h"
-#include "glog/logging.h"
+#include "absl/flags/flag.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/configuration.h"
#include "aos/events/shm_event_loop.h"
@@ -9,17 +10,18 @@
#include "y2024_swerve/constants/constants_generated.h"
#include "y2024_swerve/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<y2024_swerve::Constants,
y2024_swerve::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/y2024_swerve/swerve_publisher_lib.h b/y2024_swerve/swerve_publisher_lib.h
index e577455..e490738 100644
--- a/y2024_swerve/swerve_publisher_lib.h
+++ b/y2024_swerve/swerve_publisher_lib.h
@@ -1,8 +1,9 @@
#ifndef Y2024_SWERVE_SWERVE_PUBLISHER_H_
#define Y2024_SWERVE_SWERVE_PUBLISHER_H_
-#include "gflags/gflags.h"
-#include "glog/logging.h"
+#include "absl/flags/flag.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/events/event_loop.h"
#include "aos/flatbuffer_merge.h"
diff --git a/y2024_swerve/swerve_publisher_main.cc b/y2024_swerve/swerve_publisher_main.cc
index 5409da3..da7a99f 100644
--- a/y2024_swerve/swerve_publisher_main.cc
+++ b/y2024_swerve/swerve_publisher_main.cc
@@ -1,24 +1,27 @@
+#include "absl/flags/flag.h"
+
#include "aos/events/shm_event_loop.h"
#include "y2024_swerve/swerve_publisher_lib.h"
-DEFINE_double(duration, 100.0, "Length of time in Ms to apply current for");
-DEFINE_string(drivetrain_position, "swerve_drivetrain_output.json",
- "The path to the json drivetrain position to apply");
-DEFINE_string(config, "aos_config.json", "The path to aos_config.json");
+ABSL_FLAG(double, duration, 100.0, "Length of time in Ms to apply current for");
+ABSL_FLAG(std::string, drivetrain_position, "swerve_drivetrain_output.json",
+ "The path to the json drivetrain position to apply");
+ABSL_FLAG(std::string, config, "aos_config.json",
+ "The path to aos_config.json");
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());
std::unique_ptr<aos::ExitHandle> exit_handle = event_loop.MakeExitHandle();
- y2024_swerve::SwervePublisher publisher(&event_loop, exit_handle.get(),
- FLAGS_drivetrain_position,
- FLAGS_duration);
+ y2024_swerve::SwervePublisher publisher(
+ &event_loop, exit_handle.get(), absl::GetFlag(FLAGS_drivetrain_position),
+ absl::GetFlag(FLAGS_duration));
event_loop.Run();
}
diff --git a/y2024_swerve/vision/BUILD b/y2024_swerve/vision/BUILD
index 7bbfef9..6342b07 100644
--- a/y2024_swerve/vision/BUILD
+++ b/y2024_swerve/vision/BUILD
@@ -54,9 +54,10 @@
"//third_party:cudart",
"//third_party/apriltag",
"//y2024_swerve/constants:constants_fbs",
- "@com_github_gflags_gflags//:gflags",
- "@com_github_google_glog//:glog",
"@com_github_nvidia_cccl//:cccl",
+ "@com_google_absl//absl/flags:flag",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
)
diff --git a/y2024_swerve/vision/apriltag_detector.cc b/y2024_swerve/vision/apriltag_detector.cc
index 4d4025e..2032e2e 100644
--- a/y2024_swerve/vision/apriltag_detector.cc
+++ b/y2024_swerve/vision/apriltag_detector.cc
@@ -6,12 +6,13 @@
#include "y2024_swerve/constants/constants_generated.h"
#include "y2024_swerve/vision/vision_util.h"
-DEFINE_string(channel, "/camera", "Channel name");
-DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
+ABSL_FLAG(std::string, channel, "/camera", "Channel name");
+ABSL_FLAG(std::string, config, "aos_config.json",
+ "Path to the config file to use.");
void GpuApriltagDetector() {
aos::FlatbufferDetachedBuffer<aos::Configuration> config =
- aos::configuration::ReadConfig(FLAGS_config);
+ aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
frc971::constants::WaitForConstants<y2024_swerve::Constants>(
&config.message());
@@ -21,15 +22,15 @@
const frc971::constants::ConstantsFetcher<y2024_swerve::Constants>
calibration_data(&event_loop);
- CHECK(FLAGS_channel.length() == 8);
- int camera_id = std::stoi(FLAGS_channel.substr(7, 1));
+ CHECK(absl::GetFlag(FLAGS_channel).length() == 8);
+ int camera_id = std::stoi(absl::GetFlag(FLAGS_channel).substr(7, 1));
const frc971::vision::calibration::CameraCalibration *calibration =
y2024_swerve::vision::FindCameraCalibration(
calibration_data.constants(),
event_loop.node()->name()->string_view(), camera_id);
- frc971::apriltag::ApriltagDetector detector(&event_loop, FLAGS_channel,
- calibration);
+ frc971::apriltag::ApriltagDetector detector(
+ &event_loop, absl::GetFlag(FLAGS_channel), calibration);
// TODO(austin): Figure out our core pinning strategy.
// event_loop.SetRuntimeAffinity(aos::MakeCpusetFromCpus({5}));
diff --git a/y2024_swerve/vision/target_mapping.cc b/y2024_swerve/vision/target_mapping.cc
index c540654..b8b1f62 100644
--- a/y2024_swerve/vision/target_mapping.cc
+++ b/y2024_swerve/vision/target_mapping.cc
@@ -1,6 +1,7 @@
#include <string>
#include "Eigen/Dense"
+#include "absl/flags/flag.h"
#include "opencv2/aruco.hpp"
#include "opencv2/calib3d.hpp"
#include "opencv2/core/eigen.hpp"
@@ -25,46 +26,45 @@
#include "y2024_swerve/constants/simulated_constants_sender.h"
#include "y2024_swerve/vision/vision_util.h"
-DEFINE_string(config, "",
- "If set, override the log's config file with this one.");
-DEFINE_string(constants_path, "y2024_swerve/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, "crescendo",
- "Field name, for the output json filename and flatbuffer field");
-DEFINE_string(json_path, "y2024_swerve/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, "y2024_swerve/vision/maps",
- "Directory to write solved target map to");
-DEFINE_double(pause_on_distance, 2.0,
- "Pause if two consecutive implied robot positions differ by more "
- "than this many meters");
-DEFINE_string(orin, "orin1",
- "Orin name to generate mcap log for; defaults to orin1.");
-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_bool(split_field, false,
- "Whether to break solve into two sides of field");
-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, "y2024_swerve/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, "crescendo",
+ "Field name, for the output json filename and flatbuffer field");
+ABSL_FLAG(std::string, json_path, "y2024_swerve/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, "y2024_swerve/vision/maps",
+ "Directory to write solved target map to");
+ABSL_FLAG(double, pause_on_distance, 2.0,
+ "Pause if two consecutive implied robot positions differ by more "
+ "than this many meters");
+ABSL_FLAG(std::string, orin, "orin1",
+ "Orin name to generate mcap log for; defaults to orin1.");
+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(bool, split_field, false,
+ "Whether to break solve into two sides of field");
+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 y2024_swerve::vision {
using frc971::vision::DataAdapter;
@@ -149,8 +149,8 @@
{9, "blue"}, {10, "blue"}, {11, "red"}, {12, "red"},
{13, "red"}, {14, "blue"}, {15, "blue"}, {16, "blue"}};
-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) {
@@ -174,10 +174,11 @@
reader_->MaybeRemapLoggedChannel<Constants>("/roborio/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));
- if (FLAGS_visualize_solver) {
+ if (absl::GetFlag(FLAGS_visualize_solver)) {
vis_robot_.ClearImage();
// Set focal length to zoomed in, to view extrinsics
const double kFocalLength = 1500.0;
@@ -199,7 +200,7 @@
mapping_event_loops_[mapping_event_loops_.size() - 1].get(),
&constants_fetcher, camera_node.camera_number);
- if (FLAGS_visualize_solver) {
+ if (absl::GetFlag(FLAGS_visualize_solver)) {
// Show the extrinsics calibration to start, for reference to confirm
const auto *calibration = FindCameraCalibration(
constants_fetcher.constants(),
@@ -216,7 +217,7 @@
}
}
- if (FLAGS_visualize_solver) {
+ if (absl::GetFlag(FLAGS_visualize_solver)) {
cv::imshow("Extrinsics", vis_robot_.image_);
cv::waitKey(0);
vis_robot_.ClearImage();
@@ -244,21 +245,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();
@@ -298,7 +300,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 camera_name in the current image,
// display the image before clearing and adding the new poses
if (drawn_cameras_.count(camera_name) != 0) {
@@ -308,20 +310,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 camera " << camera_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 {
@@ -343,7 +346,8 @@
label << "id " << target_pose_fbs->id()
<< ": err (% of max): " << target_pose_fbs->pose_error() << " ("
- << (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, camera_name,
@@ -365,7 +369,7 @@
last_H_world_robot_ = H_world_robot;
}
}
- if (FLAGS_visualize_solver) {
+ if (absl::GetFlag(FLAGS_visualize_solver)) {
if (drew) {
// Collect all the labels from a given camera, and add the text
// TODO: Need to fix this one
@@ -376,7 +380,7 @@
drawn_cameras_.emplace(camera_name);
} else if (node_distributed_time - last_draw_time_ >
std::chrono::milliseconds(30) &&
- display_count_ >= FLAGS_skip_to && drew) {
+ display_count_ >= absl::GetFlag(FLAGS_skip_to) && drew) {
// TODO: Check on 30ms value-- does this make sense?
double delta_t = (node_distributed_time - last_draw_time_).count() / 1e6;
VLOG(1) << "Last result was " << delta_t << "ms ago";
@@ -386,7 +390,7 @@
// 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));
max_delta_T_world_robot_ = 0.0;
drawn_cameras_.clear();
}
@@ -425,11 +429,11 @@
}
void TargetMapperReplay::MaybeSolve() {
- if (FLAGS_solve) {
+ if (absl::GetFlag(FLAGS_solve)) {
auto target_constraints =
DataAdapter::MatchTargetDetections(timestamped_target_detections_);
- if (FLAGS_split_field) {
+ if (absl::GetFlag(FLAGS_split_field)) {
// Remove constraints between the two sides of the field - these are
// basically garbage because of how far the camera is. We will use seeding
// below to connect the two sides
@@ -446,14 +450,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));
}
mapper.PrintDiffs();
}
@@ -463,9 +468,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/y2024_swerve/vision/viewer.cc b/y2024_swerve/vision/viewer.cc
index 143868d..d857cb6 100644
--- a/y2024_swerve/vision/viewer.cc
+++ b/y2024_swerve/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"
@@ -12,12 +13,13 @@
#include "frc971/vision/vision_util_lib.h"
#include "y2024_swerve/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 y2024_swerve::vision {
namespace {
@@ -42,12 +44,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;
@@ -55,9 +57,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);
@@ -77,7 +79,7 @@
void ViewerMain() {
aos::FlatbufferDetachedBuffer<aos::Configuration> config =
- aos::configuration::ReadConfig(FLAGS_config);
+ aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
frc971::constants::WaitForConstants<y2024_swerve::Constants>(
&config.message());
@@ -86,8 +88,8 @@
frc971::constants::ConstantsFetcher<y2024_swerve::Constants>
constants_fetcher(&event_loop);
- CHECK(FLAGS_channel.length() == 8);
- int camera_id = std::stoi(FLAGS_channel.substr(7, 1));
+ CHECK(absl::GetFlag(FLAGS_channel).length() == 8);
+ int camera_id = std::stoi(absl::GetFlag(FLAGS_channel).substr(7, 1));
const auto *calibration_data = FindCameraCalibration(
constants_fetcher.constants(), event_loop.node()->name()->string_view(),
camera_id);
@@ -96,7 +98,7 @@
frc971::vision::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(
@@ -106,7 +108,7 @@
event_loop.Exit();
};
},
- ::std::chrono::milliseconds(FLAGS_rate));
+ ::std::chrono::milliseconds(absl::GetFlag(FLAGS_rate)));
event_loop.Run();
diff --git a/y2024_swerve/vision/vision_util.cc b/y2024_swerve/vision/vision_util.cc
index e08bfaa..60ba82a 100644
--- a/y2024_swerve/vision/vision_util.cc
+++ b/y2024_swerve/vision/vision_util.cc
@@ -1,6 +1,7 @@
#include "y2024_swerve/vision/vision_util.h"
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
namespace y2024_swerve::vision {
diff --git a/y2024_swerve/wpilib_interface.cc b/y2024_swerve/wpilib_interface.cc
index 579f075..e6863b9 100644
--- a/y2024_swerve/wpilib_interface.cc
+++ b/y2024_swerve/wpilib_interface.cc
@@ -1,3 +1,4 @@
+#include "absl/flags/flag.h"
#include "ctre/phoenix/cci/Diagnostics_CCI.h"
#include "ctre/phoenix6/TalonFX.hpp"
@@ -13,9 +14,9 @@
#include "frc971/wpilib/wpilib_robot_base.h"
#include "y2024_swerve/constants.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 frc971::wpilib::CANSensorReader;
using frc971::wpilib::TalonFX;
@@ -188,7 +189,7 @@
// Thread 2
// Setup CAN
- if (!FLAGS_ctre_diag_server) {
+ if (!absl::GetFlag(FLAGS_ctre_diag_server)) {
c_Phoenix_Diagnostics_SetSecondsToStart(-1);
c_Phoenix_Diagnostics_Dispose();
}