Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
ebfe517e
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 搜索 >>
提交
ebfe517e
编写于
9月 07, 2017
作者:
J
Jun Zhu
提交者:
weidezhang
9月 07, 2017
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
[perception] fix security for CNNSegmentation (#1595)
上级
281f4d99
变更
5
隐藏空白更改
内联
并排
Showing
5 changed file
with
80 addition
and
90 deletion
+80
-90
modules/perception/model/cnn_segmentation/cnnseg.conf
modules/perception/model/cnn_segmentation/cnnseg.conf
+2
-12
modules/perception/obstacle/lidar/segmentation/cnnseg/cnn_segmentation.cc
...on/obstacle/lidar/segmentation/cnnseg/cnn_segmentation.cc
+63
-33
modules/perception/obstacle/lidar/segmentation/cnnseg/feature_generator.cc
...n/obstacle/lidar/segmentation/cnnseg/feature_generator.cc
+11
-18
modules/perception/obstacle/lidar/segmentation/cnnseg/feature_generator.h
...on/obstacle/lidar/segmentation/cnnseg/feature_generator.h
+0
-1
modules/perception/obstacle/lidar/segmentation/cnnseg/proto/cnnseg.proto
...ion/obstacle/lidar/segmentation/cnnseg/proto/cnnseg.proto
+4
-26
未找到文件。
modules/perception/model/cnn_segmentation/cnnseg.conf
浏览文件 @
ebfe517e
...
...
@@ -13,24 +13,14 @@ network_param {
instance_pt_blob
:
"instance_pt"
category_pt_blob
:
"category_score"
confidence_pt_blob
:
"confidence_score"
classify_pt_blob
:
"class_score"
heading_pt_blob
:
"heading_pt"
height_pt_blob
:
"height_pt"
feature_blob
:
"data"
}
feature_param
{
use_max_height
:
true
use_mean_height
:
true
use_log_count
:
true
use_direction
:
true
use_top_intensity
:
true
use_mean_intensity
:
true
use_distance
:
true
use_nonempty
:
true
use_height_filter
:
true
use_dense_feat
:
true
width
:
512
height
:
512
point_cloud_range
:
60
min_height
: -
5
.
0
max_height
:
5
.
0
}
modules/perception/obstacle/lidar/segmentation/cnnseg/cnn_segmentation.cc
浏览文件 @
ebfe517e
...
...
@@ -44,15 +44,28 @@ bool CNNSegmentation::Init() {
auto
network_param
=
cnnseg_param_
.
network_param
();
auto
feature_param
=
cnnseg_param_
.
feature_param
();
range_
=
static_cast
<
float
>
(
feature_param
.
point_cloud_range
());
width_
=
static_cast
<
int
>
(
feature_param
.
width
());
height_
=
static_cast
<
int
>
(
feature_param
.
height
());
if
(
feature_param
.
has_point_cloud_range
())
{
range_
=
static_cast
<
float
>
(
feature_param
.
point_cloud_range
());
}
else
{
range_
=
60.0
;
}
if
(
feature_param
.
has_width
())
{
width_
=
static_cast
<
int
>
(
feature_param
.
width
());
}
else
{
width_
=
512
;
}
if
(
feature_param
.
has_height
())
{
height_
=
static_cast
<
int
>
(
feature_param
.
height
());
}
else
{
height_
=
512
;
}
/// Instantiate Caffe net
/// Instantiate Caffe net
#ifndef USE_CAFFE_GPU
caffe
::
Caffe
::
set_mode
(
caffe
::
Caffe
::
CPU
);
#else
int
gpu_id
=
static_cast
<
int
>
(
cnnseg_param_
.
gpu_id
());
int
gpu_id
=
cnnseg_param_
.
has_gpu_id
()
?
static_cast
<
int
>
(
cnnseg_param_
.
gpu_id
())
:
0
;
CHECK_GE
(
gpu_id
,
0
);
caffe
::
Caffe
::
SetDevice
(
gpu_id
);
caffe
::
Caffe
::
set_mode
(
caffe
::
Caffe
::
GPU
);
...
...
@@ -62,7 +75,6 @@ bool CNNSegmentation::Init() {
caffe_net_
.
reset
(
new
caffe
::
Net
<
float
>
(
proto_file
,
caffe
::
TEST
));
caffe_net_
->
CopyTrainedLayersFrom
(
weight_file
);
AINFO
<<
"confidence threshold = "
<<
cnnseg_param_
.
confidence_thresh
();
#ifndef USE_CAFFE_GPU
AINFO
<<
"using Caffe CPU mode"
;
#else
...
...
@@ -71,34 +83,39 @@ bool CNNSegmentation::Init() {
/// set related Caffe blobs
// center offset prediction
instance_pt_blob_
=
caffe_net_
->
blob_by_name
(
network_param
.
instance_pt_blob
());
CHECK
(
instance_pt_blob_
!=
nullptr
)
<<
"`"
<<
network_param
.
instance_pt_blob
()
string
instance_pt_blob_name
=
network_param
.
has_instance_pt_blob
()
?
network_param
.
instance_pt_blob
()
:
"instance_pt"
;
instance_pt_blob_
=
caffe_net_
->
blob_by_name
(
instance_pt_blob_name
);
CHECK
(
instance_pt_blob_
!=
nullptr
)
<<
"`"
<<
instance_pt_blob_name
<<
"` not exists!"
;
// objectness prediction
category_pt_blob_
=
caffe_net_
->
blob_by_name
(
network_param
.
category_pt_blob
());
CHECK
(
category_pt_blob_
!=
nullptr
)
<<
"`"
<<
network_param
.
category_pt_blob
()
string
category_pt_blob_name
=
network_param
.
has_category_pt_blob
()
?
network_param
.
category_pt_blob
()
:
"category_score"
;
category_pt_blob_
=
caffe_net_
->
blob_by_name
(
category_pt_blob_name
);
CHECK
(
category_pt_blob_
!=
nullptr
)
<<
"`"
<<
category_pt_blob_name
<<
"` not exists!"
;
// positiveness (foreground probability) prediction
confidence_pt_blob_
=
caffe_net_
->
blob_by_name
(
network_param
.
confidence_pt_blob
());
CHECK
(
confidence_pt_blob_
!=
nullptr
)
<<
"`"
<<
network_param
.
confidence_pt_blob
()
// positiveness (foreground object probability) prediction
string
confidence_pt_blob_name
=
network_param
.
has_confidence_pt_blob
()
?
network_param
.
confidence_pt_blob
()
:
"confidence_score"
;
confidence_pt_blob_
=
caffe_net_
->
blob_by_name
(
confidence_pt_blob_name
);
CHECK
(
confidence_pt_blob_
!=
nullptr
)
<<
"`"
<<
confidence_pt_blob_name
<<
"` not exists!"
;
// object height prediction
height_pt_blob_
=
caffe_net_
->
blob_by_name
(
network_param
.
height_pt_blob
());
CHECK
(
height_pt_blob_
!=
nullptr
)
<<
"`"
<<
network_param
.
height_pt_blob
()
string
height_pt_blob_name
=
network_param
.
has_height_pt_blob
()
?
network_param
.
height_pt_blob
()
:
"height_pt"
;
height_pt_blob_
=
caffe_net_
->
blob_by_name
(
height_pt_blob_name
);
CHECK
(
height_pt_blob_
!=
nullptr
)
<<
"`"
<<
height_pt_blob_name
<<
"` not exists!"
;
// raw feature data
feature_blob_
=
caffe_net_
->
blob_by_name
(
network_param
.
feature_blob
());
CHECK
(
feature_blob_
!=
nullptr
)
<<
"`"
<<
network_param
.
feature_blob
()
string
feature_blob_name
=
network_param
.
has_feature_blob
()
?
network_param
.
feature_blob
()
:
"data"
;
feature_blob_
=
caffe_net_
->
blob_by_name
(
feature_blob_name
);
CHECK
(
feature_blob_
!=
nullptr
)
<<
"`"
<<
feature_blob_name
<<
"` not exists!"
;
cluster2d_
.
reset
(
new
cnnseg
::
Cluster2D
());
...
...
@@ -127,7 +144,9 @@ bool CNNSegmentation::Segment(const pcl_util::PointCloudPtr& pc_ptr,
}
use_full_cloud_
=
cnnseg_param_
.
use_full_cloud
()
&&
(
options
.
origin_cloud
!=
nullptr
);
(
cnnseg_param_
.
has_use_full_cloud
()
?
cnnseg_param_
.
use_full_cloud
()
:
false
)
&&
(
options
.
origin_cloud
!=
nullptr
);
PERF_BLOCK_START
();
// generate raw features
...
...
@@ -146,15 +165,26 @@ bool CNNSegmentation::Segment(const pcl_util::PointCloudPtr& pc_ptr,
PERF_BLOCK_END
(
"[CNNSeg] CNN forward"
);
// clutser points and construct segments/objects
float
objectness_thresh
=
cnnseg_param_
.
has_objectness_thresh
()
?
cnnseg_param_
.
objectness_thresh
()
:
0.5
;
bool
use_all_grids_for_clustering
=
cnnseg_param_
.
has_use_all_grids_for_clustering
()
?
cnnseg_param_
.
use_all_grids_for_clustering
()
:
false
;
cluster2d_
->
Cluster
(
*
category_pt_blob_
,
*
instance_pt_blob_
,
pc_ptr
,
valid_indices
,
cnnseg_param_
.
objectness_thresh
()
,
cnnseg_param_
.
use_all_grids_for_clustering
()
);
valid_indices
,
objectness_thresh
,
use_all_grids_for_clustering
);
PERF_BLOCK_END
(
"[CNNSeg] clustering"
);
cluster2d_
->
Filter
(
*
confidence_pt_blob_
,
*
height_pt_blob_
);
cluster2d_
->
GetObjects
(
cnnseg_param_
.
confidence_thresh
(),
cnnseg_param_
.
height_thresh
(),
cnnseg_param_
.
min_pts_num
(),
objects
);
float
confidence_thresh
=
cnnseg_param_
.
has_confidence_thresh
()
?
cnnseg_param_
.
confidence_thresh
()
:
0.1
;
float
height_thresh
=
cnnseg_param_
.
has_height_thresh
()
?
cnnseg_param_
.
height_thresh
()
:
0.5
;
int
min_pts_num
=
cnnseg_param_
.
has_min_pts_num
()
?
static_cast
<
int
>
(
cnnseg_param_
.
min_pts_num
())
:
3
;
cluster2d_
->
GetObjects
(
confidence_thresh
,
height_thresh
,
min_pts_num
,
objects
);
PERF_BLOCK_END
(
"[CNNSeg] post-processing"
);
return
true
;
...
...
modules/perception/obstacle/lidar/segmentation/cnnseg/feature_generator.cc
浏览文件 @
ebfe517e
...
...
@@ -32,28 +32,21 @@ bool FeatureGenerator<Dtype>::Init(const FeatureParam& feature_param,
out_blob_
=
out_blob
;
// raw feature parameters
range_
=
static_cast
<
int
>
(
feature_param
.
point_cloud_range
());
width_
=
static_cast
<
int
>
(
feature_param
.
width
());
height_
=
static_cast
<
int
>
(
feature_param
.
height
());
min_height_
=
feature_param
.
min_height
();
max_height_
=
feature_param
.
max_height
();
range_
=
feature_param
.
has_point_cloud_range
()
?
static_cast
<
int
>
(
feature_param
.
point_cloud_range
())
:
60
;
width_
=
feature_param
.
has_width
()
?
static_cast
<
int
>
(
feature_param
.
width
())
:
512
;
height_
=
feature_param
.
has_height
()
?
static_cast
<
int
>
(
feature_param
.
height
())
:
512
;
min_height_
=
feature_param
.
has_min_height
()
?
feature_param
.
min_height
()
:
-
5.0
;
max_height_
=
feature_param
.
has_max_height
()
?
feature_param
.
max_height
()
:
5.0
;
CHECK_EQ
(
width_
,
height_
)
<<
"Current implementation version requires input_width == input_height."
;
CHECK
(
feature_param
.
use_max_height
());
CHECK
(
feature_param
.
use_mean_height
());
CHECK
(
feature_param
.
use_log_count
());
CHECK
(
feature_param
.
use_direction
());
CHECK
(
feature_param
.
use_top_intensity
());
CHECK
(
feature_param
.
use_mean_intensity
());
CHECK
(
feature_param
.
use_distance
());
CHECK
(
feature_param
.
use_nonempty
());
data_channel_
=
8
;
CHECK
(
feature_param
.
use_height_filter
());
CHECK
(
feature_param
.
use_dense_feat
());
// set output blob and log lookup table
out_blob_
->
Reshape
(
1
,
data_channel_
,
height_
,
width_
);
out_blob_
->
Reshape
(
1
,
8
,
height_
,
width_
);
log_table_
.
resize
(
256
);
for
(
size_t
i
=
0
;
i
<
log_table_
.
size
();
++
i
)
{
...
...
modules/perception/obstacle/lidar/segmentation/cnnseg/feature_generator.h
浏览文件 @
ebfe517e
...
...
@@ -57,7 +57,6 @@ class FeatureGenerator {
int
width_
;
int
height_
;
int
data_channel_
;
int
range_
;
float
min_height_
;
...
...
modules/perception/obstacle/lidar/segmentation/cnnseg/proto/cnnseg.proto
浏览文件 @
ebfe517e
...
...
@@ -8,14 +8,9 @@ message CNNSegParam {
optional
float
objectness_thresh
=
11
[
default
=
0.5
];
optional
bool
use_all_grids_for_clustering
=
12
[
default
=
false
];
optional
float
confidence_thresh
=
13
[
default
=
0.
0
];
optional
float
confidence_thresh
=
13
[
default
=
0.
1
];
optional
float
height_thresh
=
14
[
default
=
0.5
];
optional
uint32
min_pts_num
=
15
[
default
=
3
];
//optional bool return_bg = 16 [default = false];
//optional bool do_classification = 21 [default = false];
//optional string classification_strategy = 22 [default = "voting"];
//optional bool do_heading = 23 [default = false];
optional
bool
use_full_cloud
=
31
[
default
=
false
];
...
...
@@ -23,31 +18,14 @@ message CNNSegParam {
}
message
NetworkParam
{
optional
string
instance_pt_blob
=
1
[
default
=
"instance_
refine
"
];
optional
string
instance_pt_blob
=
1
[
default
=
"instance_
pt
"
];
optional
string
category_pt_blob
=
2
[
default
=
"category_score"
];
optional
string
confidence_pt_blob
=
3
[
default
=
"confidence_score"
];
optional
string
classify_pt_blob
=
4
[
default
=
"classify_pt"
];
optional
string
heading_pt_blob
=
5
[
default
=
"heading_pt"
];
optional
string
height_pt_blob
=
6
[
default
=
"height_pt"
];
optional
string
feature_blob
=
7
[
default
=
"data"
];
//optional string feature_map_blob = 8 [default = ""];
optional
string
height_pt_blob
=
4
[
default
=
"height_pt"
];
optional
string
feature_blob
=
5
[
default
=
"data"
];
}
message
FeatureParam
{
optional
bool
use_max_height
=
11
[
default
=
false
];
optional
bool
use_mean_height
=
12
[
default
=
false
];
optional
bool
use_log_count
=
13
[
default
=
false
];
optional
bool
use_direction
=
14
[
default
=
false
];
optional
bool
use_top_intensity
=
15
[
default
=
false
];
optional
bool
use_mean_intensity
=
16
[
default
=
false
];
optional
bool
use_distance
=
17
[
default
=
false
];
optional
bool
use_nonempty
=
18
[
default
=
false
];
//optional bool use_first_order = 19 [default = false];
//optional bool use_second_order = 20 [default = false];
optional
bool
use_height_filter
=
24
[
default
=
false
];
optional
bool
use_dense_feat
=
25
[
default
=
false
];
optional
uint32
point_cloud_range
=
26
[
default
=
60
];
optional
uint32
width
=
27
[
default
=
512
];
optional
uint32
height
=
28
[
default
=
512
];
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录