Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
464db2b4
A
apollo
项目概览
Pinoxchio
/
apollo
与 Fork 源项目一致
从无法访问的项目Fork
通知
2
Star
0
Fork
0
代码
文件
提交
分支
Tags
贡献者
分支图
Diff
Issue
0
列表
看板
标记
里程碑
合并请求
0
Wiki
0
Wiki
分析
仓库
DevOps
项目成员
Pages
A
apollo
项目概览
项目概览
详情
发布
仓库
仓库
文件
提交
分支
标签
贡献者
分支图
比较
Issue
0
Issue
0
列表
看板
标记
里程碑
合并请求
0
合并请求
0
Pages
分析
分析
仓库分析
DevOps
Wiki
0
Wiki
成员
成员
收起侧边栏
关闭侧边栏
动态
分支图
创建新Issue
提交
Issue看板
前往新版Gitcode,体验更适合开发者的 AI 搜索 >>
提交
464db2b4
编写于
11月 09, 2018
作者:
A
Aaron Xiao
提交者:
Jiangtao Hu
12月 13, 2018
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
Perception: Migrate ConfigManager to cyber Singleton.
上级
117043cf
变更
43
隐藏空白更改
内联
并排
Showing
43 changed file
with
61 addition
and
171 deletion
+61
-171
modules/perception/common/sensor_manager/sensor_manager.cc
modules/perception/common/sensor_manager/sensor_manager.cc
+1
-4
modules/perception/fusion/base/base_init_options.cc
modules/perception/fusion/base/base_init_options.cc
+2
-4
modules/perception/fusion/lib/data_fusion/existance_fusion/dst_existance_fusion/dst_existance_fusion.cc
...tance_fusion/dst_existance_fusion/dst_existance_fusion.cc
+1
-4
modules/perception/fusion/lib/data_fusion/tracker/pbf_tracker/pbf_tracker.cc
...fusion/lib/data_fusion/tracker/pbf_tracker/pbf_tracker.cc
+1
-4
modules/perception/fusion/lib/data_fusion/type_fusion/dst_type_fusion/dst_type_fusion.cc
...ata_fusion/type_fusion/dst_type_fusion/dst_type_fusion.cc
+1
-4
modules/perception/fusion/lib/fusion_system/probabilistic_fusion/probabilistic_fusion.cc
...usion_system/probabilistic_fusion/probabilistic_fusion.cc
+1
-4
modules/perception/fusion/lib/gatekeeper/pbf_gatekeeper/pbf_gatekeeper.cc
...on/fusion/lib/gatekeeper/pbf_gatekeeper/pbf_gatekeeper.cc
+1
-4
modules/perception/lib/config_manager/config_manager.h
modules/perception/lib/config_manager/config_manager.h
+5
-28
modules/perception/lib/config_manager/config_manager_test.cc
modules/perception/lib/config_manager/config_manager_test.cc
+2
-2
modules/perception/lidar/app/lidar_obstacle_segmentation.cc
modules/perception/lidar/app/lidar_obstacle_segmentation.cc
+1
-3
modules/perception/lidar/app/lidar_obstacle_tracking.cc
modules/perception/lidar/app/lidar_obstacle_tracking.cc
+1
-3
modules/perception/lidar/lib/classifier/fused_classifier/ccrf_type_fusion.cc
...lidar/lib/classifier/fused_classifier/ccrf_type_fusion.cc
+2
-6
modules/perception/lidar/lib/classifier/fused_classifier/fused_classifier.cc
...lidar/lib/classifier/fused_classifier/fused_classifier.cc
+1
-3
modules/perception/lidar/lib/classifier/fused_classifier/fused_classifier_test.cc
.../lib/classifier/fused_classifier/fused_classifier_test.cc
+0
-1
modules/perception/lidar/lib/ground_detector/ground_service_detector/ground_service_detector.cc
...tector/ground_service_detector/ground_service_detector.cc
+1
-3
modules/perception/lidar/lib/ground_detector/ground_service_detector/ground_service_detector_test.cc
...r/ground_service_detector/ground_service_detector_test.cc
+1
-3
modules/perception/lidar/lib/ground_detector/spatio_temporal_ground_detector/spatio_temporal_ground_detector.cc
...mporal_ground_detector/spatio_temporal_ground_detector.cc
+3
-5
modules/perception/lidar/lib/map_manager/map_manager.cc
modules/perception/lidar/lib/map_manager/map_manager.cc
+1
-3
modules/perception/lidar/lib/map_manager/map_manager_test.cc
modules/perception/lidar/lib/map_manager/map_manager_test.cc
+2
-6
modules/perception/lidar/lib/object_filter_bank/object_filter_bank.cc
...eption/lidar/lib/object_filter_bank/object_filter_bank.cc
+1
-3
modules/perception/lidar/lib/object_filter_bank/roi_boundary_filter/roi_boundary_filter.cc
...ct_filter_bank/roi_boundary_filter/roi_boundary_filter.cc
+1
-3
modules/perception/lidar/lib/pointcloud_preprocessor/pointcloud_preprocessor.cc
...ar/lib/pointcloud_preprocessor/pointcloud_preprocessor.cc
+1
-3
modules/perception/lidar/lib/roi_filter/hdmap_roi_filter/hdmap_roi_filter.cc
...lidar/lib/roi_filter/hdmap_roi_filter/hdmap_roi_filter.cc
+1
-3
modules/perception/lidar/lib/roi_filter/roi_service_filter/roi_service_filter_test.cc
.../roi_filter/roi_service_filter/roi_service_filter_test.cc
+1
-3
modules/perception/lidar/lib/scene_manager/ground_service/ground_service.cc
.../lidar/lib/scene_manager/ground_service/ground_service.cc
+1
-3
modules/perception/lidar/lib/scene_manager/roi_service/roi_service.cc
...eption/lidar/lib/scene_manager/roi_service/roi_service.cc
+1
-3
modules/perception/lidar/lib/scene_manager/scene_manager.cc
modules/perception/lidar/lib/scene_manager/scene_manager.cc
+1
-3
modules/perception/lidar/lib/scene_manager/scene_manager_test.cc
.../perception/lidar/lib/scene_manager/scene_manager_test.cc
+1
-3
modules/perception/lidar/lib/segmentation/cnnseg/cnn_segmentation.cc
...ception/lidar/lib/segmentation/cnnseg/cnn_segmentation.cc
+1
-3
modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_engine.cc
...eption/lidar/lib/tracker/multi_lidar_fusion/mlf_engine.cc
+1
-3
modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_motion_filter.cc
...lidar/lib/tracker/multi_lidar_fusion/mlf_motion_filter.cc
+1
-3
modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_motion_refiner.cc
...idar/lib/tracker/multi_lidar_fusion/mlf_motion_refiner.cc
+1
-3
modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_shape_filter.cc
.../lidar/lib/tracker/multi_lidar_fusion/mlf_shape_filter.cc
+1
-3
modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_track_object_distance.cc
...b/tracker/multi_lidar_fusion/mlf_track_object_distance.cc
+1
-3
modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_track_object_matcher.cc
...ib/tracker/multi_lidar_fusion/mlf_track_object_matcher.cc
+1
-3
modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_tracker.cc
...ption/lidar/lib/tracker/multi_lidar_fusion/mlf_tracker.cc
+1
-3
modules/perception/lidar/tools/offline_lidar_obstacle_perception.cc
...rception/lidar/tools/offline_lidar_obstacle_perception.cc
+2
-8
modules/perception/map/hdmap/hdmap_input.cc
modules/perception/map/hdmap/hdmap_input.cc
+2
-5
modules/perception/map/hdmap/hdmap_input_test.cc
modules/perception/map/hdmap/hdmap_input_test.cc
+0
-1
modules/perception/radar/app/radar_obstacle_perception.cc
modules/perception/radar/app/radar_obstacle_perception.cc
+1
-3
modules/perception/radar/lib/preprocessor/conti_ars_preprocessor/conti_ars_preprocessor.cc
...rocessor/conti_ars_preprocessor/conti_ars_preprocessor.cc
+2
-3
modules/perception/radar/lib/tracker/conti_ars_tracker/conti_ars_tracker.cc
.../radar/lib/tracker/conti_ars_tracker/conti_ars_tracker.cc
+2
-3
modules/perception/radar/lib/tracker/matcher/hm_matcher.cc
modules/perception/radar/lib/tracker/matcher/hm_matcher.cc
+7
-3
未找到文件。
modules/perception/common/sensor_manager/sensor_manager.cc
浏览文件 @
464db2b4
...
...
@@ -47,11 +47,8 @@ bool SensorManager::Init() {
distort_model_map_
.
clear
();
undistort_model_map_
.
clear
();
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
))
{
...
...
modules/perception/fusion/base/base_init_options.cc
浏览文件 @
464db2b4
...
...
@@ -26,11 +26,9 @@ namespace fusion {
bool
GetFusionInitOptions
(
const
std
::
string
&
module_name
,
BaseInitOptions
*
options
)
{
CHECK_NOTNULL
(
options
);
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
))
&&
...
...
modules/perception/fusion/lib/data_fusion/existance_fusion/dst_existance_fusion/dst_existance_fusion.cc
浏览文件 @
464db2b4
...
...
@@ -49,11 +49,8 @@ bool DstExistanceFusion::Init() {
return
false
;
}
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
);
...
...
modules/perception/fusion/lib/data_fusion/tracker/pbf_tracker/pbf_tracker.cc
浏览文件 @
464db2b4
...
...
@@ -44,11 +44,8 @@ bool PbfTracker::InitParams() {
return
false
;
}
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
);
...
...
modules/perception/fusion/lib/data_fusion/type_fusion/dst_type_fusion/dst_type_fusion.cc
浏览文件 @
464db2b4
...
...
@@ -72,11 +72,8 @@ bool DstTypeFusion::Init() {
return
false
;
}
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
);
...
...
modules/perception/fusion/lib/fusion_system/probabilistic_fusion/probabilistic_fusion.cc
浏览文件 @
464db2b4
...
...
@@ -52,11 +52,8 @@ bool ProbabilisticFusion::Init(const FusionInitOptions& init_options) {
return
false
;
}
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
);
...
...
modules/perception/fusion/lib/gatekeeper/pbf_gatekeeper/pbf_gatekeeper.cc
浏览文件 @
464db2b4
...
...
@@ -38,11 +38,8 @@ bool PbfGatekeeper::Init() {
return
false
;
}
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
);
...
...
modules/perception/lib/config_manager/config_manager.h
浏览文件 @
464db2b4
...
...
@@ -119,7 +119,7 @@
#include <utility>
#include <vector>
#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
<
ConfigManager
>
;
/* TODO(all): to remove
typedef std::map<std::string, ModelConfig *> ModelConfigMap;
typedef ModelConfigMap::iterator ModelConfigMapIterator;
typedef ModelConfigMap::const_iterator ModelConfigMapConstIterator;
*/
// key: model_name
std
::
map
<
std
::
string
,
ModelConfig
*>
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<std::string, int> IntegerParamMap;
typedef std::map<std::string, std::string> StringParamMap;
typedef std::map<std::string, double> DoubleParamMap;
typedef std::map<std::string, float> FloatParamMap;
typedef std::map<std::string, bool> BoolParamMap;
typedef std::map<std::string, std::vector<int>> ArrayIntegerParamMap;
typedef std::map<std::string, std::vector<std::string>> ArrayStringParamMap;
typedef std::map<std::string, std::vector<double>> ArrayDoubleParamMap;
typedef std::map<std::string, std::vector<float>> ArrayFloatParamMap;
typedef std::map<std::string, std::vector<bool>> ArrayBoolParamMap;
*/
std
::
map
<
std
::
string
,
int
>
integer_param_map_
;
std
::
map
<
std
::
string
,
std
::
string
>
string_param_map_
;
std
::
map
<
std
::
string
,
double
>
double_param_map_
;
...
...
modules/perception/lib/config_manager/config_manager_test.cc
浏览文件 @
464db2b4
...
...
@@ -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
<
ConfigManager
>::
get_i
nstance
();
config_manager_
=
ConfigManager
::
I
nstance
();
ASSERT_TRUE
(
config_manager_
!=
nullptr
);
}
protected:
ConfigManager
*
config_manager_
;
std
::
shared_ptr
<
ConfigManager
>
config_manager_
;
};
TEST_F
(
ConfigManagerTest
,
TestInit
)
{
...
...
modules/perception/lidar/app/lidar_obstacle_segmentation.cc
浏览文件 @
464db2b4
...
...
@@ -30,9 +30,7 @@ namespace lidar {
bool
LidarObstacleSegmentation
::
Init
(
const
LidarObstacleSegmentationInitOptions
&
options
)
{
auto
&
sensor_name
=
options
.
sensor_name
;
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
));
...
...
modules/perception/lidar/app/lidar_obstacle_tracking.cc
浏览文件 @
464db2b4
...
...
@@ -29,9 +29,7 @@ namespace lidar {
bool
LidarObstacleTracking
::
Init
(
const
LidarObstacleTrackingInitOptions
&
options
)
{
auto
&
sensor_name
=
options
.
sensor_name
;
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
));
...
...
modules/perception/lidar/lib/classifier/fused_classifier/ccrf_type_fusion.cc
浏览文件 @
464db2b4
...
...
@@ -34,9 +34,7 @@ using ObjectPtr = std::shared_ptr<apollo::perception::base::Object>;
using
apollo
::
perception
::
base
::
ObjectType
;
bool
CCRFOneShotTypeFusion
::
Init
(
const
TypeFusionInitOption
&
option
)
{
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
<
lib
::
ConfigManager
>::
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
();
...
...
modules/perception/lidar/lib/classifier/fused_classifier/fused_classifier.cc
浏览文件 @
464db2b4
...
...
@@ -28,9 +28,7 @@ using ObjectPtr = std::shared_ptr<apollo::perception::base::Object>;
using
apollo
::
perception
::
base
::
ObjectType
;
bool
FusedClassifier
::
Init
(
const
ClassifierInitOptions
&
options
)
{
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
();
...
...
modules/perception/lidar/lib/classifier/fused_classifier/fused_classifier_test.cc
浏览文件 @
464db2b4
...
...
@@ -71,7 +71,6 @@ class FusedClassifierTest : public testing::Test {
std
::
vector
<
double
>
timestamps_
;
static
const
size_t
kSequenceLength
;
static
const
size_t
kObjectNum
;
lib
::
ConfigManager
*
config_manager_
;
};
const
size_t
FusedClassifierTest
::
kSequenceLength
=
10
;
...
...
modules/perception/lidar/lib/ground_detector/ground_service_detector/ground_service_detector.cc
浏览文件 @
464db2b4
...
...
@@ -27,9 +27,7 @@ namespace perception {
namespace
lidar
{
bool
GroundServiceDetector
::
Init
(
const
GroundDetectorInitOptions
&
options
)
{
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
));
...
...
modules/perception/lidar/lib/ground_detector/ground_service_detector/ground_service_detector_test.cc
浏览文件 @
464db2b4
...
...
@@ -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
<
lib
::
ConfigManager
>::
get_instance
();
config_manager
->
Reset
();
lib
::
ConfigManager
::
Instance
()
->
Reset
();
}
void
TearDown
()
{}
...
...
modules/perception/lidar/lib/ground_detector/spatio_temporal_ground_detector/spatio_temporal_ground_detector.cc
浏览文件 @
464db2b4
...
...
@@ -32,12 +32,10 @@ using apollo::common::util::GetProtoFromFile;
bool
SpatioTemporalGroundDetector
::
Init
(
const
GroundDetectorInitOptions
&
options
)
{
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
();
...
...
modules/perception/lidar/lib/map_manager/map_manager.cc
浏览文件 @
464db2b4
...
...
@@ -28,9 +28,7 @@ namespace perception {
namespace
lidar
{
bool
MapManager
::
Init
(
const
MapManagerInitOptions
&
options
)
{
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
();
...
...
modules/perception/lidar/lib/map_manager/map_manager_test.cc
浏览文件 @
464db2b4
...
...
@@ -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
<
lib
::
ConfigManager
>::
get_instance
();
config_manager
->
Reset
();
lib
::
ConfigManager
::
Instance
()
->
Reset
();
map
::
HDMapInput
*
hdmap_input
=
lib
::
Singleton
<
map
::
HDMapInput
>::
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
<
lib
::
ConfigManager
>::
get_instance
();
config_manager
->
Reset
();
lib
::
ConfigManager
::
Instance
()
->
Reset
();
map
::
HDMapInput
*
hdmap_input
=
lib
::
Singleton
<
map
::
HDMapInput
>::
get_instance
();
...
...
modules/perception/lidar/lib/object_filter_bank/object_filter_bank.cc
浏览文件 @
464db2b4
...
...
@@ -26,9 +26,7 @@ namespace perception {
namespace
lidar
{
bool
ObjectFilterBank
::
Init
(
const
ObjectFilterInitOptions
&
options
)
{
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
();
...
...
modules/perception/lidar/lib/object_filter_bank/roi_boundary_filter/roi_boundary_filter.cc
浏览文件 @
464db2b4
...
...
@@ -29,9 +29,7 @@ namespace lidar {
using
apollo
::
perception
::
base
::
PointD
;
bool
ROIBoundaryFilter
::
Init
(
const
ObjectFilterInitOptions
&
options
)
{
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
();
...
...
modules/perception/lidar/lib/pointcloud_preprocessor/pointcloud_preprocessor.cc
浏览文件 @
464db2b4
...
...
@@ -33,9 +33,7 @@ const float PointCloudPreprocessor::kPointInfThreshold = 1e3;
bool
PointCloudPreprocessor
::
Init
(
const
PointCloudPreprocessorInitOptions
&
options
)
{
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
();
...
...
modules/perception/lidar/lib/roi_filter/hdmap_roi_filter/hdmap_roi_filter.cc
浏览文件 @
464db2b4
...
...
@@ -39,9 +39,7 @@ using Polygon = typename PolygonScanCvter<T>::Polygon;
bool
HdmapROIFilter
::
Init
(
const
ROIFilterInitOptions
&
options
)
{
// load model config
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
();
...
...
modules/perception/lidar/lib/roi_filter/roi_service_filter/roi_service_filter_test.cc
浏览文件 @
464db2b4
...
...
@@ -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
<
lib
::
ConfigManager
>::
get_instance
();
config_manager
->
Reset
();
lib
::
ConfigManager
::
Instance
()
->
Reset
();
map
::
HDMapInput
*
hdmap_input
=
lib
::
Singleton
<
map
::
HDMapInput
>::
get_instance
();
...
...
modules/perception/lidar/lib/scene_manager/ground_service/ground_service.cc
浏览文件 @
464db2b4
...
...
@@ -137,9 +137,7 @@ bool GroundService::Init(const SceneServiceInitOptions& options) {
dynamic_cast
<
GroundServiceContent
*>
(
self_content_
.
get
());
// initialize ground service content from config manager and proto
// including resolution, grid size, ...
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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"
;
...
...
modules/perception/lidar/lib/scene_manager/roi_service/roi_service.cc
浏览文件 @
464db2b4
...
...
@@ -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
<
ROIServiceContent
*>
(
self_content_
.
get
());
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
();
...
...
modules/perception/lidar/lib/scene_manager/scene_manager.cc
浏览文件 @
464db2b4
...
...
@@ -30,9 +30,7 @@ bool SceneManager::InitInternal(const SceneManagerInitOptions& options) {
if
(
initialized_
)
{
return
true
;
}
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
();
...
...
modules/perception/lidar/lib/scene_manager/scene_manager_test.cc
浏览文件 @
464db2b4
...
...
@@ -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
<
lib
::
ConfigManager
>::
get_instance
();
config_manager
->
Reset
();
lib
::
ConfigManager
::
Instance
()
->
Reset
();
map
::
HDMapInput
*
hdmap_input
=
lib
::
Singleton
<
map
::
HDMapInput
>::
get_instance
();
...
...
modules/perception/lidar/lib/segmentation/cnnseg/cnn_segmentation.cc
浏览文件 @
464db2b4
...
...
@@ -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
<
lib
::
ConfigManager
>::
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"
;
...
...
modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_engine.cc
浏览文件 @
464db2b4
...
...
@@ -29,9 +29,7 @@ namespace perception {
namespace
lidar
{
bool
MlfEngine
::
Init
(
const
MultiTargetTrackerInitOptions
&
options
)
{
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
();
...
...
modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_motion_filter.cc
浏览文件 @
464db2b4
...
...
@@ -30,9 +30,7 @@ namespace perception {
namespace
lidar
{
bool
MlfMotionFilter
::
Init
(
const
MlfFilterInitOptions
&
options
)
{
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
();
...
...
modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_motion_refiner.cc
浏览文件 @
464db2b4
...
...
@@ -29,9 +29,7 @@ namespace perception {
namespace
lidar
{
bool
MlfMotionRefiner
::
Init
(
const
MlfMotionRefinerInitOptions
&
options
)
{
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
();
...
...
modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_shape_filter.cc
浏览文件 @
464db2b4
...
...
@@ -28,9 +28,7 @@ namespace perception {
namespace
lidar
{
bool
MlfShapeFilter
::
Init
(
const
MlfFilterInitOptions
&
options
)
{
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
();
...
...
modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_track_object_distance.cc
浏览文件 @
464db2b4
...
...
@@ -41,9 +41,7 @@ const std::vector<float> MlfTrackObjectDistance::kBackgroundDefaultWeight = {
bool
MlfTrackObjectDistance
::
Init
(
const
MlfTrackObjectDistanceInitOptions
&
options
)
{
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
();
...
...
modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_track_object_matcher.cc
浏览文件 @
464db2b4
...
...
@@ -29,9 +29,7 @@ namespace lidar {
bool
MlfTrackObjectMatcher
::
Init
(
const
MlfTrackObjectMatcherInitOptions
&
options
)
{
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
();
...
...
modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_tracker.cc
浏览文件 @
464db2b4
...
...
@@ -26,9 +26,7 @@ namespace perception {
namespace
lidar
{
bool
MlfTracker
::
Init
(
const
MlfTrackerInitOptions
options
)
{
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
();
...
...
modules/perception/lidar/tools/offline_lidar_obstacle_perception.cc
浏览文件 @
464db2b4
...
...
@@ -62,13 +62,8 @@ class OfflineLidarObstaclePerception {
bool
setup
()
{
FLAGS_config_manager_path
=
"./conf"
;
config_manager_
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
<
LidarFrame
>
frame_
;
LidarObstacleSegmentationInitOptions
segment_init_options_
;
LidarObstacleSegmentationOptions
segment_options_
;
...
...
modules/perception/map/hdmap/hdmap_input.cc
浏览文件 @
464db2b4
...
...
@@ -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
<
ConfigManager
>::
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
;
}
...
...
modules/perception/map/hdmap/hdmap_input_test.cc
浏览文件 @
464db2b4
...
...
@@ -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;
...
...
modules/perception/radar/app/radar_obstacle_perception.cc
浏览文件 @
464db2b4
...
...
@@ -29,11 +29,9 @@ namespace perception {
namespace
radar
{
bool
RadarObstaclePerception
::
Init
(
const
std
::
string
&
pipeline_name
)
{
ConfigManager
*
config_manager
=
lib
::
Singleton
<
ConfigManager
>::
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
;
...
...
modules/perception/radar/lib/preprocessor/conti_ars_preprocessor/conti_ars_preprocessor.cc
浏览文件 @
464db2b4
...
...
@@ -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
<
lib
::
ConfigManager
>::
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
;
}
...
...
modules/perception/radar/lib/tracker/conti_ars_tracker/conti_ars_tracker.cc
浏览文件 @
464db2b4
...
...
@@ -36,12 +36,11 @@ ContiArsTracker::~ContiArsTracker() {
}
bool
ContiArsTracker
::
Init
()
{
lib
::
ConfigManager
*
config_manager
=
lib
::
Singleton
<
lib
::
ConfigManager
>::
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
;
}
...
...
modules/perception/radar/lib/tracker/matcher/hm_matcher.cc
浏览文件 @
464db2b4
...
...
@@ -14,9 +14,11 @@
* limitations under the License.
*****************************************************************************/
#include "modules/perception/radar/lib/tracker/matcher/hm_matcher.h"
#include <iomanip>
#include <string>
#include <utility>
#include <iomanip>
#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
<
lib
::
ConfigManager
>::
get_instance
();
auto
&
config_manager
=
lib
::
ConfigManager
::
Instance
();
std
::
string
model_name
=
name_
;
const
lib
::
ModelConfig
*
model_config
=
nullptr
;
AINFO
<<
"matcher name: "
<<
name_
;
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录