From 5b853b4a922d5a182511b7b6f202230b056d390e Mon Sep 17 00:00:00 2001 From: Xiangquan Xiao Date: Fri, 31 Jul 2020 12:50:16 -0700 Subject: [PATCH] Revert "absl_flag: convert gflags to absl_flag" This reverts commit 6581599127f5b349b314b2499695c7307a34f2e2. --- modules/common/configs/BUILD | 1 - modules/common/configs/config_gflags.cc | 16 ++++++++-------- modules/common/configs/config_gflags.h | 11 ++++------- modules/dreamview/backend/hmi/hmi_worker.cc | 8 +++----- modules/dreamview/backend/map/map_service.cc | 2 +- modules/dreamview/backend/map/map_service.h | 2 +- .../dreamview/backend/map/map_service_test.cc | 4 ++-- .../backend/sim_control/sim_control_test.cc | 4 ++-- .../simulation_world_service_test.cc | 4 ++-- modules/dreamview/proto/hmi_status.proto | 2 +- modules/localization/msf/README.md | 2 +- .../online_visualizer_component.cc | 3 +-- modules/localization/msf/msf_localization.cc | 5 ++--- modules/localization/ndt/README.md | 2 +- modules/localization/ndt/ndt_localization.cc | 5 ++--- .../localization/ndt/ndt_localization_test.cc | 2 +- modules/map/hdmap/hdmap_util.cc | 18 +++++++----------- modules/map/hdmap/hdmap_util.h | 3 +-- modules/map/tools/bin_map_generator.cc | 2 +- modules/map/tools/proto_map_generator.cc | 3 +-- modules/perception/map/hdmap/hdmap_input.cc | 2 +- modules/planning/common/message_process.cc | 17 +++++++++-------- .../planning/integration_tests/garage_test.cc | 4 ++-- .../integration_tests/planning_test_base.cc | 2 +- .../sunnyvale_big_loop_test.cc | 4 ++-- .../integration_tests/sunnyvale_loop_test.cc | 4 ++-- .../birdview_img_feature_renderer.cc | 3 +-- .../model_inference/model_inference_test.cc | 5 ++--- .../pipeline/record_to_learning_data.cc | 2 +- modules/prediction/common/kml_map_based_test.h | 4 ++-- modules/v2x/v2x_proxy/app/v2x_proxy.cc | 15 +++++++-------- 31 files changed, 72 insertions(+), 89 deletions(-) diff --git a/modules/common/configs/BUILD b/modules/common/configs/BUILD index 8ae5f79e78..ecc3fdd106 100644 --- a/modules/common/configs/BUILD +++ b/modules/common/configs/BUILD @@ -12,7 +12,6 @@ cc_library( ], deps = [ "@com_github_gflags_gflags//:gflags", - "@com_google_absl//absl/flags:flag" ], ) diff --git a/modules/common/configs/config_gflags.cc b/modules/common/configs/config_gflags.cc index 07caa79753..72e63ee897 100644 --- a/modules/common/configs/config_gflags.cc +++ b/modules/common/configs/config_gflags.cc @@ -16,15 +16,15 @@ #include "modules/common/configs/config_gflags.h" -ABSL_FLAG(std::string, map_dir, "/apollo/modules/map/data/demo", - "Directory which contains a group of related maps."); -ABSL_FLAG(int32_t, local_utm_zone_id, 10, "UTM zone id."); -ABSL_FLAG(std::string, test_base_map_filename, "", - "If not empty, use this test base map files."); -ABSL_FLAG(std::string, base_map_filename, - "base_map.bin|base_map.xml|base_map.txt", - "Base map files in the map_dir, search in order."); +DEFINE_string(map_dir, "/apollo/modules/map/data/demo", + "Directory which contains a group of related maps."); +DEFINE_int32(local_utm_zone_id, 10, "UTM zone id."); +DEFINE_string(test_base_map_filename, "", + "If not empty, use this test base map files."); + +DEFINE_string(base_map_filename, "base_map.bin|base_map.xml|base_map.txt", + "Base map files in the map_dir, search in order."); DEFINE_string(sim_map_filename, "sim_map.bin|sim_map.txt", "Simulation map files in the map_dir, search in order."); DEFINE_string(routing_map_filename, "routing_map.bin|routing_map.txt", diff --git a/modules/common/configs/config_gflags.h b/modules/common/configs/config_gflags.h index eb0bdb2ce1..7e539c5509 100644 --- a/modules/common/configs/config_gflags.h +++ b/modules/common/configs/config_gflags.h @@ -15,19 +15,16 @@ *****************************************************************************/ #pragma once -#include -#include "absl/flags/flag.h" #include "gflags/gflags.h" // The directory which contains a group of related maps, such as base_map, // sim_map, routing_topo_grapth, etc. +DECLARE_string(map_dir); +DECLARE_int32(local_utm_zone_id); -ABSL_DECLARE_FLAG(std::string, map_dir); -ABSL_DECLARE_FLAG(int32_t, local_utm_zone_id); -ABSL_DECLARE_FLAG(std::string, test_base_map_filename); -ABSL_DECLARE_FLAG(std::string, base_map_filename); - +DECLARE_string(test_base_map_filename); +DECLARE_string(base_map_filename); DECLARE_string(sim_map_filename); DECLARE_string(routing_map_filename); DECLARE_string(end_way_point_filename); diff --git a/modules/dreamview/backend/hmi/hmi_worker.cc b/modules/dreamview/backend/hmi/hmi_worker.cc index 6ba7b6dd67..8609481a7c 100644 --- a/modules/dreamview/backend/hmi/hmi_worker.cc +++ b/modules/dreamview/backend/hmi/hmi_worker.cc @@ -210,7 +210,7 @@ HMIMode HMIWorker::LoadMode(const std::string& mode_config_path) { void HMIWorker::InitStatus() { static const std::string kDockerImageEnv = "DOCKER_IMG"; status_.set_docker_image(cyber::common::GetEnv(kDockerImageEnv)); - status_.set_utm_zone_id(absl::GetFlag(FLAGS_local_utm_zone_id)); + status_.set_utm_zone_id(FLAGS_local_utm_zone_id); // Populate modes and current_mode. const auto& modes = config_.modes(); @@ -223,7 +223,7 @@ void HMIWorker::InitStatus() { status_.add_maps(map_entry.first); // If current FLAG_map_dir is available, set it as current_map. - if (map_entry.second == absl::GetFlag(FLAGS_map_dir)) { + if (map_entry.second == FLAGS_map_dir) { status_.set_current_map(map_entry.first); } } @@ -444,9 +444,7 @@ void HMIWorker::ChangeMap(const std::string& map_name) { status_changed_ = true; } - // SetGlobalFlag("map_dir", *map_dir, &FLAGS_map_dir); - absl::SetFlag(&FLAGS_map_dir, *map_dir); - + SetGlobalFlag("map_dir", *map_dir, &FLAGS_map_dir); ResetMode(); } diff --git a/modules/dreamview/backend/map/map_service.cc b/modules/dreamview/backend/map/map_service.cc index cd6254b15c..8ce9dc1b0b 100644 --- a/modules/dreamview/backend/map/map_service.cc +++ b/modules/dreamview/backend/map/map_service.cc @@ -102,7 +102,7 @@ bool MapService::ReloadMap(bool force_reload) { void MapService::UpdateOffsets() { x_offset_ = 0.0; y_offset_ = 0.0; - std::ifstream ifs(absl::StrCat(absl::GetFlag(FLAGS_map_dir), kMetaFileName)); + std::ifstream ifs(FLAGS_map_dir + kMetaFileName); if (!ifs.is_open()) { AINFO << "Failed to open map meta file: " << kMetaFileName; } else { diff --git a/modules/dreamview/backend/map/map_service.h b/modules/dreamview/backend/map/map_service.h index b29efa3c7d..87fc002ab0 100644 --- a/modules/dreamview/backend/map/map_service.h +++ b/modules/dreamview/backend/map/map_service.h @@ -79,7 +79,7 @@ class MapService { bool CheckRoutingPointLaneType(apollo::hdmap::LaneInfoConstPtr lane) const; - // Reload map from current absl::GetFlag(FLAGS_map_dir). + // Reload map from current FLAGS_map_dir. bool ReloadMap(bool force_reload); size_t CalculateMapHash(const MapElementIds &ids) const; diff --git a/modules/dreamview/backend/map/map_service_test.cc b/modules/dreamview/backend/map/map_service_test.cc index 6e93dfce67..8430c8fca9 100644 --- a/modules/dreamview/backend/map/map_service_test.cc +++ b/modules/dreamview/backend/map/map_service_test.cc @@ -30,8 +30,8 @@ namespace dreamview { class MapServiceTest : public ::testing::Test { protected: MapServiceTest() { - absl::SetFlag(&FLAGS_map_dir, "modules/dreamview/backend/testdata"); - absl::SetFlag(&FLAGS_base_map_filename, "garage.bin"); + FLAGS_map_dir = "modules/dreamview/backend/testdata"; + FLAGS_base_map_filename = "garage.bin"; map_service.reset(new MapService(false)); } diff --git a/modules/dreamview/backend/sim_control/sim_control_test.cc b/modules/dreamview/backend/sim_control/sim_control_test.cc index bc0bdf01ad..58d88ccc8c 100644 --- a/modules/dreamview/backend/sim_control/sim_control_test.cc +++ b/modules/dreamview/backend/sim_control/sim_control_test.cc @@ -44,8 +44,8 @@ class SimControlTest : public ::testing::Test { } virtual void SetUp() { - absl::GetFlag(FLAGS_map_dir) = "modules/dreamview/backend/testdata"; - absl::GetFlag(FLAGS_base_map_filename) = "garage.bin"; + FLAGS_map_dir = "modules/dreamview/backend/testdata"; + FLAGS_base_map_filename = "garage.bin"; map_service_.reset(new MapService(false)); sim_control_.reset(new SimControl(map_service_.get())); diff --git a/modules/dreamview/backend/simulation_world/simulation_world_service_test.cc b/modules/dreamview/backend/simulation_world/simulation_world_service_test.cc index d1e691fa9c..64c2f6beb1 100644 --- a/modules/dreamview/backend/simulation_world/simulation_world_service_test.cc +++ b/modules/dreamview/backend/simulation_world/simulation_world_service_test.cc @@ -62,8 +62,8 @@ class SimulationWorldServiceTest : public ::testing::Test { protected: SimulationWorldServiceTest() { - absl::SetFlag(&FLAGS_map_dir, "modules/dreamview/backend/testdata"); - absl::SetFlag(&FLAGS_base_map_filename, "garage.bin"); + FLAGS_map_dir = "modules/dreamview/backend/testdata"; + FLAGS_base_map_filename = "garage.bin"; FLAGS_sim_world_with_routing_path = true; map_service_.reset(new MapService(false)); } diff --git a/modules/dreamview/proto/hmi_status.proto b/modules/dreamview/proto/hmi_status.proto index a3e72b01fe..a00d36aef9 100644 --- a/modules/dreamview/proto/hmi_status.proto +++ b/modules/dreamview/proto/hmi_status.proto @@ -23,7 +23,7 @@ message HMIStatus { map monitored_components = 9; optional string docker_image = 10; - optional int32 utm_zone_id = 11; // absl::GetFlag(FLAGS_local_utm_zone_id) + optional int32 utm_zone_id = 11; // FLAGS_local_utm_zone_id // Message which will be read aloud to drivers and passengers through // Dreamview. diff --git a/modules/localization/msf/README.md b/modules/localization/msf/README.md index 134e3e9099..dac4287223 100644 --- a/modules/localization/msf/README.md +++ b/modules/localization/msf/README.md @@ -13,7 +13,7 @@ * GNSS observation and ephemeris data from GNSS sensor (ROS topic `/apollo/sensor/gnss/rtk_obs` and `/apollo/sensor/gnss/rtk_eph`) * GNSS best pose from GNSS sensor (ROS topic is `/apollo/sensor/gnss/best_pose`) * Imu data from IMU sensor (ROS topic `/apollo/sensor/gnss/imu`) - * Localization map absl::StrCat(absl::GetFlag(FLAGS_map_dir), "/", FLAGS_local_map_name) + * Localization map (FLAGS_map_dir + "/" + FLAGS_local_map_name) * Parameter config files (velodyne64_novatel_extrinsics_example.yaml, velodyne64_height.yaml, and ant_imu_leverarm.yaml, located in `modules/localization/msf/params/`) ## Output diff --git a/modules/localization/msf/local_tool/local_visualization/online_visual/online_visualizer_component.cc b/modules/localization/msf/local_tool/local_visualization/online_visual/online_visualizer_component.cc index 39146bdd93..4e614440d1 100644 --- a/modules/localization/msf/local_tool/local_visualization/online_visual/online_visualizer_component.cc +++ b/modules/localization/msf/local_tool/local_visualization/online_visual/online_visualizer_component.cc @@ -51,8 +51,7 @@ bool OnlineVisualizerComponent::Init() { } bool OnlineVisualizerComponent::InitConfig() { - map_folder_ = - absl::StrCat(absl::GetFlag(FLAGS_map_dir), "/", FLAGS_local_map_name); + map_folder_ = FLAGS_map_dir + "/" + FLAGS_local_map_name; map_visual_folder_ = FLAGS_map_visual_dir; lidar_extrinsic_file_ = FLAGS_lidar_extrinsics_file; diff --git a/modules/localization/msf/msf_localization.cc b/modules/localization/msf/msf_localization.cc index 8b87dd35ec..864a3e58e5 100644 --- a/modules/localization/msf/msf_localization.cc +++ b/modules/localization/msf/msf_localization.cc @@ -61,8 +61,7 @@ void MSFLocalization::InitParams() { localization_param_.enable_ins_aid_rtk = FLAGS_enable_ins_aid_rtk; // lidar module - localization_param_.map_path = - absl::StrCat(absl::GetFlag(FLAGS_map_dir), "/", FLAGS_local_map_name); + localization_param_.map_path = FLAGS_map_dir + "/" + FLAGS_local_map_name; localization_param_.lidar_extrinsic_file = FLAGS_lidar_extrinsics_file; localization_param_.lidar_height_file = FLAGS_lidar_height_file; localization_param_.lidar_height_default = FLAGS_lidar_height_default; @@ -77,7 +76,7 @@ void MSFLocalization::InitParams() { AINFO << "lidar_extrin: " << localization_param_.lidar_extrinsic_file; AINFO << "lidar_height: " << localization_param_.lidar_height_file; - localization_param_.utm_zone_id = absl::GetFlag(FLAGS_local_utm_zone_id); + localization_param_.utm_zone_id = FLAGS_local_utm_zone_id; // try load zone id from local_map folder if (FLAGS_if_utm_zone_id_from_folder) { bool success = LoadZoneIdFromFolder(localization_param_.map_path, diff --git a/modules/localization/ndt/README.md b/modules/localization/ndt/README.md index 769e92f6da..1b767e88aa 100644 --- a/modules/localization/ndt/README.md +++ b/modules/localization/ndt/README.md @@ -8,7 +8,7 @@ ## Input * Point cloud data from LiDAR sensor ( `/apollo/sensor/velodyne64/compensator/PointCloud2`) * Inspva message from integrated navigation sensor ( `/apollo/sensor/gnss/odometry`) - * Localization map absl::strcat(absl::GetFlag(FLAGS_map_dir), "/", FLAGS_ndt_map_dir, "/", FLAGS_local_map_name) + * Localization map (FLAGS_map_dir + "/" + FLAGS_ndt_map_dir + "/" + FLAGS_local_map_name) * Parameter config files (velodyne64_novatel_extrinsics_example.yaml, velodyne64_height.yaml, located in `modules/localization/msf/params/`) ## Output diff --git a/modules/localization/ndt/ndt_localization.cc b/modules/localization/ndt/ndt_localization.cc index e753e9a5bf..fb680593c8 100644 --- a/modules/localization/ndt/ndt_localization.cc +++ b/modules/localization/ndt/ndt_localization.cc @@ -35,7 +35,7 @@ void NDTLocalization::Init() { tf_buffer_->Init(); resolution_id_ = 0; - zone_id_ = absl::GetFlag(FLAGS_local_utm_zone_id); + zone_id_ = FLAGS_local_utm_zone_id; online_resolution_ = FLAGS_online_resolution; ndt_debug_log_flag_ = FLAGS_ndt_debug_log_flag; tf_source_frame_id_ = FLAGS_broadcast_tf_frame_id; @@ -47,8 +47,7 @@ void NDTLocalization::Init() { error_ndt_score_ = FLAGS_ndt_error_ndt_score; std::string map_path_ = - absl::StrCat(absl::GetFlag(FLAGS_map_dir), "/", FLAGS_ndt_map_dir, "/", - FLAGS_local_map_name); + FLAGS_map_dir + "/" + FLAGS_ndt_map_dir + "/" + FLAGS_local_map_name; AINFO << "map folder: " << map_path_; velodyne_extrinsic_ = Eigen::Affine3d::Identity(); bool success = diff --git a/modules/localization/ndt/ndt_localization_test.cc b/modules/localization/ndt/ndt_localization_test.cc index a025cb1441..a72172794b 100644 --- a/modules/localization/ndt/ndt_localization_test.cc +++ b/modules/localization/ndt/ndt_localization_test.cc @@ -38,7 +38,7 @@ class NDTLocalizationTest : public ::testing::Test { }; TEST_F(NDTLocalizationTest, Init) { - absl::SetFlag(&FLAGS_local_utm_zone_id, 10); + FLAGS_local_utm_zone_id = 10; FLAGS_online_resolution = 0.25; ndt_localization_ptr_->Init(); EXPECT_EQ(ndt_localization_ptr_->GetZoneId(), 10); diff --git a/modules/map/hdmap/hdmap_util.cc b/modules/map/hdmap/hdmap_util.cc index cbb172d990..ef114d6fa3 100644 --- a/modules/map/hdmap/hdmap_util.cc +++ b/modules/map/hdmap/hdmap_util.cc @@ -32,8 +32,7 @@ namespace { std::string FindFirstExist(const std::string& dir, const std::string& files) { const std::vector candidates = absl::StrSplit(files, '|'); for (const auto& filename : candidates) { - const std::string file_path = - absl::StrCat(absl::GetFlag(FLAGS_map_dir), "/", filename); + const std::string file_path = absl::StrCat(FLAGS_map_dir, "/", filename); if (cyber::common::PathExists(file_path)) { return file_path; } @@ -41,7 +40,7 @@ std::string FindFirstExist(const std::string& dir, const std::string& files) { AERROR << "No existing file found in " << dir << "/" << files << ". Fallback to first candidate as default result."; ACHECK(!candidates.empty()) << "Please specify at least one map."; - return absl::StrCat(absl::GetFlag(FLAGS_map_dir), "/", candidates[0]); + return absl::StrCat(FLAGS_map_dir, "/", candidates[0]); } } // namespace @@ -50,18 +49,16 @@ std::string BaseMapFile() { if (FLAGS_use_navigation_mode) { AWARN << "base_map file is not used when FLAGS_use_navigation_mode is true"; } - return absl::GetFlag(FLAGS_test_base_map_filename).empty() - ? FindFirstExist(absl::GetFlag(FLAGS_map_dir), - absl::GetFlag(FLAGS_base_map_filename)) - : FindFirstExist(absl::GetFlag(FLAGS_map_dir), - absl::GetFlag(FLAGS_test_base_map_filename)); + return FLAGS_test_base_map_filename.empty() + ? FindFirstExist(FLAGS_map_dir, FLAGS_base_map_filename) + : FindFirstExist(FLAGS_map_dir, FLAGS_test_base_map_filename); } std::string SimMapFile() { if (FLAGS_use_navigation_mode) { AWARN << "sim_map file is not used when FLAGS_use_navigation_mode is true"; } - return FindFirstExist(absl::GetFlag(FLAGS_map_dir), FLAGS_sim_map_filename); + return FindFirstExist(FLAGS_map_dir, FLAGS_sim_map_filename); } std::string RoutingMapFile() { @@ -69,8 +66,7 @@ std::string RoutingMapFile() { AWARN << "routing_map file is not used when FLAGS_use_navigation_mode is " "true"; } - return FindFirstExist(absl::GetFlag(FLAGS_map_dir), - FLAGS_routing_map_filename); + return FindFirstExist(FLAGS_map_dir, FLAGS_routing_map_filename); } std::unique_ptr CreateMap(const std::string& map_file_path) { diff --git a/modules/map/hdmap/hdmap_util.h b/modules/map/hdmap/hdmap_util.h index f39f81f5ac..e9ce5d55c3 100644 --- a/modules/map/hdmap/hdmap_util.h +++ b/modules/map/hdmap/hdmap_util.h @@ -57,8 +57,7 @@ inline std::string EndWayPointFile() { if (FLAGS_use_navigation_mode) { return absl::StrCat(FLAGS_navigation_mode_end_way_point_file); } else { - return absl::StrCat(absl::GetFlag(FLAGS_map_dir), "/", - FLAGS_end_way_point_filename); + return absl::StrCat(FLAGS_map_dir, "/", FLAGS_end_way_point_filename); } } diff --git a/modules/map/tools/bin_map_generator.cc b/modules/map/tools/bin_map_generator.cc index 6900e276cf..7c2a8c29b3 100644 --- a/modules/map/tools/bin_map_generator.cc +++ b/modules/map/tools/bin_map_generator.cc @@ -33,7 +33,7 @@ int main(int argc, char **argv) { google::ParseCommandLineFlags(&argc, &argv, true); - const auto map_filename = absl::GetFlag(FLAGS_map_dir) + "/base_map.txt"; + const auto map_filename = FLAGS_map_dir + "/base_map.txt"; apollo::hdmap::Map pb_map; ACHECK(apollo::cyber::common::GetProtoFromFile(map_filename, &pb_map)) << "fail to load data from : " << map_filename; diff --git a/modules/map/tools/proto_map_generator.cc b/modules/map/tools/proto_map_generator.cc index 775472422c..8588034bdf 100644 --- a/modules/map/tools/proto_map_generator.cc +++ b/modules/map/tools/proto_map_generator.cc @@ -33,8 +33,7 @@ int main(int argc, char **argv) { google::ParseCommandLineFlags(&argc, &argv, true); - const auto map_filename = - absl::StrCat(absl::GetFlag(FLAGS_map_dir), "/base_map.xml"); + const auto map_filename = FLAGS_map_dir + "/base_map.xml"; apollo::hdmap::Map pb_map; ACHECK( apollo::hdmap::adapter::OpendriveAdapter::LoadData(map_filename, &pb_map)) diff --git a/modules/perception/map/hdmap/hdmap_input.cc b/modules/perception/map/hdmap/hdmap_input.cc index c4bff29bae..10b7bef1ea 100644 --- a/modules/perception/map/hdmap/hdmap_input.cc +++ b/modules/perception/map/hdmap/hdmap_input.cc @@ -87,7 +87,7 @@ bool HDMapInput::InitHDMap() { // Option2: Load own map with different hdmap_sample_step_ // Load hdmap path from global_flagfile.txt - hdmap_file_ = absl::StrCat(absl::GetFlag(FLAGS_map_dir), "/base_map.bin"); + hdmap_file_ = absl::StrCat(FLAGS_map_dir, "/base_map.bin"); AINFO << "hdmap_file_: " << hdmap_file_; if (!apollo::cyber::common::PathExists(hdmap_file_)) { AERROR << "Failed to find hadmap file: " << hdmap_file_; diff --git a/modules/planning/common/message_process.cc b/modules/planning/common/message_process.cc index a886a20bce..1272186b8b 100644 --- a/modules/planning/common/message_process.cc +++ b/modules/planning/common/message_process.cc @@ -58,7 +58,8 @@ using apollo::routing::RoutingResponse; using apollo::storytelling::CloseToJunction; using apollo::storytelling::Stories; -bool MessageProcess::Init(const PlanningConfig& planning_config) { +bool MessageProcess::Init( + const PlanningConfig& planning_config) { planning_config_.CopyFrom(planning_config); map_m_["Sunnyvale"] = "sunnyvale"; @@ -68,8 +69,7 @@ bool MessageProcess::Init(const PlanningConfig& planning_config) { map_m_["Sunnyvale Loop"] = "sunnyvale_loop"; map_m_["San Mateo"] = "san_mateo"; - map_name_ = absl::GetFlag(FLAGS_map_dir) - .substr(absl::GetFlag(FLAGS_map_dir).find_last_of("/") + 1); + map_name_ = FLAGS_map_dir.substr(FLAGS_map_dir.find_last_of("/") + 1); obstacle_history_map_.clear(); @@ -85,8 +85,9 @@ bool MessageProcess::Init(const PlanningConfig& planning_config) { return true; } -bool MessageProcess::Init(const PlanningConfig& planning_config, - const std::shared_ptr& injector) { +bool MessageProcess::Init( + const PlanningConfig& planning_config, + const std::shared_ptr& injector) { injector_ = injector; return Init(planning_config); } @@ -123,7 +124,7 @@ void MessageProcess::OnHMIStatus(apollo::dreamview::HMIStatus hmi_status) { if (map_m_.count(current_map) > 0) { map_name_ = map_m_[current_map]; const std::string& map_base_folder = "/apollo/modules/map/data/"; - absl::SetFlag(&FLAGS_map_dir, (map_base_folder + map_name_)); + FLAGS_map_dir = map_base_folder + map_name_; } } @@ -173,8 +174,8 @@ void MessageProcess::OnLocalization(const LocalizationEstimate& le) { FeatureOutput::InsertLearningDataFrame(record_file_, learning_data_frame); } else { // online - injector_->learning_based_data()->InsertLearningDataFrame( - learning_data_frame); + injector_->learning_based_data() + ->InsertLearningDataFrame(learning_data_frame); } } diff --git a/modules/planning/integration_tests/garage_test.cc b/modules/planning/integration_tests/garage_test.cc index f150d8721b..9fe1fdb2f0 100644 --- a/modules/planning/integration_tests/garage_test.cc +++ b/modules/planning/integration_tests/garage_test.cc @@ -37,8 +37,8 @@ class GarageTest : public PlanningTestBase { FLAGS_use_multi_thread_to_add_obstacles = false; FLAGS_enable_multi_thread_in_dp_st_graph = false; FLAGS_use_navigation_mode = false; - absl::SetFlag(&FLAGS_map_dir, "modules/planning/testdata/garage_map"); - absl::SetFlag(&FLAGS_base_map_filename, "base_map.txt"); + FLAGS_map_dir = "modules/planning/testdata/garage_map"; + FLAGS_base_map_filename = "base_map.txt"; FLAGS_test_data_dir = "modules/planning/testdata/garage_test"; FLAGS_planning_upper_speed_limit = 12.5; FLAGS_test_routing_response_file = "garage_routing.pb.txt"; diff --git a/modules/planning/integration_tests/planning_test_base.cc b/modules/planning/integration_tests/planning_test_base.cc index 03bc41a055..b94a1a9086 100644 --- a/modules/planning/integration_tests/planning_test_base.cc +++ b/modules/planning/integration_tests/planning_test_base.cc @@ -56,7 +56,7 @@ void PlanningTestBase::SetUpTestCase() { "/apollo/modules/planning/conf/traffic_rule_config.pb.txt"; FLAGS_smoother_config_filename = "/apollo/modules/planning/conf/qp_spline_smoother_config.pb.txt"; - absl::SetFlag(&FLAGS_map_dir, "/apollo/modules/planning/testdata"); + FLAGS_map_dir = "/apollo/modules/planning/testdata"; FLAGS_test_localization_file = ""; FLAGS_test_chassis_file = ""; FLAGS_test_routing_response_file = ""; diff --git a/modules/planning/integration_tests/sunnyvale_big_loop_test.cc b/modules/planning/integration_tests/sunnyvale_big_loop_test.cc index 7b20d6aa6a..b108c3f288 100644 --- a/modules/planning/integration_tests/sunnyvale_big_loop_test.cc +++ b/modules/planning/integration_tests/sunnyvale_big_loop_test.cc @@ -45,8 +45,8 @@ class SunnyvaleBigLoopTest : public PlanningTestBase { public: virtual void SetUp() { FLAGS_use_navigation_mode = false; - absl::SetFlag(&FLAGS_map_dir, "modules/map/data/sunnyvale_big_loop"); - absl::SetFlag(&FLAGS_test_base_map_filename, "base_map.bin"); + FLAGS_map_dir = "modules/map/data/sunnyvale_big_loop"; + FLAGS_test_base_map_filename = "base_map.bin"; FLAGS_test_data_dir = "modules/planning/testdata/sunnyvale_big_loop_test"; FLAGS_planning_upper_speed_limit = 12.5; diff --git a/modules/planning/integration_tests/sunnyvale_loop_test.cc b/modules/planning/integration_tests/sunnyvale_loop_test.cc index f11ee62252..a8b2687dd1 100644 --- a/modules/planning/integration_tests/sunnyvale_loop_test.cc +++ b/modules/planning/integration_tests/sunnyvale_loop_test.cc @@ -33,8 +33,8 @@ class SunnyvaleLoopTest : public PlanningTestBase { public: virtual void SetUp() { FLAGS_use_navigation_mode = false; - absl::SetFlag(&FLAGS_map_dir, "modules/map/data/sunnyvale_loop"); - absl::SetFlag(&FLAGS_test_base_map_filename, "base_map_test.bin"); + FLAGS_map_dir = "modules/map/data/sunnyvale_loop"; + FLAGS_test_base_map_filename = "base_map_test.bin"; FLAGS_test_data_dir = "modules/planning/testdata/sunnyvale_loop_test"; FLAGS_planning_upper_speed_limit = 12.5; FLAGS_use_multi_thread_to_add_obstacles = false; diff --git a/modules/planning/learning_based/img_feature_renderer/birdview_img_feature_renderer.cc b/modules/planning/learning_based/img_feature_renderer/birdview_img_feature_renderer.cc index 369338c637..2297f82410 100644 --- a/modules/planning/learning_based/img_feature_renderer/birdview_img_feature_renderer.cc +++ b/modules/planning/learning_based/img_feature_renderer/birdview_img_feature_renderer.cc @@ -46,8 +46,7 @@ bool BirdviewImgFeatureRenderer::Init(const PlanningSemanticMapConfig& config) { apollo::hdmap::HDMapUtil::BaseMap(); const std::string map_name = - absl::GetFlag(FLAGS_map_dir) - .substr(absl::GetFlag(FLAGS_map_dir).find_last_of("/") + 1); + FLAGS_map_dir.substr(FLAGS_map_dir.find_last_of("/") + 1); if (map_name != "sunnyvale_with_two_offices" && map_name != "sunnyvale") { AERROR << "Map other than sunnyvale_with_two_offices are not supported"; } diff --git a/modules/planning/learning_based/model_inference/model_inference_test.cc b/modules/planning/learning_based/model_inference/model_inference_test.cc index 7062b5514c..55b738a3c7 100644 --- a/modules/planning/learning_based/model_inference/model_inference_test.cc +++ b/modules/planning/learning_based/model_inference/model_inference_test.cc @@ -43,9 +43,8 @@ class ModelInferenceTest : public ::testing::Test { public: virtual ~ModelInferenceTest() = default; virtual void SetUp() { - absl::SetFlag(&FLAGS_map_dir, - "/apollo/modules/map/data/sunnyvale_with_two_offices"); - absl::SetFlag(&FLAGS_base_map_filename, "base_map.bin"); + FLAGS_map_dir = "/apollo/modules/map/data/sunnyvale_with_two_offices"; + FLAGS_base_map_filename = "base_map.bin"; } }; diff --git a/modules/planning/pipeline/record_to_learning_data.cc b/modules/planning/pipeline/record_to_learning_data.cc index da8ecfbd8d..139c9b8fba 100644 --- a/modules/planning/pipeline/record_to_learning_data.cc +++ b/modules/planning/pipeline/record_to_learning_data.cc @@ -30,7 +30,7 @@ namespace apollo { namespace planning { void GenerateLearningData() { - AINFO << "map_dir: " << absl::GetFlag(FLAGS_map_dir); + AINFO << "map_dir: " << FLAGS_map_dir; if (FLAGS_planning_offline_bags.empty()) { return; } diff --git a/modules/prediction/common/kml_map_based_test.h b/modules/prediction/common/kml_map_based_test.h index 5b5104733b..bce55f9684 100644 --- a/modules/prediction/common/kml_map_based_test.h +++ b/modules/prediction/common/kml_map_based_test.h @@ -26,8 +26,8 @@ namespace prediction { class KMLMapBasedTest : public ::testing::Test { public: KMLMapBasedTest() { - absl::SetFlag(&FLAGS_map_dir, "modules/prediction/testdata"); - absl::SetFlag(&FLAGS_base_map_filename, "kml_map.bin"); + FLAGS_map_dir = "modules/prediction/testdata"; + FLAGS_base_map_filename = "kml_map.bin"; } }; diff --git a/modules/v2x/v2x_proxy/app/v2x_proxy.cc b/modules/v2x/v2x_proxy/app/v2x_proxy.cc index eb069e199b..c333f22d1c 100644 --- a/modules/v2x/v2x_proxy/app/v2x_proxy.cc +++ b/modules/v2x/v2x_proxy/app/v2x_proxy.cc @@ -35,14 +35,14 @@ V2xProxy::V2xProxy() auto x2v_trafficlight_timer_period = ceil( (1.0 / static_cast(FLAGS_x2v_trafficlight_timer_frequency)) * 1000); - x2v_trafficlight_timer_.reset(new cyber::Timer( - static_cast(x2v_trafficlight_timer_period), - [this]() { this->OnX2vTrafficLightTimer(); }, false)); + x2v_trafficlight_timer_.reset( + new cyber::Timer(static_cast(x2v_trafficlight_timer_period), + [this]() { this->OnX2vTrafficLightTimer(); }, false)); auto v2x_carstatus_timer_period = ceil( (1.0 / static_cast(FLAGS_v2x_carstatus_timer_frequency)) * 1000); - v2x_carstatus_timer_.reset(new cyber::Timer( - static_cast(v2x_carstatus_timer_period), - [this]() { this->OnV2xCarStatusTimer(); }, false)); + v2x_carstatus_timer_.reset( + new cyber::Timer(static_cast(v2x_carstatus_timer_period), + [this]() { this->OnV2xCarStatusTimer(); }, false)); os_interface_.reset(new OsInterFace()); obu_interface_.reset(new ObuInterFaceGrpcImpl()); @@ -57,8 +57,7 @@ V2xProxy::V2xProxy() } hdmap_.reset(new apollo::hdmap::HDMap()); - std::string map_name = absl::StrCat(absl::GetFlag(FLAGS_map_dir), "/", - absl::GetFlag(FLAGS_base_map_filename)); + std::string map_name = FLAGS_map_dir + "/" + FLAGS_base_map_filename; if (FLAGS_debug_flag) { map_name = FLAGS_hdmap_file_name; } -- GitLab