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/vision/modify_extrinsics.cc b/frc971/vision/modify_extrinsics.cc
index d021744..355f790 100644
--- a/frc971/vision/modify_extrinsics.cc
+++ b/frc971/vision/modify_extrinsics.cc
@@ -4,6 +4,7 @@
#include "Eigen/Dense"
#include "Eigen/Geometry"
+#include "absl/flags/flag.h"
#include "absl/strings/str_format.h"
#include "aos/configuration.h"
@@ -23,28 +24,30 @@
// By default, writes to /tmp, but will write to calib_files folder if
// full path is given and calibration_folder is blank
-DEFINE_string(orig_calib_file, "",
- "Intrinsics to use for estimating board pose prior to solving "
- "for the new intrinsics.");
-DEFINE_string(calibration_folder, "/tmp", "Folder to place calibration files.");
-DEFINE_string(node_name, "",
- "Node name to use, e.g. orin1, imu; unchanged if blank");
-DEFINE_int32(team_number, -1, "Team number to use; unchanged if -1");
-DEFINE_int32(camera_number, -1, "Camera number to use; unchanged if -1");
+ABSL_FLAG(std::string, orig_calib_file, "",
+ "Intrinsics to use for estimating board pose prior to solving "
+ "for the new intrinsics.");
+ABSL_FLAG(std::string, calibration_folder, "/tmp",
+ "Folder to place calibration files.");
+ABSL_FLAG(std::string, node_name, "",
+ "Node name to use, e.g. orin1, imu; unchanged if blank");
+ABSL_FLAG(int32_t, team_number, -1, "Team number to use; unchanged if -1");
+ABSL_FLAG(int32_t, camera_number, -1, "Camera number to use; unchanged if -1");
-DEFINE_bool(set_extrinsics, true, "Set to false to ignore extrinsic data");
-DEFINE_bool(use_inches, true,
- "Whether to use inches as units (meters if false)");
-DEFINE_bool(use_degrees, true,
- "Whether to use degrees as units (radians if false)");
-DEFINE_double(camera_x, 0.0, "x location of camera");
-DEFINE_double(camera_y, 0.0, "y location of camera");
-DEFINE_double(camera_z, 0.0, "z location of camera");
+ABSL_FLAG(bool, set_extrinsics, true, "Set to false to ignore extrinsic data");
+ABSL_FLAG(bool, use_inches, true,
+ "Whether to use inches as units (meters if false)");
+ABSL_FLAG(bool, use_degrees, true,
+ "Whether to use degrees as units (radians if false)");
+ABSL_FLAG(double, camera_x, 0.0, "x location of camera");
+ABSL_FLAG(double, camera_y, 0.0, "y location of camera");
+ABSL_FLAG(double, camera_z, 0.0, "z location of camera");
// Don't currently allow for roll of cameras
-DEFINE_double(camera_yaw, 0.0, "yaw of camera about robot z axis");
-DEFINE_double(camera_pitch, 0.0, "pitch of camera relative to robot y axis");
+ABSL_FLAG(double, camera_yaw, 0.0, "yaw of camera about robot z axis");
+ABSL_FLAG(double, camera_pitch, 0.0,
+ "pitch of camera relative to robot y axis");
// TODO: This could be done by setting the pixel size and using the intrinsics
-DEFINE_double(focal_length, 0.002, "Focal length in meters");
+ABSL_FLAG(double, focal_length, 0.002, "Focal length in meters");
namespace frc971::vision {
namespace {
@@ -74,30 +77,34 @@
// If we're told to set the extrinsics, clear old and add in new
flatbuffers::Offset<calibration::TransformationMatrix>
fixed_extrinsics_offset;
- if (FLAGS_set_extrinsics) {
+ if (absl::GetFlag(FLAGS_set_extrinsics)) {
cal_copy.mutable_message()->clear_fixed_extrinsics();
Eigen::Affine3d extrinsic_matrix;
// Convert to metric
- double translation_scale = (FLAGS_use_inches ? 0.0254 : 1.0);
- Eigen::Translation3d translation(FLAGS_camera_x * translation_scale,
- FLAGS_camera_y * translation_scale,
- FLAGS_camera_z * translation_scale);
+ double translation_scale = (absl::GetFlag(FLAGS_use_inches) ? 0.0254 : 1.0);
+ Eigen::Translation3d translation(
+ absl::GetFlag(FLAGS_camera_x) * translation_scale,
+ absl::GetFlag(FLAGS_camera_y) * translation_scale,
+ absl::GetFlag(FLAGS_camera_z) * translation_scale);
// convert to radians
- double angle_scale = (FLAGS_use_degrees ? M_PI / 180.0 : 1.0);
+ double angle_scale =
+ (absl::GetFlag(FLAGS_use_degrees) ? M_PI / 180.0 : 1.0);
// The rotation that takes robot coordinates (x forward, z up) to camera
// coordiantes (z forward, x right)
Eigen::Quaterniond R_robo_cam =
Eigen::AngleAxisd(-M_PI / 2.0, Eigen::Vector3d::UnitZ()) *
Eigen::AngleAxisd(-M_PI / 2.0, Eigen::Vector3d::UnitX());
- Eigen::AngleAxisd pitchAngle(FLAGS_camera_pitch * angle_scale,
- Eigen::Vector3d::UnitY());
- Eigen::AngleAxisd yawAngle(FLAGS_camera_yaw * angle_scale,
+ Eigen::AngleAxisd pitchAngle(
+ absl::GetFlag(FLAGS_camera_pitch) * angle_scale,
+ Eigen::Vector3d::UnitY());
+ Eigen::AngleAxisd yawAngle(absl::GetFlag(FLAGS_camera_yaw) * angle_scale,
Eigen::Vector3d::UnitZ());
Eigen::Quaterniond rotation = yawAngle * pitchAngle * R_robo_cam;
Eigen::Vector3d focal_length_offset =
- (rotation * Eigen::Translation3d(0.0, 0.0, FLAGS_focal_length))
+ (rotation *
+ Eigen::Translation3d(0.0, 0.0, absl::GetFlag(FLAGS_focal_length)))
.translation();
translation = translation * Eigen::Translation3d(focal_length_offset);
@@ -113,7 +120,7 @@
calibration::CameraCalibration::Builder camera_calibration_builder(fbb);
camera_calibration_builder.add_node_name(node_name_offset);
camera_calibration_builder.add_team_number(team_number);
- if (FLAGS_set_extrinsics) {
+ if (absl::GetFlag(FLAGS_set_extrinsics)) {
camera_calibration_builder.add_fixed_extrinsics(fixed_extrinsics_offset);
}
camera_calibration_builder.add_camera_number(camera_number);
@@ -136,15 +143,15 @@
orig_calib_filename);
// Populate the new variables from command-line or from base_calibration
- std::string node_name =
- (FLAGS_node_name == "" ? base_calibration.message().node_name()->str()
- : FLAGS_node_name);
- int team_number =
- (FLAGS_team_number == -1 ? base_calibration.message().team_number()
- : FLAGS_team_number);
- int camera_number =
- (FLAGS_camera_number == -1 ? base_calibration.message().camera_number()
- : FLAGS_camera_number);
+ std::string node_name = (absl::GetFlag(FLAGS_node_name) == ""
+ ? base_calibration.message().node_name()->str()
+ : absl::GetFlag(FLAGS_node_name));
+ int team_number = (absl::GetFlag(FLAGS_team_number) == -1
+ ? base_calibration.message().team_number()
+ : absl::GetFlag(FLAGS_team_number));
+ int camera_number = (absl::GetFlag(FLAGS_camera_number) == -1
+ ? base_calibration.message().camera_number()
+ : absl::GetFlag(FLAGS_camera_number));
aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
new_calibration = BuildCalibration(&base_calibration.message(), node_name,
camera_number, team_number);
@@ -158,9 +165,9 @@
std::string camera_id = base_calibration.message().camera_id()->str();
const std::string dirname =
- (FLAGS_calibration_folder == ""
+ (absl::GetFlag(FLAGS_calibration_folder) == ""
? std::filesystem::path(orig_calib_filename).parent_path().string()
- : FLAGS_calibration_folder);
+ : absl::GetFlag(FLAGS_calibration_folder));
const std::string new_calib_filename = frc971::vision::CalibrationFilename(
dirname, node_name.c_str(), team_number, camera_number, camera_id.c_str(),
time_ss.str());