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