Move over to ABSL logging and flags.
Removes gperftools too since that wants gflags.
Here come the fireworks.
Change-Id: I79cb7bcf60f1047fbfa28bfffc21a0fd692e4b1c
Signed-off-by: Austin Schuh <austin.linux@gmail.com>
diff --git a/frc971/orin/BUILD b/frc971/orin/BUILD
index 250ebef..a95bd84 100644
--- a/frc971/orin/BUILD
+++ b/frc971/orin/BUILD
@@ -52,8 +52,10 @@
"//aos/time",
"//third_party:cudart",
"//third_party/apriltag",
- "@com_github_google_glog//:glog",
"@com_github_nvidia_cccl//:cccl",
+ "@com_google_absl//absl/flags:flag",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
)
@@ -210,7 +212,8 @@
"//aos/events/logging:log_writer",
"//aos/events/logging:snappy_encoder",
"//aos/logging:log_namer",
- "@com_github_gflags_gflags//:gflags",
- "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/flags:flag",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
],
)
diff --git a/frc971/orin/apriltag.cc b/frc971/orin/apriltag.cc
index 92513c2..3aa0c1b 100644
--- a/frc971/orin/apriltag.cc
+++ b/frc971/orin/apriltag.cc
@@ -14,7 +14,8 @@
#include <cub/iterator/transform_input_iterator.cuh>
#include <vector>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "third_party/apriltag/common/g2d.h"
#include "aos/time/time.h"
diff --git a/frc971/orin/apriltag_detect.cc b/frc971/orin/apriltag_detect.cc
index 26de7fa..9420ef0 100644
--- a/frc971/orin/apriltag_detect.cc
+++ b/frc971/orin/apriltag_detect.cc
@@ -12,14 +12,16 @@
#include <cub/iterator/transform_input_iterator.cuh>
#include <vector>
-#include "glog/logging.h"
+#include "absl/flags/flag.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/time/time.h"
#include "frc971/orin/apriltag.h"
#include "frc971/orin/labeling_allegretti_2019_BKE.h"
#include "frc971/orin/threshold.h"
-DEFINE_int32(debug_blob_index, 4096, "Blob to print out for");
+ABSL_FLAG(int32_t, debug_blob_index, 4096, "Blob to print out for");
constexpr int kUndistortIterationThreshold = 100;
constexpr double kUndistortConvergenceEpsilon = 1e-6;
@@ -101,7 +103,7 @@
quad_corners_host_.resize(0);
VLOG(1) << "Considering " << fit_quads_host_.size();
for (const FitQuad &quad : fit_quads_host_) {
- bool print = quad.blob_index == FLAGS_debug_blob_index;
+ bool print = quad.blob_index == absl::GetFlag(FLAGS_debug_blob_index);
if (!quad.valid) {
continue;
}
diff --git a/frc971/orin/argus_camera.cc b/frc971/orin/argus_camera.cc
index c7825ae..e970754 100644
--- a/frc971/orin/argus_camera.cc
+++ b/frc971/orin/argus_camera.cc
@@ -4,7 +4,9 @@
#include <filesystem>
#include <thread>
-#include "glog/logging.h"
+#include "absl/flags/flag.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "Argus/Argus.h"
#include "Argus/EGLStream.h"
@@ -25,21 +27,22 @@
#include "frc971/vision/vision_generated.h"
#include "nvbufsurface.h"
-DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
+ABSL_FLAG(std::string, config, "aos_config.json",
+ "Path to the config file to use.");
-DEFINE_int32(colorformat, NVBUF_COLOR_FORMAT_NV16,
- "Mode to use. Don't change unless you know what you are doing.");
-DEFINE_int32(camera, 0, "Camera number");
-DEFINE_int32(mode, 0, "Mode number to use.");
-DEFINE_int32(exposure, 100, "Exposure number to use.");
-DEFINE_int32(gain, 5, "gain number to use.");
-DEFINE_int32(width, 1456, "Image width");
-DEFINE_int32(height, 1088, "Image height");
-DEFINE_double(rgain, 1.0, "R gain");
-DEFINE_double(g1gain, 1.0, "G gain");
-DEFINE_double(g2gain, 1.0, "G gain");
-DEFINE_double(bgain, 1.0, "B gain");
-DEFINE_string(channel, "/camera", "Channel name for the image.");
+ABSL_FLAG(int32_t, colorformat, NVBUF_COLOR_FORMAT_NV16,
+ "Mode to use. Don't change unless you know what you are doing.");
+ABSL_FLAG(int32_t, camera, 0, "Camera number");
+ABSL_FLAG(int32_t, mode, 0, "Mode number to use.");
+ABSL_FLAG(int32_t, exposure, 100, "Exposure number to use.");
+ABSL_FLAG(int32_t, gain, 5, "gain number to use.");
+ABSL_FLAG(int32_t, width, 1456, "Image width");
+ABSL_FLAG(int32_t, height, 1088, "Image height");
+ABSL_FLAG(double, rgain, 1.0, "R gain");
+ABSL_FLAG(double, g1gain, 1.0, "G gain");
+ABSL_FLAG(double, g2gain, 1.0, "G gain");
+ABSL_FLAG(double, bgain, 1.0, "B gain");
+ABSL_FLAG(std::string, channel, "/camera", "Channel name for the image.");
namespace frc971 {
@@ -221,7 +224,8 @@
CHECK_GT(sensor_modes.size(), 0u);
Argus::ISensorMode *i_sensor_mode =
- Argus::interface_cast<Argus::ISensorMode>(sensor_modes[FLAGS_mode]);
+ Argus::interface_cast<Argus::ISensorMode>(
+ sensor_modes[absl::GetFlag(FLAGS_mode)]);
CHECK(i_sensor_mode);
{
@@ -264,10 +268,11 @@
// Build the DmaBuffers
for (size_t i = 0; i < native_buffers_.size(); ++i) {
- native_buffers_[i] = DmaBuffer::Create(
- i_sensor_mode->getResolution(),
- static_cast<NvBufSurfaceColorFormat>(FLAGS_colorformat),
- NVBUF_LAYOUT_PITCH);
+ native_buffers_[i] =
+ DmaBuffer::Create(i_sensor_mode->getResolution(),
+ static_cast<NvBufSurfaceColorFormat>(
+ absl::GetFlag(FLAGS_colorformat)),
+ NVBUF_LAYOUT_PITCH);
}
// Create EGLImages from the native buffers
@@ -350,18 +355,19 @@
i_source_settings->setFrameDurationRange(
i_sensor_mode->getFrameDurationRange().min());
- CHECK_EQ(i_source_settings->setSensorMode(sensor_modes[FLAGS_mode]),
+ CHECK_EQ(i_source_settings->setSensorMode(
+ sensor_modes[absl::GetFlag(FLAGS_mode)]),
Argus::STATUS_OK);
Argus::Range<float> sensor_mode_analog_gain_range;
- sensor_mode_analog_gain_range.min() = FLAGS_gain;
- sensor_mode_analog_gain_range.max() = FLAGS_gain;
+ sensor_mode_analog_gain_range.min() = absl::GetFlag(FLAGS_gain);
+ sensor_mode_analog_gain_range.max() = absl::GetFlag(FLAGS_gain);
CHECK_EQ(i_source_settings->setGainRange(sensor_mode_analog_gain_range),
Argus::STATUS_OK);
Argus::Range<uint64_t> limit_exposure_time_range;
- limit_exposure_time_range.min() = FLAGS_exposure * 1000;
- limit_exposure_time_range.max() = FLAGS_exposure * 1000;
+ limit_exposure_time_range.min() = absl::GetFlag(FLAGS_exposure) * 1000;
+ limit_exposure_time_range.max() = absl::GetFlag(FLAGS_exposure) * 1000;
CHECK_EQ(i_source_settings->setExposureTimeRange(limit_exposure_time_range),
Argus::STATUS_OK);
@@ -412,9 +418,9 @@
<< nvbuf_surf_->surfaceList->planeParams.bytesPerPix[i];
}
CHECK_EQ(nvbuf_surf_->surfaceList->planeParams.width[0],
- static_cast<size_t>(FLAGS_width));
+ static_cast<size_t>(absl::GetFlag(FLAGS_width)));
CHECK_EQ(nvbuf_surf_->surfaceList->planeParams.height[0],
- static_cast<size_t>(FLAGS_height));
+ static_cast<size_t>(absl::GetFlag(FLAGS_height)));
}
MappedBuffer(const MappedBuffer &other) = delete;
MappedBuffer &operator=(const MappedBuffer &other) = delete;
@@ -524,10 +530,11 @@
};
int Main() {
- std::this_thread::sleep_for(std::chrono::seconds(FLAGS_camera + 1));
+ std::this_thread::sleep_for(
+ std::chrono::seconds(absl::GetFlag(FLAGS_camera) + 1));
aos::FlatbufferDetachedBuffer<aos::Configuration> config =
- aos::configuration::ReadConfig(FLAGS_config);
+ aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
aos::ShmEventLoop event_loop(&config.message());
@@ -535,7 +542,8 @@
event_loop.SetRuntimeAffinity(aos::MakeCpusetFromCpus({2, 3, 4}));
aos::Sender<frc971::vision::CameraImage> sender =
- event_loop.MakeSender<frc971::vision::CameraImage>(FLAGS_channel);
+ event_loop.MakeSender<frc971::vision::CameraImage>(
+ absl::GetFlag(FLAGS_channel));
LOG(INFO) << "Started";
// Initialize the Argus camera provider.
@@ -565,7 +573,8 @@
}
{
- ArgusCamera camera(i_camera_provider, camera_devices[FLAGS_camera]);
+ ArgusCamera camera(i_camera_provider,
+ camera_devices[absl::GetFlag(FLAGS_camera)]);
aos::monotonic_clock::time_point last_time = aos::monotonic_clock::epoch();
@@ -586,18 +595,20 @@
sender.MakeBuilder();
uint8_t *data_pointer = nullptr;
- builder.fbb()->StartIndeterminateVector(FLAGS_width * FLAGS_height * 2,
- 1, 64, &data_pointer);
+ builder.fbb()->StartIndeterminateVector(
+ absl::GetFlag(FLAGS_width) * absl::GetFlag(FLAGS_height) * 2, 1, 64,
+ &data_pointer);
YCbCr422(buffer.nvbuf_surf(), data_pointer);
flatbuffers::Offset<flatbuffers::Vector<uint8_t>> data_offset =
builder.fbb()->EndIndeterminateVector(
- FLAGS_width * FLAGS_height * 2, 1);
+ absl::GetFlag(FLAGS_width) * absl::GetFlag(FLAGS_height) * 2,
+ 1);
auto image_builder = builder.MakeBuilder<frc971::vision::CameraImage>();
image_builder.add_data(data_offset);
- image_builder.add_rows(FLAGS_height);
- image_builder.add_cols(FLAGS_width);
+ image_builder.add_rows(absl::GetFlag(FLAGS_height));
+ image_builder.add_cols(absl::GetFlag(FLAGS_width));
{
aos::ScopedNotRealtime nrt;
image_builder.add_monotonic_timestamp_ns(
diff --git a/frc971/orin/argus_monitor.cc b/frc971/orin/argus_monitor.cc
index 13130cc..c145c87 100644
--- a/frc971/orin/argus_monitor.cc
+++ b/frc971/orin/argus_monitor.cc
@@ -2,7 +2,7 @@
#include <iostream>
-#include "gflags/gflags.h"
+#include "absl/flags/flag.h"
#include "aos/aos_cli_utils.h"
#include "aos/configuration.h"
@@ -10,13 +10,13 @@
#include "aos/json_to_flatbuffer.h"
#include "aos/realtime.h"
-DEFINE_int32(priority, -1, "If set, the RT priority to run at.");
-DEFINE_double(max_jitter, 10.00,
- "The max time in seconds between messages before considering the "
- "camera processes dead.");
-DEFINE_double(grace_period, 10.00,
- "The grace period at startup before enforcing that messages must "
- "flow from the camera processes.");
+ABSL_FLAG(int32_t, priority, -1, "If set, the RT priority to run at.");
+ABSL_FLAG(double, max_jitter, 10.00,
+ "The max time in seconds between messages before considering the "
+ "camera processes dead.");
+ABSL_FLAG(double, grace_period, 10.00,
+ "The grace period at startup before enforcing that messages must "
+ "flow from the camera processes.");
namespace aos {
@@ -38,7 +38,8 @@
timer_handle_->Schedule(
event_loop->monotonic_now() +
std::chrono::duration_cast<std::chrono::nanoseconds>(
- std::chrono::duration<double>(FLAGS_grace_period)),
+ std::chrono::duration<double>(
+ absl::GetFlag(FLAGS_grace_period))),
std::chrono::milliseconds(1000));
});
}
@@ -52,12 +53,13 @@
void RunHealthCheck(aos::EventLoop *event_loop) {
if (last_time_ + std::chrono::duration_cast<std::chrono::nanoseconds>(
- std::chrono::duration<double>(FLAGS_max_jitter)) <
+ std::chrono::duration<double>(
+ absl::GetFlag(FLAGS_max_jitter))) <
event_loop->monotonic_now()) {
// Restart camera services
LOG(INFO) << "Restarting camera services";
LOG(INFO) << "Channel " << channel_name_ << " has not received a message "
- << FLAGS_max_jitter << " seconds";
+ << absl::GetFlag(FLAGS_max_jitter) << " seconds";
CHECK_EQ(std::system("aos_starter stop argus_camera0"), 0);
CHECK_EQ(std::system("aos_starter stop argus_camera1"), 0);
CHECK_EQ(std::system("sudo systemctl restart nvargus-daemon.service"), 0);
@@ -102,8 +104,9 @@
std::make_unique<aos::State>(&(cli_info.event_loop.value()), channel));
}
- if (FLAGS_priority > 0) {
- cli_info.event_loop->SetRuntimeRealtimePriority(FLAGS_priority);
+ if (absl::GetFlag(FLAGS_priority) > 0) {
+ cli_info.event_loop->SetRuntimeRealtimePriority(
+ absl::GetFlag(FLAGS_priority));
}
cli_info.event_loop->Run();
diff --git a/frc971/orin/cuda.cc b/frc971/orin/cuda.cc
index 6bcc79c..cd68a6c 100644
--- a/frc971/orin/cuda.cc
+++ b/frc971/orin/cuda.cc
@@ -1,10 +1,10 @@
#include "frc971/orin/cuda.h"
-#include "gflags/gflags.h"
-#include "glog/logging.h"
+#include "absl/flags/flag.h"
+#include "absl/log/check.h"
-DEFINE_bool(
- sync, false,
+ABSL_FLAG(
+ bool, sync, false,
"If true, force synchronization after each step to isolate errors better.");
namespace frc971::apriltag {
@@ -17,11 +17,11 @@
}
void MaybeCheckAndSynchronize() {
- if (FLAGS_sync) CheckAndSynchronize();
+ if (absl::GetFlag(FLAGS_sync)) CheckAndSynchronize();
}
void MaybeCheckAndSynchronize(std::string_view message) {
- if (FLAGS_sync) CheckAndSynchronize(message);
+ if (absl::GetFlag(FLAGS_sync)) CheckAndSynchronize(message);
}
} // namespace frc971::apriltag
diff --git a/frc971/orin/cuda.h b/frc971/orin/cuda.h
index 0e44fb4..293fc84 100644
--- a/frc971/orin/cuda.h
+++ b/frc971/orin/cuda.h
@@ -4,7 +4,8 @@
#include <chrono>
#include <span>
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "cuda_runtime.h"
#include "device_launch_parameters.h"
diff --git a/frc971/orin/cuda_april_tag_test.cc b/frc971/orin/cuda_april_tag_test.cc
index 638bf6a..c3cd160 100644
--- a/frc971/orin/cuda_april_tag_test.cc
+++ b/frc971/orin/cuda_april_tag_test.cc
@@ -2,7 +2,10 @@
#include <random>
#include <string>
-#include "glog/logging.h"
+#include "absl/flags/declare.h"
+#include "absl/flags/flag.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "gtest/gtest.h"
#include "opencv2/imgproc.hpp"
#include "third_party/apriltag/apriltag.h"
@@ -20,14 +23,14 @@
#include "frc971/orin/apriltag.h"
#include "frc971/vision/vision_generated.h"
-DEFINE_int32(pixel_border, 10,
- "Size of image border within which to reject detected corners");
-DEFINE_double(min_decision_margin, 50.0,
- "Minimum decision margin (confidence) for an apriltag detection");
+ABSL_FLAG(int32_t, pixel_border, 10,
+ "Size of image border within which to reject detected corners");
+ABSL_FLAG(double, min_decision_margin, 50.0,
+ "Minimum decision margin (confidence) for an apriltag detection");
-DEFINE_bool(debug, false, "If true, write debug images.");
+ABSL_FLAG(bool, debug, false, "If true, write debug images.");
-DECLARE_int32(debug_blob_index);
+ABSL_DECLARE_FLAG(int32_t, debug_blob_index);
// Get access to the intermediates of aprilrobotics.
extern "C" {
@@ -240,7 +243,7 @@
tag_detector->nthreads = 6;
tag_detector->wp = workerpool_create(tag_detector->nthreads);
tag_detector->qtp.min_white_black_diff = 5;
- tag_detector->debug = FLAGS_debug;
+ tag_detector->debug = absl::GetFlag(FLAGS_debug);
return tag_detector;
}
@@ -386,7 +389,7 @@
apriltag_detection_t *det;
zarray_get(aprilrobotics_detections_, i, &det);
- if (det->decision_margin > FLAGS_min_decision_margin) {
+ if (det->decision_margin > absl::GetFlag(FLAGS_min_decision_margin)) {
LOG(INFO) << "Found tag number " << det->id
<< " hamming: " << det->hamming
<< " margin: " << det->decision_margin;
@@ -1313,7 +1316,8 @@
VLOG(1) << "Inspecting blob of size " << group.size() << " global start "
<< accumulated_size;
for (size_t i = 0; i < group.size(); i++) {
- if (group[i].blob_index() == (size_t)FLAGS_debug_blob_index) {
+ if (group[i].blob_index() ==
+ (size_t)absl::GetFlag(FLAGS_debug_blob_index)) {
LOG(INFO) << "For idx " << i << " global " << accumulated_size + i
<< "(" << group[i].x() << ", " << group[i].y()
<< "), cuda: " << line_fit_points_cuda[accumulated_size + i]
@@ -1339,7 +1343,8 @@
}
for (size_t i = 0; i < group.size(); i++) {
- if (group[i].blob_index() == (size_t)FLAGS_debug_blob_index) {
+ if (group[i].blob_index() ==
+ (size_t)absl::GetFlag(FLAGS_debug_blob_index)) {
LOG(INFO) << " Cuda error[" << i << "] -> "
<< errors_device[accumulated_size + i] << ", filtered "
<< filtered_errors_device[i + accumulated_size];
@@ -1508,8 +1513,10 @@
<< before_cuda << " vs " << us_cuda << " vs " << after_cuda;
CHECK_EQ(peaks_device[accumulated_size + i].filtered_point_index,
accumulated_size + i);
- CHECK_NEAR(peaks_device[accumulated_size + i].error,
- -filtered_errors_device[accumulated_size + i], 1e-3);
+ CHECK_LE(peaks_device[accumulated_size + i].error,
+ -filtered_errors_device[accumulated_size + i] + 1e-3);
+ CHECK_GE(peaks_device[accumulated_size + i].error,
+ -filtered_errors_device[accumulated_size + i] - 1e-3);
if (is_peak_cuda) {
CHECK_EQ(peaks_device[accumulated_size + i].blob_index,
group[0].blob_index())
@@ -1683,7 +1690,7 @@
zarray_t *cluster;
zarray_get(clusters, i, &cluster);
- if (i == FLAGS_debug_blob_index) {
+ if (i == absl::GetFlag(FLAGS_debug_blob_index)) {
LOG(INFO) << "cuda points for blob " << i << " are";
for (size_t j = 0; j < sorted_blobs[i].size(); ++j) {
LOG(INFO) << " blob[" << j << "]: (" << sorted_blobs[i][j].x()
@@ -1715,10 +1722,15 @@
QuadCorners cuda_corner = *quad_iterator;
for (size_t point = 0; point < 4; ++point) {
- CHECK_NEAR(quad_result.p[point][0], cuda_corner.corners[point][0],
- 1e-3);
- CHECK_NEAR(quad_result.p[point][1], cuda_corner.corners[point][1],
- 1e-3);
+ constexpr double kEpsilon = 1e-3;
+ CHECK_LE(quad_result.p[point][0],
+ cuda_corner.corners[point][0] + kEpsilon);
+ CHECK_GE(quad_result.p[point][0],
+ cuda_corner.corners[point][0] - kEpsilon);
+ CHECK_LE(quad_result.p[point][1],
+ cuda_corner.corners[point][1] + kEpsilon);
+ CHECK_GE(quad_result.p[point][1],
+ cuda_corner.corners[point][1] - kEpsilon);
}
}
}
@@ -1755,7 +1767,8 @@
zarray_get(aprilrobotics_detections, i, &aprilrobotics_detection);
zarray_get(gpu_detections, i, &gpu_detection);
- bool valid = gpu_detection->decision_margin > FLAGS_min_decision_margin;
+ bool valid = gpu_detection->decision_margin >
+ absl::GetFlag(FLAGS_min_decision_margin);
LOG(INFO) << "Found GPU " << (valid ? "valid" : "invalid")
<< " tag number " << gpu_detection->id
@@ -1774,8 +1787,8 @@
zarray_get(aprilrobotics_detections, i, &aprilrobotics_detection);
zarray_get(gpu_detections, i, &gpu_detection);
- const bool valid =
- gpu_detection->decision_margin > FLAGS_min_decision_margin;
+ const bool valid = gpu_detection->decision_margin >
+ absl::GetFlag(FLAGS_min_decision_margin);
// TODO(austin): Crank down the thresholds and figure out why these
// deviate. It should be the same function for both at this point.
@@ -2151,7 +2164,7 @@
cuda_detector.DetectCPU(color_image.clone());
}
cuda_detector.Check(color_image.clone());
- if (FLAGS_debug) {
+ if (absl::GetFlag(FLAGS_debug)) {
cuda_detector.WriteDebug(color_image);
}
}
@@ -2175,7 +2188,7 @@
cuda_detector.DetectGPU(color_image.clone());
cuda_detector.DetectCPU(color_image.clone());
cuda_detector.Check(color_image.clone());
- if (FLAGS_debug) {
+ if (absl::GetFlag(FLAGS_debug)) {
cuda_detector.WriteDebug(color_image);
}
}
@@ -2289,7 +2302,7 @@
cuda_detector.DetectGPU(color_image.clone());
cuda_detector.DetectCPU(color_image.clone());
cuda_detector.Check(color_image.clone());
- if (FLAGS_debug) {
+ if (absl::GetFlag(FLAGS_debug)) {
cuda_detector.WriteDebug(color_image);
}
}
@@ -2314,7 +2327,7 @@
cuda_detector.DetectGPU(color_image.clone());
cuda_detector.DetectCPU(color_image.clone());
cuda_detector.Check(color_image.clone());
- if (FLAGS_debug) {
+ if (absl::GetFlag(FLAGS_debug)) {
cuda_detector.WriteDebug(color_image);
}
}
diff --git a/frc971/orin/gpu_apriltag.cc b/frc971/orin/gpu_apriltag.cc
index 425e45f..83ae3ee 100644
--- a/frc971/orin/gpu_apriltag.cc
+++ b/frc971/orin/gpu_apriltag.cc
@@ -2,6 +2,7 @@
#include <chrono>
+#include "absl/flags/flag.h"
#include "third_party/apriltag/apriltag.h"
#include "third_party/apriltag/apriltag_pose.h"
#include "third_party/apriltag/tag16h5.h"
@@ -18,18 +19,18 @@
#include "frc971/vision/charuco_lib.h"
#include "frc971/vision/vision_util_lib.h"
-DEFINE_bool(debug, false, "If true, write debug images.");
-DEFINE_double(
- max_expected_distortion, 0.314,
+ABSL_FLAG(bool, debug, false, "If true, write debug images.");
+ABSL_FLAG(
+ double, max_expected_distortion, 0.314,
"Maximum expected value for unscaled distortion factors. Will scale "
"distortion factors so that this value (and a higher distortion) maps to "
"1.0.");
-DEFINE_double(min_decision_margin, 50.0,
- "Minimum decision margin (confidence) for an apriltag detection");
-DEFINE_int32(pixel_border, 150,
- "Size of image border within which to reject detected corners");
-DEFINE_uint64(pose_estimation_iterations, 50,
- "Number of iterations for apriltag pose estimation.");
+ABSL_FLAG(double, min_decision_margin, 50.0,
+ "Minimum decision margin (confidence) for an apriltag detection");
+ABSL_FLAG(int32_t, pixel_border, 150,
+ "Size of image border within which to reject detected corners");
+ABSL_FLAG(uint64_t, pose_estimation_iterations, 50,
+ "Number of iterations for apriltag pose estimation.");
namespace frc971::apriltag {
@@ -111,7 +112,7 @@
tag_detector->nthreads = 6;
tag_detector->wp = workerpool_create(tag_detector->nthreads);
tag_detector->qtp.min_white_black_diff = 5;
- tag_detector->debug = FLAGS_debug;
+ tag_detector->debug = absl::GetFlag(FLAGS_debug);
return tag_detector;
}
@@ -169,7 +170,8 @@
double distortion_factor =
avg_distance /
cv::norm(cv::Point2d(image_size_.width, image_size_.height));
- return std::min(distortion_factor / FLAGS_max_expected_distortion, 1.0);
+ return std::min(
+ distortion_factor / absl::GetFlag(FLAGS_max_expected_distortion), 1.0);
}
std::vector<cv::Point2f> ApriltagDetector::MakeCornerVector(
@@ -195,7 +197,7 @@
gpu_detector_.Detect(color_image.data);
image_size_ = color_image.size();
cv::Mat image_copy;
- if (FLAGS_visualize) {
+ if (absl::GetFlag(FLAGS_visualize)) {
// TODO: Need to figure out how to extract displayable color image from this
image_copy = color_image.clone();
}
@@ -204,10 +206,10 @@
aos::monotonic_clock::time_point end_time = aos::monotonic_clock::now();
- const uint32_t min_x = FLAGS_pixel_border;
- const uint32_t max_x = color_image.cols - FLAGS_pixel_border;
- const uint32_t min_y = FLAGS_pixel_border;
- const uint32_t max_y = color_image.rows - FLAGS_pixel_border;
+ const uint32_t min_x = absl::GetFlag(FLAGS_pixel_border);
+ const uint32_t max_x = color_image.cols - absl::GetFlag(FLAGS_pixel_border);
+ const uint32_t min_y = absl::GetFlag(FLAGS_pixel_border);
+ const uint32_t max_y = color_image.rows - absl::GetFlag(FLAGS_pixel_border);
// Define variables for storing / visualizing the output
std::vector<Detection> results;
@@ -219,7 +221,8 @@
zarray_get(detections, i, &gpu_detection);
- bool valid = gpu_detection->decision_margin > FLAGS_min_decision_margin;
+ bool valid = gpu_detection->decision_margin >
+ absl::GetFlag(FLAGS_min_decision_margin);
if (valid) {
// Reject tags that are too close to the boundary, since they often
@@ -303,9 +306,9 @@
apriltag_pose_t pose_2;
double pose_error_1;
double pose_error_2;
- estimate_tag_pose_orthogonal_iteration(&info, &pose_error_1, &pose_1,
- &pose_error_2, &pose_2,
- FLAGS_pose_estimation_iterations);
+ estimate_tag_pose_orthogonal_iteration(
+ &info, &pose_error_1, &pose_1, &pose_error_2, &pose_2,
+ absl::GetFlag(FLAGS_pose_estimation_iterations));
const aos::monotonic_clock::time_point after_pose_estimation =
aos::monotonic_clock::now();
@@ -351,7 +354,7 @@
.distortion_factor = distortion_factor,
.pose_error_ratio = pose_error_ratio});
- if (FLAGS_visualize) {
+ if (absl::GetFlag(FLAGS_visualize)) {
// Draw raw (distorted) corner points in green
cv::line(image_copy, orig_corner_points[0], orig_corner_points[1],
cv::Scalar(0, 255, 0), 2);
@@ -381,7 +384,7 @@
}
}
- if (FLAGS_visualize) {
+ if (absl::GetFlag(FLAGS_visualize)) {
// Display the result
// Rotate by 180 degrees to make it upright
// TODO: Make this an option?
@@ -422,7 +425,7 @@
end_time = aos::monotonic_clock::now();
- if (FLAGS_debug) {
+ if (absl::GetFlag(FLAGS_debug)) {
timeprofile_display(tag_detector_->tp);
}
diff --git a/frc971/orin/hardware_monitor.cc b/frc971/orin/hardware_monitor.cc
index e1c785b..cc019fd 100644
--- a/frc971/orin/hardware_monitor.cc
+++ b/frc971/orin/hardware_monitor.cc
@@ -1,16 +1,17 @@
#include <dirent.h>
#include <sys/statvfs.h>
+#include "absl/flags/flag.h"
#include "absl/strings/numbers.h"
#include "absl/strings/str_format.h"
-#include "gflags/gflags.h"
#include "aos/events/shm_event_loop.h"
#include "aos/init.h"
#include "frc971/orin/hardware_stats_generated.h"
-DEFINE_string(config, "aos_config.json", "File path of aos configuration");
-DEFINE_bool(log_voltages, false, "If true, log voltages too.");
+ABSL_FLAG(std::string, config, "aos_config.json",
+ "File path of aos configuration");
+ABSL_FLAG(bool, log_voltages, false, "If true, log voltages too.");
namespace frc971::orin {
namespace {
@@ -102,7 +103,7 @@
flatbuffers::Offset<
flatbuffers::Vector<flatbuffers::Offset<ElectricalReading>>>
electrical_readings_offset;
- if (FLAGS_log_voltages) {
+ if (absl::GetFlag(FLAGS_log_voltages)) {
std::vector<flatbuffers::Offset<ElectricalReading>> electrical_readings;
// Iterate through INA3221 electrical reading channels
for (int channel = 1; channel <= 3; channel++) {
@@ -182,7 +183,7 @@
aos::InitGoogle(&argc, &argv);
aos::FlatbufferDetachedBuffer<aos::Configuration> config =
- aos::configuration::ReadConfig(FLAGS_config);
+ aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
aos::ShmEventLoop shm_event_loop(&config.message());
diff --git a/frc971/orin/labeling_allegretti_2019_BKE.cc b/frc971/orin/labeling_allegretti_2019_BKE.cc
index 2806199..0ec1664 100644
--- a/frc971/orin/labeling_allegretti_2019_BKE.cc
+++ b/frc971/orin/labeling_allegretti_2019_BKE.cc
@@ -19,7 +19,8 @@
#include "frc971/orin/labeling_allegretti_2019_BKE.h"
-#include "glog/logging.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "cuda_runtime.h"
#include "device_launch_parameters.h"
diff --git a/frc971/orin/localizer_logger.cc b/frc971/orin/localizer_logger.cc
index ec8d3ac..c571bd7 100644
--- a/frc971/orin/localizer_logger.cc
+++ b/frc971/orin/localizer_logger.cc
@@ -1,8 +1,10 @@
#include <sys/resource.h>
#include <sys/time.h>
-#include "gflags/gflags.h"
-#include "glog/logging.h"
+#include "absl/flags/flag.h"
+#include "absl/flags/usage.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
#include "aos/configuration.h"
#include "aos/events/logging/log_writer.h"
@@ -11,15 +13,15 @@
#include "aos/init.h"
#include "aos/logging/log_namer.h"
-DEFINE_string(config, "aos_config.json", "Config file to use.");
+ABSL_FLAG(std::string, config, "aos_config.json", "Config file to use.");
-DEFINE_double(rotate_every, 30.0,
- "If set, rotate the logger after this many seconds");
+ABSL_FLAG(double, rotate_every, 30.0,
+ "If set, rotate the logger after this many seconds");
-DECLARE_int32(flush_size);
+ABSL_DECLARE_FLAG(int32_t, flush_size);
int main(int argc, char *argv[]) {
- gflags::SetUsageMessage(
+ absl::SetProgramUsageMessage(
"This program provides a simple logger binary that logs all SHMEM data "
"directly to a file specified at the command line. It does not manage "
"filenames, so it will just crash if you attempt to overwrite an "
@@ -28,7 +30,7 @@
aos::InitGoogle(&argc, &argv);
aos::FlatbufferDetachedBuffer<aos::Configuration> config =
- aos::configuration::ReadConfig(FLAGS_config);
+ aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
aos::ShmEventLoop event_loop(&config.message());
@@ -40,8 +42,8 @@
log_namer->set_extension(aos::logger::SnappyDecoder::kExtension);
log_namer->set_encoder_factory([](size_t max_message_size) {
- return std::make_unique<aos::logger::SnappyEncoder>(max_message_size,
- FLAGS_flush_size);
+ return std::make_unique<aos::logger::SnappyEncoder>(
+ max_message_size, absl::GetFlag(FLAGS_flush_size));
});
aos::monotonic_clock::time_point last_rotation_time =
@@ -53,11 +55,11 @@
return (channel->max_size() * channel->frequency()) < 10e6;
});
- if (FLAGS_rotate_every != 0.0) {
+ if (absl::GetFlag(FLAGS_rotate_every) != 0.0) {
logger.set_on_logged_period(
[&logger, &last_rotation_time](aos::monotonic_clock::time_point t) {
- if (t > last_rotation_time +
- std::chrono::duration<double>(FLAGS_rotate_every)) {
+ if (t > last_rotation_time + std::chrono::duration<double>(
+ absl::GetFlag(FLAGS_rotate_every))) {
logger.Rotate();
last_rotation_time = t;
}