diff --git a/modules/perception/common/sensor_manager/sensor_manager.cc b/modules/perception/common/sensor_manager/sensor_manager.cc index 30b2de23d25cc5e7e8998856056592796de0e5c0..f9d074cdb3ce30b4891fef4039a23c5ee1f2e12b 100644 --- a/modules/perception/common/sensor_manager/sensor_manager.cc +++ b/modules/perception/common/sensor_manager/sensor_manager.cc @@ -47,11 +47,8 @@ bool SensorManager::Init() { distort_model_map_.clear(); undistort_model_map_.clear(); - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); std::string file_path = lib::FileUtil::GetAbsolutePath( - config_manager->work_root(), FLAGS_obs_sensor_meta_path); + lib::ConfigManager::Instance()->work_root(), FLAGS_obs_sensor_meta_path); MultiSensorMeta sensor_list_proto; if (!GetProtoFromASCIIFile(file_path, &sensor_list_proto)) { diff --git a/modules/perception/fusion/base/base_init_options.cc b/modules/perception/fusion/base/base_init_options.cc index b5aea3345c9dd17ef3fc08c01a17a3b12441fe32..46a67b8dd9b8cb9d38f052dfaf886f113a7b6d96 100644 --- a/modules/perception/fusion/base/base_init_options.cc +++ b/modules/perception/fusion/base/base_init_options.cc @@ -26,11 +26,9 @@ namespace fusion { bool GetFusionInitOptions(const std::string& module_name, BaseInitOptions* options) { CHECK_NOTNULL(options); - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); const lib::ModelConfig* model_config = nullptr; - if (!config_manager->GetModelConfig(module_name, &model_config)) { + if (!lib::ConfigManager::Instance()->GetModelConfig(module_name, + &model_config)) { return false; } bool state = model_config->get_value("root_dir", &(options->root_dir)) && diff --git a/modules/perception/fusion/lib/data_fusion/existance_fusion/dst_existance_fusion/dst_existance_fusion.cc b/modules/perception/fusion/lib/data_fusion/existance_fusion/dst_existance_fusion/dst_existance_fusion.cc index 6558af5cdc548224fd9cb0ca0a13695eb7417a97..9cf45a9e939f6557cb0bb00a019de5e1f42f6c2c 100644 --- a/modules/perception/fusion/lib/data_fusion/existance_fusion/dst_existance_fusion/dst_existance_fusion.cc +++ b/modules/perception/fusion/lib/data_fusion/existance_fusion/dst_existance_fusion/dst_existance_fusion.cc @@ -49,11 +49,8 @@ bool DstExistanceFusion::Init() { return false; } - lib::ConfigManager *config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); std::string woork_root_config = lib::FileUtil::GetAbsolutePath( - config_manager->work_root(), options.root_dir); + lib::ConfigManager::Instance()->work_root(), options.root_dir); std::string config = lib::FileUtil::GetAbsolutePath(woork_root_config, options.conf_file); diff --git a/modules/perception/fusion/lib/data_fusion/tracker/pbf_tracker/pbf_tracker.cc b/modules/perception/fusion/lib/data_fusion/tracker/pbf_tracker/pbf_tracker.cc index 38ac90fa50a8423d0cc15880cee4cfafdfc9c202..4362685c209a357f1a5502d3d3d2369eef37cb32 100644 --- a/modules/perception/fusion/lib/data_fusion/tracker/pbf_tracker/pbf_tracker.cc +++ b/modules/perception/fusion/lib/data_fusion/tracker/pbf_tracker/pbf_tracker.cc @@ -44,11 +44,8 @@ bool PbfTracker::InitParams() { return false; } - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); std::string woork_root_config = lib::FileUtil::GetAbsolutePath( - config_manager->work_root(), options.root_dir); + lib::ConfigManager::Instance()->work_root(), options.root_dir); std::string config = lib::FileUtil::GetAbsolutePath(woork_root_config, options.conf_file); diff --git a/modules/perception/fusion/lib/data_fusion/type_fusion/dst_type_fusion/dst_type_fusion.cc b/modules/perception/fusion/lib/data_fusion/type_fusion/dst_type_fusion/dst_type_fusion.cc index dcc70d7f21489a9ee35a105d446b0dcbaaddb009..ba15fffa2173563585206dc2785849ac7bcf9106 100644 --- a/modules/perception/fusion/lib/data_fusion/type_fusion/dst_type_fusion/dst_type_fusion.cc +++ b/modules/perception/fusion/lib/data_fusion/type_fusion/dst_type_fusion/dst_type_fusion.cc @@ -72,11 +72,8 @@ bool DstTypeFusion::Init() { return false; } - lib::ConfigManager *config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); std::string woork_root_config = lib::FileUtil::GetAbsolutePath( - config_manager->work_root(), options.root_dir); + lib::ConfigManager::Instance()->work_root(), options.root_dir); std::string config = lib::FileUtil::GetAbsolutePath(woork_root_config, options.conf_file); diff --git a/modules/perception/fusion/lib/fusion_system/probabilistic_fusion/probabilistic_fusion.cc b/modules/perception/fusion/lib/fusion_system/probabilistic_fusion/probabilistic_fusion.cc index 5bd9f6fff286210033ef97579ef71b3473ec0d54..d59a39d5e632e79842496c7713fc8662122b601e 100644 --- a/modules/perception/fusion/lib/fusion_system/probabilistic_fusion/probabilistic_fusion.cc +++ b/modules/perception/fusion/lib/fusion_system/probabilistic_fusion/probabilistic_fusion.cc @@ -52,11 +52,8 @@ bool ProbabilisticFusion::Init(const FusionInitOptions& init_options) { return false; } - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); std::string woork_root_config = lib::FileUtil::GetAbsolutePath( - config_manager->work_root(), options.root_dir); + lib::ConfigManager::Instance()->work_root(), options.root_dir); std::string config = lib::FileUtil::GetAbsolutePath(woork_root_config, options.conf_file); diff --git a/modules/perception/fusion/lib/gatekeeper/pbf_gatekeeper/pbf_gatekeeper.cc b/modules/perception/fusion/lib/gatekeeper/pbf_gatekeeper/pbf_gatekeeper.cc index 2e2f90364b79c5dfc06dedc846a14ae09c43af8c..853dbf319c62ef9b4473bdde775e328da9530600 100644 --- a/modules/perception/fusion/lib/gatekeeper/pbf_gatekeeper/pbf_gatekeeper.cc +++ b/modules/perception/fusion/lib/gatekeeper/pbf_gatekeeper/pbf_gatekeeper.cc @@ -38,11 +38,8 @@ bool PbfGatekeeper::Init() { return false; } - lib::ConfigManager *config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); std::string woork_root_config = lib::FileUtil::GetAbsolutePath( - config_manager->work_root(), options.root_dir); + lib::ConfigManager::Instance()->work_root(), options.root_dir); std::string config = lib::FileUtil::GetAbsolutePath(woork_root_config, options.conf_file); diff --git a/modules/perception/lib/config_manager/config_manager.h b/modules/perception/lib/config_manager/config_manager.h index 235d32231b7039a869ae7afd0d733d598a6eb5c9..569a662bab8d8d6e2c6f8f80e2659abcff19478f 100644 --- a/modules/perception/lib/config_manager/config_manager.h +++ b/modules/perception/lib/config_manager/config_manager.h @@ -119,7 +119,7 @@ #include #include -#include "modules/perception/lib/singleton/singleton.h" +#include "cyber/common/macros.h" #include "modules/perception/lib/thread/mutex.h" #include "modules/perception/proto/perception_config_schema.pb.h" @@ -131,6 +131,8 @@ class ModelConfig; class ConfigManager { public: + ~ConfigManager(); + // thread-safe interface. bool Init(); @@ -146,29 +148,17 @@ class ConfigManager { void set_work_root(const std::string &work_root) { work_root_ = work_root; } - ConfigManager(const ConfigManager &) = delete; - ConfigManager operator=(const ConfigManager &) = delete; - private: - ConfigManager(); - ~ConfigManager(); - bool InitInternal(); std::string get_env(const std::string &var_name); - friend class lib::Singleton; - - /* TODO(all): to remove - typedef std::map ModelConfigMap; - typedef ModelConfigMap::iterator ModelConfigMapIterator; - typedef ModelConfigMap::const_iterator ModelConfigMapConstIterator; - */ - // key: model_name std::map model_config_map_; Mutex mutex_; // multi-thread init safe. bool inited_ = false; std::string work_root_; // ConfigManager work root dir. + + DECLARE_SINGLETON(ConfigManager); }; class ModelConfig { @@ -243,19 +233,6 @@ class ModelConfig { std::string name_; std::string version_; - /* TODO(all): to remove - typedef std::map IntegerParamMap; - typedef std::map StringParamMap; - typedef std::map DoubleParamMap; - typedef std::map FloatParamMap; - typedef std::map BoolParamMap; - typedef std::map> ArrayIntegerParamMap; - typedef std::map> ArrayStringParamMap; - typedef std::map> ArrayDoubleParamMap; - typedef std::map> ArrayFloatParamMap; - typedef std::map> ArrayBoolParamMap; - */ - std::map integer_param_map_; std::map string_param_map_; std::map double_param_map_; diff --git a/modules/perception/lib/config_manager/config_manager_test.cc b/modules/perception/lib/config_manager/config_manager_test.cc index 19fec096a3ddde41e1286033dae766950c2eb5b6..7fe7d9f063a65f2be00395c62b12575b0930d85d 100644 --- a/modules/perception/lib/config_manager/config_manager_test.cc +++ b/modules/perception/lib/config_manager/config_manager_test.cc @@ -35,12 +35,12 @@ class ConfigManagerTest : public testing::Test { char module_path[80] = "MODULE_PATH="; putenv(module_path); FLAGS_config_manager_path = "/apollo/modules/perception/testdata/lib/conf"; - config_manager_ = lib::Singleton::get_instance(); + config_manager_ = ConfigManager::Instance(); ASSERT_TRUE(config_manager_ != nullptr); } protected: - ConfigManager* config_manager_; + std::shared_ptr config_manager_; }; TEST_F(ConfigManagerTest, TestInit) { diff --git a/modules/perception/lidar/app/lidar_obstacle_segmentation.cc b/modules/perception/lidar/app/lidar_obstacle_segmentation.cc index 9ed8dcdbc3a5f703b1cd64f59bdbd70a9a83769c..ce967bb0bc29fb9c394a598e6986406a97867f7b 100644 --- a/modules/perception/lidar/app/lidar_obstacle_segmentation.cc +++ b/modules/perception/lidar/app/lidar_obstacle_segmentation.cc @@ -30,9 +30,7 @@ namespace lidar { bool LidarObstacleSegmentation::Init( const LidarObstacleSegmentationInitOptions& options) { auto& sensor_name = options.sensor_name; - lib::ConfigManager* config_manager - = lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); + auto& config_manager = lib::ConfigManager::Instance(); const lib::ModelConfig* model_config = nullptr; CHECK(config_manager->GetModelConfig(Name(), &model_config)); diff --git a/modules/perception/lidar/app/lidar_obstacle_tracking.cc b/modules/perception/lidar/app/lidar_obstacle_tracking.cc index 4cc4300613bb77197e71c39547d0f9e42769301e..d2195d64b7f21d4c9e0cbe263bf1ff5c6546848e 100644 --- a/modules/perception/lidar/app/lidar_obstacle_tracking.cc +++ b/modules/perception/lidar/app/lidar_obstacle_tracking.cc @@ -29,9 +29,7 @@ namespace lidar { bool LidarObstacleTracking::Init( const LidarObstacleTrackingInitOptions& options) { auto& sensor_name = options.sensor_name; - lib::ConfigManager* config_manager - = lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); + auto& config_manager = lib::ConfigManager::Instance(); const lib::ModelConfig* model_config = nullptr; CHECK(config_manager->GetModelConfig(Name(), &model_config)); diff --git a/modules/perception/lidar/lib/classifier/fused_classifier/ccrf_type_fusion.cc b/modules/perception/lidar/lib/classifier/fused_classifier/ccrf_type_fusion.cc index 6b9ce4f7ce85e35e81da277a3ec1f5b93fbc5c32..3152f597c88d594720f4bfdda4479858575c07b4 100644 --- a/modules/perception/lidar/lib/classifier/fused_classifier/ccrf_type_fusion.cc +++ b/modules/perception/lidar/lib/classifier/fused_classifier/ccrf_type_fusion.cc @@ -34,9 +34,7 @@ using ObjectPtr = std::shared_ptr; using apollo::perception::base::ObjectType; bool CCRFOneShotTypeFusion::Init(const TypeFusionInitOption& option) { - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); + auto& config_manager = lib::ConfigManager::Instance(); const lib::ModelConfig* model_config = nullptr; CHECK(config_manager->GetModelConfig(Name(), &model_config)); const std::string work_root = config_manager->work_root(); @@ -131,9 +129,7 @@ bool CCRFOneShotTypeFusion::FuseOneShotTypeProbs(const ObjectPtr& object, bool CCRFSequenceTypeFusion::Init(const TypeFusionInitOption& option) { CHECK(one_shot_fuser_.Init(option)); - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); + auto& config_manager = lib::ConfigManager::Instance(); const lib::ModelConfig* model_config = nullptr; CHECK(config_manager->GetModelConfig(Name(), &model_config)); const std::string work_root = config_manager->work_root(); diff --git a/modules/perception/lidar/lib/classifier/fused_classifier/fused_classifier.cc b/modules/perception/lidar/lib/classifier/fused_classifier/fused_classifier.cc index f7cc5c9fe24a13ff6206e95fb2a5ff0352cbd178..c795c9cdb7f45a99103c1f7d3f55f89838c39fb6 100644 --- a/modules/perception/lidar/lib/classifier/fused_classifier/fused_classifier.cc +++ b/modules/perception/lidar/lib/classifier/fused_classifier/fused_classifier.cc @@ -28,9 +28,7 @@ using ObjectPtr = std::shared_ptr; using apollo::perception::base::ObjectType; bool FusedClassifier::Init(const ClassifierInitOptions& options) { - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); + auto& config_manager = lib::ConfigManager::Instance(); const lib::ModelConfig* model_config = nullptr; CHECK(config_manager->GetModelConfig(Name(), &model_config)); const std::string work_root = config_manager->work_root(); diff --git a/modules/perception/lidar/lib/classifier/fused_classifier/fused_classifier_test.cc b/modules/perception/lidar/lib/classifier/fused_classifier/fused_classifier_test.cc index 4181ff9df7717a1bec7018c83e618aa90a1d6770..cb17106b0f93e64391f6f554e15c6caeca3ebf67 100644 --- a/modules/perception/lidar/lib/classifier/fused_classifier/fused_classifier_test.cc +++ b/modules/perception/lidar/lib/classifier/fused_classifier/fused_classifier_test.cc @@ -71,7 +71,6 @@ class FusedClassifierTest : public testing::Test { std::vector timestamps_; static const size_t kSequenceLength; static const size_t kObjectNum; - lib::ConfigManager* config_manager_; }; const size_t FusedClassifierTest::kSequenceLength = 10; diff --git a/modules/perception/lidar/lib/ground_detector/ground_service_detector/ground_service_detector.cc b/modules/perception/lidar/lib/ground_detector/ground_service_detector/ground_service_detector.cc index 34524ca540283443702aee6466e437006864735f..2bee24c150d1e2d1c486fe47d5c70bb40030909a 100644 --- a/modules/perception/lidar/lib/ground_detector/ground_service_detector/ground_service_detector.cc +++ b/modules/perception/lidar/lib/ground_detector/ground_service_detector/ground_service_detector.cc @@ -27,9 +27,7 @@ namespace perception { namespace lidar { bool GroundServiceDetector::Init(const GroundDetectorInitOptions& options) { - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); + auto& config_manager = lib::ConfigManager::Instance(); const lib::ModelConfig* model_config = nullptr; CHECK(config_manager->GetModelConfig(Name(), &model_config)); diff --git a/modules/perception/lidar/lib/ground_detector/ground_service_detector/ground_service_detector_test.cc b/modules/perception/lidar/lib/ground_detector/ground_service_detector/ground_service_detector_test.cc index 8f972c3919af699edde1837ee84387503d104164..8d1a1015465b2846bace76eb82b6046d9ea68f4c 100644 --- a/modules/perception/lidar/lib/ground_detector/ground_service_detector/ground_service_detector_test.cc +++ b/modules/perception/lidar/lib/ground_detector/ground_service_detector/ground_service_detector_test.cc @@ -35,9 +35,7 @@ class LidarLibGroundServiceDetectorTest : public testing::Test { FLAGS_work_root = "/apollo/modules/perception/testdata/" "lidar/lib/ground_detector/ground_service_detector"; FLAGS_config_manager_path = "./conf"; - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - config_manager->Reset(); + lib::ConfigManager::Instance()->Reset(); } void TearDown() {} diff --git a/modules/perception/lidar/lib/ground_detector/spatio_temporal_ground_detector/spatio_temporal_ground_detector.cc b/modules/perception/lidar/lib/ground_detector/spatio_temporal_ground_detector/spatio_temporal_ground_detector.cc index eb48e770727356bfb231b41b2541ed0f0f9b2cd1..7f5c82a50d70dfe580ed3d0cd9afc53476fb1dfa 100644 --- a/modules/perception/lidar/lib/ground_detector/spatio_temporal_ground_detector/spatio_temporal_ground_detector.cc +++ b/modules/perception/lidar/lib/ground_detector/spatio_temporal_ground_detector/spatio_temporal_ground_detector.cc @@ -32,12 +32,10 @@ using apollo::common::util::GetProtoFromFile; bool SpatioTemporalGroundDetector::Init( const GroundDetectorInitOptions& options) { - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); const lib::ModelConfig* model_config = nullptr; - CHECK(config_manager->GetModelConfig("SpatioTemporalGroundDetector", - &model_config)) + auto& config_manager = lib::ConfigManager::Instance(); + CHECK(config_manager->GetModelConfig( + "SpatioTemporalGroundDetector", &model_config)) << "Failed to get model config: SpatioTemporalGroundDetector"; const std::string& work_root = config_manager->work_root(); diff --git a/modules/perception/lidar/lib/map_manager/map_manager.cc b/modules/perception/lidar/lib/map_manager/map_manager.cc index 9f64e14487d5eab60d4e01f89380cce4c1865954..ff53240ede96fe1dc793b1ba5ef110d8db88426c 100644 --- a/modules/perception/lidar/lib/map_manager/map_manager.cc +++ b/modules/perception/lidar/lib/map_manager/map_manager.cc @@ -28,9 +28,7 @@ namespace perception { namespace lidar { bool MapManager::Init(const MapManagerInitOptions& options) { - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); + auto& config_manager = lib::ConfigManager::Instance(); const lib::ModelConfig* model_config = nullptr; CHECK(config_manager->GetModelConfig(Name(), &model_config)); const std::string work_root = config_manager->work_root(); diff --git a/modules/perception/lidar/lib/map_manager/map_manager_test.cc b/modules/perception/lidar/lib/map_manager/map_manager_test.cc index 7fe0663ac608d9c3177f8c1f83485cbfc83b5990..f439b72ab76855bea1622547d4437ee9013c1c20 100644 --- a/modules/perception/lidar/lib/map_manager/map_manager_test.cc +++ b/modules/perception/lidar/lib/map_manager/map_manager_test.cc @@ -32,9 +32,7 @@ TEST(LidarLibMapManagerTest, lidar_map_manager_empty_test) { FLAGS_work_root = "/apollo/modules/perception/testdata/lidar/lib/map_manager"; FLAGS_config_manager_path = "./empty_conf"; - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - config_manager->Reset(); + lib::ConfigManager::Instance()->Reset(); map::HDMapInput* hdmap_input = lib::Singleton::get_instance(); @@ -52,9 +50,7 @@ TEST(LidarLibMapManagerTest, lidar_map_manager_test) { FLAGS_work_root = "/apollo/modules/perception/testdata/lidar/lib/map_manager"; FLAGS_config_manager_path = "./conf"; - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - config_manager->Reset(); + lib::ConfigManager::Instance()->Reset(); map::HDMapInput* hdmap_input = lib::Singleton::get_instance(); diff --git a/modules/perception/lidar/lib/object_filter_bank/object_filter_bank.cc b/modules/perception/lidar/lib/object_filter_bank/object_filter_bank.cc index 1e56769487ee54956e020ae12d608896b7ae117d..f01d0647e731d252e20ec3220360bf072f131a21 100644 --- a/modules/perception/lidar/lib/object_filter_bank/object_filter_bank.cc +++ b/modules/perception/lidar/lib/object_filter_bank/object_filter_bank.cc @@ -26,9 +26,7 @@ namespace perception { namespace lidar { bool ObjectFilterBank::Init(const ObjectFilterInitOptions& options) { - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); + auto& config_manager = lib::ConfigManager::Instance(); const lib::ModelConfig* model_config = nullptr; CHECK(config_manager->GetModelConfig(Name(), &model_config)); const std::string work_root = config_manager->work_root(); diff --git a/modules/perception/lidar/lib/object_filter_bank/roi_boundary_filter/roi_boundary_filter.cc b/modules/perception/lidar/lib/object_filter_bank/roi_boundary_filter/roi_boundary_filter.cc index 0f8388987d67400a7ba5f701057046ef1647b235..f9a62f4545ba6560f57a293111429a94e24e142b 100644 --- a/modules/perception/lidar/lib/object_filter_bank/roi_boundary_filter/roi_boundary_filter.cc +++ b/modules/perception/lidar/lib/object_filter_bank/roi_boundary_filter/roi_boundary_filter.cc @@ -29,9 +29,7 @@ namespace lidar { using apollo::perception::base::PointD; bool ROIBoundaryFilter::Init(const ObjectFilterInitOptions& options) { - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); + auto& config_manager = lib::ConfigManager::Instance(); const lib::ModelConfig* model_config = nullptr; CHECK(config_manager->GetModelConfig(Name(), &model_config)); const std::string work_root = config_manager->work_root(); diff --git a/modules/perception/lidar/lib/pointcloud_preprocessor/pointcloud_preprocessor.cc b/modules/perception/lidar/lib/pointcloud_preprocessor/pointcloud_preprocessor.cc index 9ac7d5754c34f039d32e1718871bf1c68220c9fa..a1652c933b7bd18a6d878a4166b9d15d44cdfeb1 100644 --- a/modules/perception/lidar/lib/pointcloud_preprocessor/pointcloud_preprocessor.cc +++ b/modules/perception/lidar/lib/pointcloud_preprocessor/pointcloud_preprocessor.cc @@ -33,9 +33,7 @@ const float PointCloudPreprocessor::kPointInfThreshold = 1e3; bool PointCloudPreprocessor::Init( const PointCloudPreprocessorInitOptions& options) { - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); + auto& config_manager = lib::ConfigManager::Instance(); const lib::ModelConfig* model_config = nullptr; CHECK(config_manager->GetModelConfig(Name(), &model_config)); const std::string work_root = config_manager->work_root(); diff --git a/modules/perception/lidar/lib/roi_filter/hdmap_roi_filter/hdmap_roi_filter.cc b/modules/perception/lidar/lib/roi_filter/hdmap_roi_filter/hdmap_roi_filter.cc index b1f266909b3ecb11509a2297beed94bf1a736572..1570e045d9824f7aee445e9d60f3e8c3d5fea2d2 100644 --- a/modules/perception/lidar/lib/roi_filter/hdmap_roi_filter/hdmap_roi_filter.cc +++ b/modules/perception/lidar/lib/roi_filter/hdmap_roi_filter/hdmap_roi_filter.cc @@ -39,9 +39,7 @@ using Polygon = typename PolygonScanCvter::Polygon; bool HdmapROIFilter::Init(const ROIFilterInitOptions& options) { // load model config - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); + auto& config_manager = lib::ConfigManager::Instance(); const lib::ModelConfig* model_config = nullptr; CHECK(config_manager->GetModelConfig(Name(), &model_config)); const std::string work_root = config_manager->work_root(); diff --git a/modules/perception/lidar/lib/roi_filter/roi_service_filter/roi_service_filter_test.cc b/modules/perception/lidar/lib/roi_filter/roi_service_filter/roi_service_filter_test.cc index fa40f0193d3a58aa5151fc8b68588f791c725390..1db82df18b175fb9360656e24a6a6b93f1b09b79 100644 --- a/modules/perception/lidar/lib/roi_filter/roi_service_filter/roi_service_filter_test.cc +++ b/modules/perception/lidar/lib/roi_filter/roi_service_filter/roi_service_filter_test.cc @@ -49,9 +49,7 @@ class LidarLibROIServiceFilterTest : public testing::Test { FLAGS_work_root = "/apollo/modules/perception/testdata/" "lidar/lib/roi_filter/roi_service_filter"; FLAGS_config_manager_path = "./conf"; - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - config_manager->Reset(); + lib::ConfigManager::Instance()->Reset(); map::HDMapInput* hdmap_input = lib::Singleton::get_instance(); diff --git a/modules/perception/lidar/lib/scene_manager/ground_service/ground_service.cc b/modules/perception/lidar/lib/scene_manager/ground_service/ground_service.cc index 758496518044c8f6464506cbb8e17381b76e2998..515c9542dc13d3a6c7a6d63cdf6c74309575e5cc 100644 --- a/modules/perception/lidar/lib/scene_manager/ground_service/ground_service.cc +++ b/modules/perception/lidar/lib/scene_manager/ground_service/ground_service.cc @@ -137,9 +137,7 @@ bool GroundService::Init(const SceneServiceInitOptions& options) { dynamic_cast(self_content_.get()); // initialize ground service content from config manager and proto // including resolution, grid size, ... - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); + auto& config_manager = lib::ConfigManager::Instance(); const lib::ModelConfig* model_config = nullptr; CHECK(config_manager->GetModelConfig(Name(), &model_config)) << "Failed to get model config: SceneManager"; diff --git a/modules/perception/lidar/lib/scene_manager/roi_service/roi_service.cc b/modules/perception/lidar/lib/scene_manager/roi_service/roi_service.cc index 82e2a41ca2fda8457d219f219fcd3aa4853ca053..b8f4f315655b7af6d9f047645fc3ebb42a4114e4 100644 --- a/modules/perception/lidar/lib/scene_manager/roi_service/roi_service.cc +++ b/modules/perception/lidar/lib/scene_manager/roi_service/roi_service.cc @@ -83,9 +83,7 @@ bool ROIServiceContent::Check(const Eigen::Vector3d& world_point) const { bool ROIService::Init(const SceneServiceInitOptions& options) { self_content_.reset(new ROIServiceContent); roi_content_ref_ = dynamic_cast(self_content_.get()); - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); + auto& config_manager = lib::ConfigManager::Instance(); const lib::ModelConfig* model_config = nullptr; CHECK(config_manager->GetModelConfig(Name(), &model_config)); const std::string work_root = config_manager->work_root(); diff --git a/modules/perception/lidar/lib/scene_manager/scene_manager.cc b/modules/perception/lidar/lib/scene_manager/scene_manager.cc index 7c7fdd9ed58915ffa72b38f8cfb8b435bd1f0df4..502152ad3b54ba83611224498d5a81a4218cb169 100644 --- a/modules/perception/lidar/lib/scene_manager/scene_manager.cc +++ b/modules/perception/lidar/lib/scene_manager/scene_manager.cc @@ -30,9 +30,7 @@ bool SceneManager::InitInternal(const SceneManagerInitOptions& options) { if (initialized_) { return true; } - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); + auto& config_manager = lib::ConfigManager::Instance(); const lib::ModelConfig* model_config = nullptr; CHECK(config_manager->GetModelConfig(Name(), &model_config)); const std::string work_root = config_manager->work_root(); diff --git a/modules/perception/lidar/lib/scene_manager/scene_manager_test.cc b/modules/perception/lidar/lib/scene_manager/scene_manager_test.cc index b3a427b307f3a340ff131e2b7c6a6db3112942c5..89c7406c1e071e4e51d5d99355bebcc5236d6d13 100644 --- a/modules/perception/lidar/lib/scene_manager/scene_manager_test.cc +++ b/modules/perception/lidar/lib/scene_manager/scene_manager_test.cc @@ -43,9 +43,7 @@ class LidarLibSceneManagerTest : public testing::Test { FLAGS_work_root = "/apollo/modules/perception/testdata/lidar/lib/scene_manager"; FLAGS_config_manager_path = "./conf"; - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - config_manager->Reset(); + lib::ConfigManager::Instance()->Reset(); map::HDMapInput* hdmap_input = lib::Singleton::get_instance(); diff --git a/modules/perception/lidar/lib/segmentation/cnnseg/cnn_segmentation.cc b/modules/perception/lidar/lib/segmentation/cnnseg/cnn_segmentation.cc index 9d261570dfeaacc9f2ec54040943019225ad5801..5038ad0b7b21cfec09fdb31d74351c77113641a4 100644 --- a/modules/perception/lidar/lib/segmentation/cnnseg/cnn_segmentation.cc +++ b/modules/perception/lidar/lib/segmentation/cnnseg/cnn_segmentation.cc @@ -425,9 +425,7 @@ bool CNNSegmentation::GetConfigs(std::string* param_file, std::string* proto_file, std::string* weight_file, std::string* engine_file) { - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); + auto& config_manager = lib::ConfigManager::Instance(); const lib::ModelConfig* model_config = nullptr; CHECK(config_manager->GetModelConfig("CNNSegmentation", &model_config)) << "Failed to get model config: CNNSegmentation"; diff --git a/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_engine.cc b/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_engine.cc index a38af006bc2b224dbbf6e453c66ed5ea8bd8cc61..a5ce372c57adf22d64eda2bb557109abda661515 100644 --- a/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_engine.cc +++ b/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_engine.cc @@ -29,9 +29,7 @@ namespace perception { namespace lidar { bool MlfEngine::Init(const MultiTargetTrackerInitOptions& options) { - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); + auto& config_manager = lib::ConfigManager::Instance(); const lib::ModelConfig* model_config = nullptr; CHECK(config_manager->GetModelConfig(Name(), &model_config)); const std::string work_root = config_manager->work_root(); diff --git a/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_motion_filter.cc b/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_motion_filter.cc index d41a36fc176991edec6b65a2b220bc9851c8b1a5..4b8b774a6b34f23f935f20a50615f510c7a87604 100644 --- a/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_motion_filter.cc +++ b/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_motion_filter.cc @@ -30,9 +30,7 @@ namespace perception { namespace lidar { bool MlfMotionFilter::Init(const MlfFilterInitOptions& options) { - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); + auto& config_manager = lib::ConfigManager::Instance(); const lib::ModelConfig* model_config = nullptr; CHECK(config_manager->GetModelConfig(Name(), &model_config)); const std::string work_root = config_manager->work_root(); diff --git a/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_motion_refiner.cc b/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_motion_refiner.cc index 7c70a85afac42bfc994d27e117851371d72a3a7e..9785646ff4c7d2ef615a80a6b5ffa8877d96c70f 100644 --- a/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_motion_refiner.cc +++ b/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_motion_refiner.cc @@ -29,9 +29,7 @@ namespace perception { namespace lidar { bool MlfMotionRefiner::Init(const MlfMotionRefinerInitOptions& options) { - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); + auto& config_manager = lib::ConfigManager::Instance(); const lib::ModelConfig* model_config = nullptr; CHECK(config_manager->GetModelConfig(Name(), &model_config)); const std::string work_root = config_manager->work_root(); diff --git a/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_shape_filter.cc b/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_shape_filter.cc index 95f575fdca100da2e8574dc2be2bba96d2307085..765fa3f2eee1fe77311ba902d517c74e2fbf9c2c 100644 --- a/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_shape_filter.cc +++ b/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_shape_filter.cc @@ -28,9 +28,7 @@ namespace perception { namespace lidar { bool MlfShapeFilter::Init(const MlfFilterInitOptions& options) { - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); + auto& config_manager = lib::ConfigManager::Instance(); const lib::ModelConfig* model_config = nullptr; CHECK(config_manager->GetModelConfig(Name(), &model_config)); const std::string work_root = config_manager->work_root(); diff --git a/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_track_object_distance.cc b/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_track_object_distance.cc index 0ffeab8310a8d1a076bdf8c3b3cdcd44bae15925..5a36a3153bf4c5f3572c38fd354afaf976b73733 100644 --- a/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_track_object_distance.cc +++ b/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_track_object_distance.cc @@ -41,9 +41,7 @@ const std::vector MlfTrackObjectDistance::kBackgroundDefaultWeight = { bool MlfTrackObjectDistance::Init( const MlfTrackObjectDistanceInitOptions& options) { - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); + auto& config_manager = lib::ConfigManager::Instance(); const lib::ModelConfig* model_config = nullptr; CHECK(config_manager->GetModelConfig(Name(), &model_config)); const std::string work_root = config_manager->work_root(); diff --git a/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_track_object_matcher.cc b/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_track_object_matcher.cc index 208eedc3b0f1116de13f30b933a3a13ead1c8731..6e9d2da64a1b918db9e8b68e677aa57f810822ea 100644 --- a/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_track_object_matcher.cc +++ b/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_track_object_matcher.cc @@ -29,9 +29,7 @@ namespace lidar { bool MlfTrackObjectMatcher::Init( const MlfTrackObjectMatcherInitOptions &options) { - lib::ConfigManager *config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); + auto& config_manager = lib::ConfigManager::Instance(); const lib::ModelConfig *model_config = nullptr; CHECK(config_manager->GetModelConfig(Name(), &model_config)); const std::string work_root = config_manager->work_root(); diff --git a/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_tracker.cc b/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_tracker.cc index 497f5d3b3a74f49253ec012f1db91fcffb415417..ed1d404687a6996ad40ec763014d4fb0c11f7f48 100644 --- a/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_tracker.cc +++ b/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_tracker.cc @@ -26,9 +26,7 @@ namespace perception { namespace lidar { bool MlfTracker::Init(const MlfTrackerInitOptions options) { - lib::ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); + auto& config_manager = lib::ConfigManager::Instance(); const lib::ModelConfig* model_config = nullptr; CHECK(config_manager->GetModelConfig(Name(), &model_config)); const std::string work_root = config_manager->work_root(); diff --git a/modules/perception/lidar/tools/offline_lidar_obstacle_perception.cc b/modules/perception/lidar/tools/offline_lidar_obstacle_perception.cc index 503f767861c07508f47a592888f5c6e59f081210..94541bb72f5183369475ff9ff858ceede5b85fe3 100644 --- a/modules/perception/lidar/tools/offline_lidar_obstacle_perception.cc +++ b/modules/perception/lidar/tools/offline_lidar_obstacle_perception.cc @@ -62,13 +62,8 @@ class OfflineLidarObstaclePerception { bool setup() { FLAGS_config_manager_path = "./conf"; - config_manager_ = lib::Singleton::get_instance(); - if (config_manager_ == nullptr) { - AERROR << "Failed to get ConfigManager instance."; - return false; - } - if (!config_manager_->Init()) { - AERROR << "Failed to int ConfigManage."; + if (!lib::ConfigManager::Instance()->Init()) { + AERROR << "Failed to init ConfigManage."; return false; } lidar_segmentation_.reset(new LidarObstacleSegmentation); @@ -325,7 +320,6 @@ class OfflineLidarObstaclePerception { protected: std::string output_dir_; - lib::ConfigManager* config_manager_ = nullptr; std::shared_ptr frame_; LidarObstacleSegmentationInitOptions segment_init_options_; LidarObstacleSegmentationOptions segment_options_; diff --git a/modules/perception/map/hdmap/hdmap_input.cc b/modules/perception/map/hdmap/hdmap_input.cc index 5033bba024f36a7051da7930aa63e43aab4d0520..980fd406c81b96a1977c51ce029c516819b3cc90 100644 --- a/modules/perception/map/hdmap/hdmap_input.cc +++ b/modules/perception/map/hdmap/hdmap_input.cc @@ -41,7 +41,6 @@ using apollo::hdmap::JunctionBoundaryPtr; using apollo::hdmap::LineBoundary; using apollo::hdmap::SignalInfoConstPtr; using apollo::hdmap::LaneInfoConstPtr; -using lib::ConfigManager; using base::PolygonDType; using base::PointD; @@ -74,12 +73,10 @@ bool HDMapInput::Reset() { bool HDMapInput::InitHDMap() { hdmap_.reset(new apollo::hdmap::HDMap()); - ConfigManager* config_manager = - lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); std::string model_name = "HDMapInput"; const lib::ModelConfig* model_config = nullptr; - if (!config_manager->GetModelConfig(model_name, &model_config)) { + if (!lib::ConfigManager::Instance()->GetModelConfig(model_name, + &model_config)) { AERROR << "not found model: " << model_name; return false; } diff --git a/modules/perception/map/hdmap/hdmap_input_test.cc b/modules/perception/map/hdmap/hdmap_input_test.cc index abab5a36b3b09e85ff65af71c2eb8975d856b365..0e4643bf2d75cf43c186c619d0c0c01c23cdc1eb 100644 --- a/modules/perception/map/hdmap/hdmap_input_test.cc +++ b/modules/perception/map/hdmap/hdmap_input_test.cc @@ -26,7 +26,6 @@ namespace apollo { namespace perception { namespace map { -// using apollo::perception::lib::ConfigManager; // using adu::hdmap::JunctionInfo; // using adu::hdmap::JunctionInfoConstPtr; // using adu::hdmap::RoiRoadBoundaryPtr; diff --git a/modules/perception/radar/app/radar_obstacle_perception.cc b/modules/perception/radar/app/radar_obstacle_perception.cc index f53563198882488c8fd2775357366f3f33e47c6a..13492483fc642b9c59db3c10614255bf9c774a6e 100644 --- a/modules/perception/radar/app/radar_obstacle_perception.cc +++ b/modules/perception/radar/app/radar_obstacle_perception.cc @@ -29,11 +29,9 @@ namespace perception { namespace radar { bool RadarObstaclePerception::Init(const std::string& pipeline_name) { - ConfigManager* config_manager = lib::Singleton::get_instance(); - CHECK_NOTNULL(config_manager); std::string model_name = pipeline_name; const ModelConfig* model_config = nullptr; - CHECK(config_manager->GetModelConfig(model_name, &model_config)) + CHECK(ConfigManager::Instance()->GetModelConfig(model_name, &model_config)) << "not found model: " << model_name; std::string detector_name; diff --git a/modules/perception/radar/lib/preprocessor/conti_ars_preprocessor/conti_ars_preprocessor.cc b/modules/perception/radar/lib/preprocessor/conti_ars_preprocessor/conti_ars_preprocessor.cc index b02a51ffb57fa1ccca10d6bf31e3d8180f1ffd1e..7a3108774796bed5e8fcd9f37d810a7356ebf4ae 100644 --- a/modules/perception/radar/lib/preprocessor/conti_ars_preprocessor/conti_ars_preprocessor.cc +++ b/modules/perception/radar/lib/preprocessor/conti_ars_preprocessor/conti_ars_preprocessor.cc @@ -24,11 +24,10 @@ int ContiArsPreprocessor::current_idx_ = 0; int ContiArsPreprocessor::local2global_[ORIGIN_CONTI_MAX_ID_NUM] = {0}; bool ContiArsPreprocessor::Init() { - lib::ConfigManager* config_manager - = lib::Singleton::get_instance(); std::string model_name = "ContiArsPreprocessor"; const lib::ModelConfig* model_config = nullptr; - CHECK(config_manager->GetModelConfig(model_name, &model_config)); + CHECK(lib::ConfigManager::Instance()->GetModelConfig(model_name, + &model_config)); CHECK(model_config->get_value("delay_time", &delay_time_)); return true; } diff --git a/modules/perception/radar/lib/tracker/conti_ars_tracker/conti_ars_tracker.cc b/modules/perception/radar/lib/tracker/conti_ars_tracker/conti_ars_tracker.cc index 839c3f52efd3dbc6bea710995ba213597e8d7629..b2b3170aa3216d09083be6df9262287ebee1b88f 100644 --- a/modules/perception/radar/lib/tracker/conti_ars_tracker/conti_ars_tracker.cc +++ b/modules/perception/radar/lib/tracker/conti_ars_tracker/conti_ars_tracker.cc @@ -36,12 +36,11 @@ ContiArsTracker::~ContiArsTracker() { } bool ContiArsTracker::Init() { - lib::ConfigManager *config_manager = - lib::Singleton::get_instance(); std::string model_name = name_; const lib::ModelConfig *model_config = nullptr; bool state = true; - if (!config_manager->GetModelConfig(model_name, &model_config)) { + if (!lib::ConfigManager::Instance()->GetModelConfig(model_name, + &model_config)) { AERROR << "not found model: " << model_name; state = false; } diff --git a/modules/perception/radar/lib/tracker/matcher/hm_matcher.cc b/modules/perception/radar/lib/tracker/matcher/hm_matcher.cc index db907a8530b74b37f48e6b97ca359aa6793faa01..8268d1187ac9f9b6c7dfa10c40822aadcb4e51ce 100644 --- a/modules/perception/radar/lib/tracker/matcher/hm_matcher.cc +++ b/modules/perception/radar/lib/tracker/matcher/hm_matcher.cc @@ -14,9 +14,11 @@ * limitations under the License. *****************************************************************************/ #include "modules/perception/radar/lib/tracker/matcher/hm_matcher.h" + +#include #include #include -#include + #include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/perception/lib/io/file_util.h" @@ -25,11 +27,13 @@ namespace apollo { namespace perception { namespace radar { + HMMatcher::HMMatcher() { name_ = "HMMatcher"; } + HMMatcher::~HMMatcher() {} + bool HMMatcher::Init() { - lib::ConfigManager *config_manager = - lib::Singleton::get_instance(); + auto& config_manager = lib::ConfigManager::Instance(); std::string model_name = name_; const lib::ModelConfig *model_config = nullptr; AINFO << "matcher name: " << name_;