Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
85088842
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 搜索 >>
提交
85088842
编写于
11月 12, 2018
作者:
T
Tae Eun Choe
提交者:
Jiangtao Hu
12月 13, 2018
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
Perception: Removed warnings 3 in perception build (#1738)
上级
bae035cb
变更
5
隐藏空白更改
内联
并排
Showing
5 changed file
with
80 addition
and
59 deletion
+80
-59
modules/perception/camera/lib/obstacle/tracker/omt/target.cc
modules/perception/camera/lib/obstacle/tracker/omt/target.cc
+21
-19
modules/perception/camera/test/camera_lib_calibrator_common_histogram_estimator_test.cc
.../camera_lib_calibrator_common_histogram_estimator_test.cc
+18
-18
modules/perception/common/i_lib/geometry/i_plane.h
modules/perception/common/i_lib/geometry/i_plane.h
+3
-1
modules/perception/common/i_lib/pc/i_ground.cc
modules/perception/common/i_lib/pc/i_ground.cc
+35
-20
modules/perception/common/i_lib/pc/i_ground.h
modules/perception/common/i_lib/pc/i_ground.h
+3
-1
未找到文件。
modules/perception/camera/lib/obstacle/tracker/omt/target.cc
浏览文件 @
85088842
...
...
@@ -142,8 +142,8 @@ void Target::Predict(CameraFrame *frame) {
void
Target
::
Update2D
(
CameraFrame
*
frame
)
{
// measurements
auto
obj
=
latest_object
->
object
;
float
width
=
frame
->
data_provider
->
src_width
(
);
float
height
=
frame
->
data_provider
->
src_height
(
);
float
width
=
static_cast
<
float
>
(
frame
->
data_provider
->
src_width
()
);
float
height
=
static_cast
<
float
>
(
frame
->
data_provider
->
src_height
()
);
base
::
RectF
rect
(
latest_object
->
projected_box
);
base
::
Point2DF
center
=
rect
.
Center
();
...
...
@@ -177,11 +177,11 @@ void Target::Update3D(CameraFrame *frame) {
z
<<
std
::
sin
(
object
->
theta
*
2
),
std
::
cos
(
object
->
theta
*
2
);
direction
.
AddMeasure
(
z
);
z
=
direction
.
get_state
();
float
theta
=
st
d
::
atan2
(
z
[
0
],
z
[
1
])
/
2
;
float
theta
=
st
atic_cast
<
float
>
(
std
::
atan2
(
z
[
0
],
z
[
1
])
/
2.0
)
;
AINFO
<<
"dir "
<<
id
<<
" "
<<
object
->
theta
<<
" "
<<
theta
;
object
->
theta
=
theta
;
object
->
direction
[
0
]
=
cos
(
object
->
theta
);
object
->
direction
[
1
]
=
s
in
(
object
->
theta
);
object
->
direction
[
0
]
=
static_cast
<
float
>
(
cos
(
object
->
theta
)
);
object
->
direction
[
1
]
=
s
tatic_cast
<
float
>
(
sin
(
object
->
theta
)
);
object
->
direction
[
2
]
=
0
;
z
<<
object
->
center
(
0
),
object
->
center
(
1
);
...
...
@@ -215,8 +215,8 @@ void Target::Update3D(CameraFrame *frame) {
const
Eigen
::
MatrixXd
&
var
=
world_center_for_unmovable
.
get_variance
();
object
->
center
(
0
)
=
x
(
0
);
object
->
center
(
1
)
=
x
(
1
);
object
->
center_uncertainty
(
0
)
=
var
(
0
);
object
->
center_uncertainty
(
1
)
=
var
(
1
);
object
->
center_uncertainty
(
0
)
=
static_cast
<
float
>
(
var
(
0
)
);
object
->
center_uncertainty
(
1
)
=
static_cast
<
float
>
(
var
(
1
)
);
object
->
velocity
(
0
)
=
0
;
object
->
velocity
(
1
)
=
0
;
object
->
velocity
(
2
)
=
0
;
...
...
@@ -261,18 +261,20 @@ void Target::Update3D(CameraFrame *frame) {
object
->
center
(
0
)
=
x
(
0
);
object
->
center
(
1
)
=
x
(
1
);
object
->
center_uncertainty
.
setConstant
(
0
);
object
->
center_uncertainty
(
0
,
0
)
=
world_center
.
variance_
(
0
,
0
);
object
->
center_uncertainty
(
1
,
1
)
=
world_center
.
variance_
(
1
,
1
);
object
->
velocity
(
0
)
=
x
(
2
);
object
->
velocity
(
1
)
=
x
(
3
);
object
->
center_uncertainty
(
0
,
0
)
=
static_cast
<
float
>
(
world_center
.
variance_
(
0
,
0
));
object
->
center_uncertainty
(
1
,
1
)
=
static_cast
<
float
>
(
world_center
.
variance_
(
1
,
1
));
object
->
velocity
(
0
)
=
static_cast
<
float
>
(
x
(
2
));
object
->
velocity
(
1
)
=
static_cast
<
float
>
(
x
(
3
));
object
->
velocity
(
2
)
=
0
;
world_velocity
.
AddMeasure
(
object
->
velocity
.
cast
<
double
>
());
object
->
velocity_uncertainty
=
world_velocity
.
get_variance
().
cast
<
float
>
();
if
(
speed
>
target_param_
.
velocity_threshold
())
{
object
->
direction
(
0
)
=
x
(
2
)
/
speed
;
object
->
direction
(
1
)
=
x
(
3
)
/
speed
;
object
->
direction
(
0
)
=
static_cast
<
float
>
(
x
(
2
)
/
speed
)
;
object
->
direction
(
1
)
=
static_cast
<
float
>
(
x
(
3
)
/
speed
)
;
object
->
direction
(
2
)
=
0
;
object
->
theta
=
st
d
::
atan2
(
x
(
3
),
x
(
2
));
object
->
theta
=
st
atic_cast
<
float
>
(
std
::
atan2
(
x
(
3
),
x
(
2
)
));
}
}
...
...
@@ -422,7 +424,7 @@ bool Target::CheckStatic() {
obj1
.
velocity
+
obj2
.
velocity
;
return
ret_obj
;
});
tmp_obj_vel_avg
.
velocity
/=
min_vel_size
;
tmp_obj_vel_avg
.
velocity
/=
static_cast
<
float
>
(
min_vel_size
)
;
double
speed_avg
=
tmp_obj_vel_avg
.
velocity
.
head
(
2
).
norm
();
const
auto
&
obj_type
=
history_world_states_
.
back
().
type
;
// check speed by type
...
...
@@ -440,12 +442,12 @@ bool Target::CheckStatic() {
if
(
static_cast
<
int
>
(
history_world_states_
.
size
())
>=
std
::
max
(
target_param_
.
min_cached_position_size
(),
target_param_
.
calc_avg_position_window_size
()))
{
double
move_distance
=
0.0
f
;
double
move_distance
=
0.0
;
Eigen
::
Vector3d
start_position
(
0.0
,
0.0
,
0.0
);
Eigen
::
Vector3d
end_position
(
0.0
,
0.0
,
0.0
);
const
int
start_idx
=
history_world_states_
.
size
(
)
-
target_param_
.
min_cached_position_size
(
);
const
int
end_idx
=
history_world_states_
.
size
(
)
-
1
;
const
int
start_idx
=
static_cast
<
int
>
(
history_world_states_
.
size
()
)
-
static_cast
<
int
>
(
target_param_
.
min_cached_position_size
()
);
const
int
end_idx
=
static_cast
<
int
>
(
history_world_states_
.
size
()
)
-
1
;
// calculate window-averaged start and end positions
// and calculate moved distance
if
(
end_idx
-
start_idx
>=
...
...
modules/perception/camera/test/camera_lib_calibrator_common_histogram_estimator_test.cc
浏览文件 @
85088842
...
...
@@ -38,60 +38,60 @@ TEST(HistogramEstimatorTest, histogram_estimator_test) {
estimator
.
get_val_estimation
();
estimator
.
get_bin_value
(
0
);
estimator
.
Push
(
params1
.
data_ep
-
1.0
);
estimator
.
Push
(
params1
.
data_ep
+
1.0
);
estimator
.
Push
(
params1
.
data_sp
-
1.0
);
estimator
.
Push
(
params1
.
data_sp
+
1.0
);
estimator
.
Push
((
params1
.
data_sp
+
params1
.
data_ep
)
/
2.0
);
estimator
.
Push
(
params1
.
data_ep
-
1.0
f
);
estimator
.
Push
(
params1
.
data_ep
+
1.0
f
);
estimator
.
Push
(
params1
.
data_sp
-
1.0
f
);
estimator
.
Push
(
params1
.
data_sp
+
1.0
f
);
estimator
.
Push
((
params1
.
data_sp
+
params1
.
data_ep
)
/
2.0
f
);
estimator
.
Process
();
estimator
.
Clear
();
estimator
.
Push
((
params1
.
data_sp
+
params1
.
data_ep
)
/
2.0
);
estimator
.
Push
((
params1
.
data_sp
+
params1
.
data_ep
)
/
2.0
f
);
estimator
.
Process
();
estimator
.
Clear
();
for
(
int
i
=
0
;
i
<
10
;
i
++
)
{
estimator
.
Push
((
params1
.
data_sp
+
params1
.
data_ep
)
/
2.0
);
estimator
.
Push
((
params1
.
data_sp
+
params1
.
data_ep
)
/
2.0
f
);
}
estimator
.
Process
();
estimator
.
Clear
();
for
(
int
i
=
0
;
i
<
100
;
i
++
)
{
estimator
.
Push
((
params1
.
data_sp
+
params1
.
data_ep
)
/
2.0
);
estimator
.
Push
((
params1
.
data_sp
+
params1
.
data_ep
)
/
2.0
f
);
}
estimator
.
Process
();
estimator
.
Clear
();
for
(
int
i
=
0
;
i
<
10
;
i
++
)
{
estimator
.
Push
(
params1
.
data_sp
*
i
/
100.0
+
params1
.
data_ep
*
(
1.0
-
i
/
100.0
));
estimator
.
Push
(
params1
.
data_sp
*
static_cast
<
float
>
(
i
)
/
100.0
f
+
params1
.
data_ep
*
(
1.0
f
-
static_cast
<
float
>
(
i
)
/
100.0
f
));
}
estimator
.
Process
();
estimator
.
Clear
();
for
(
int
i
=
0
;
i
<
10
;
i
++
)
{
estimator
.
Push
(
params1
.
data_ep
*
i
/
10.0
+
params1
.
data_sp
*
(
1.0
-
i
/
10.0
));
estimator
.
Push
(
params1
.
data_ep
*
static_cast
<
float
>
(
i
)
/
10.0
f
+
params1
.
data_sp
*
(
1.0
f
-
static_cast
<
float
>
(
i
)
/
10.0
f
));
}
estimator
.
Process
();
estimator
.
Clear
();
for
(
int
i
=
0
;
i
<
10
;
i
++
)
{
estimator
.
Push
(
params1
.
data_sp
*
i
/
10.0
+
params1
.
data_ep
*
(
1.0
-
i
/
10.0
));
estimator
.
Push
(
params1
.
data_sp
*
static_cast
<
float
>
(
i
)
/
10.0
f
+
params1
.
data_ep
*
(
1.0
f
-
static_cast
<
float
>
(
i
)
/
10.0
f
));
}
for
(
int
i
=
0
;
i
<
10
;
i
++
)
{
estimator
.
Push
((
params1
.
data_sp
+
params1
.
data_ep
)
/
2.0
);
estimator
.
Push
((
params1
.
data_sp
+
params1
.
data_ep
)
/
2.0
f
);
}
estimator
.
Process
();
estimator
.
Clear
();
for
(
int
i
=
0
;
i
<
10
;
i
++
)
{
estimator
.
Push
(
params1
.
data_ep
*
i
/
10.0
+
params1
.
data_sp
*
(
1.0
-
i
/
10.0
));
estimator
.
Push
(
params1
.
data_ep
*
static_cast
<
float
>
(
i
)
/
10.0
f
+
params1
.
data_sp
*
(
1.0
f
-
static_cast
<
float
>
(
i
)
/
10.0
f
));
}
for
(
int
i
=
0
;
i
<
10
;
i
++
)
{
estimator
.
Push
((
params1
.
data_sp
+
params1
.
data_ep
)
/
2.0
);
estimator
.
Push
((
params1
.
data_sp
+
params1
.
data_ep
)
/
2.0
f
);
}
estimator
.
Process
();
params1
.
smooth_kernel_radius
=
params1
.
nr_bins_in_histogram
;
...
...
modules/perception/common/i_lib/geometry/i_plane.h
浏览文件 @
85088842
...
...
@@ -178,7 +178,9 @@ inline void IPlaneFitTotalLeastSquare(T *X, T *pi, int n) {
// pi is stored as 4 - vector[a, b, c, d]. x will be destroyed after calling
// this routine.
template
<
typename
T
>
inline
void
IPlaneFitTotalLeastSquare3
(
T
*
X
,
T
*
pi
)
{
T
mat_a
[
9
],
eigv
[
3
],
mat_q
[
9
];
T
mat_a
[
9
];
T
eigv
[
3
];
T
mat_q
[
9
];
// compute the centroid of input Data points
IZero4
(
pi
);
T
xm
=
(
X
[
0
]
+
X
[
3
]
+
X
[
6
])
/
3
;
...
...
modules/perception/common/i_lib/pc/i_ground.cc
浏览文件 @
85088842
...
...
@@ -66,7 +66,7 @@ bool PlaneFitGroundDetectorParam::Validate() const {
int
PlaneFitPointCandIndices
::
Prune
(
unsigned
int
min_nr_samples
,
unsigned
int
max_nr_samples
)
{
assert
(
min_nr_samples
<
max_nr_samples
);
unsigned
int
size
=
indices
.
size
(
);
unsigned
int
size
=
static_cast
<
unsigned
int
>
(
indices
.
size
()
);
unsigned
int
half
=
0
;
if
(
size
>
max_nr_samples
)
{
IRandomizedShuffle1
(
indices
.
data
(),
static_cast
<
int
>
(
indices
.
size
()),
...
...
@@ -114,7 +114,7 @@ void PlaneFitGroundDetector::InitOrderTable(const VoxelGridXY<float> *vg,
int
id
=
0
;
for
(
i
=
0
;
i
<
vg
->
NrVoxel
();
++
i
)
{
const
auto
&
voxel
=
vg
->
GetConstVoxels
()[
i
];
radius
=
voxel
.
dim_x_
*
0.5
;
radius
=
voxel
.
dim_x_
*
0.5
f
;
cx
=
voxel
.
v_
[
0
]
+
radius
;
cy
=
voxel
.
v_
[
1
]
+
radius
;
dist2
=
cx
*
cx
+
cy
*
cy
;
...
...
@@ -639,7 +639,8 @@ int PlaneFitGroundDetector::FitGrid(const float *point_cloud,
int
nr_samples
=
candi
->
Prune
(
param_
.
nr_samples_min_threshold
,
param_
.
nr_samples_max_threshold
);
int
nr_inliers_termi
=
IRound
(
nr_samples
*
param_
.
termi_inlier_percen_threshold
);
IRound
(
static_cast
<
float
>
(
nr_samples
)
*
param_
.
termi_inlier_percen_threshold
);
// 3x3 matrix stores: x, y, z; x, y, z; x, y, z;
float
samples
[
9
];
// copy 3D points
...
...
@@ -678,7 +679,8 @@ int PlaneFitGroundDetector::FitGrid(const float *point_cloud,
// Assign number of supports
plane
.
SetNrSupport
(
nr_inliers
);
fit_cost
=
nr_inliers
>
0
?
(
fit_cost
/
nr_inliers
)
:
dist_thre
;
fit_cost
=
nr_inliers
>
0
?
(
fit_cost
/
static_cast
<
float
>
(
nr_inliers
))
:
dist_thre
;
// record the best plane
if
(
nr_inliers
>=
nr_inliers_best
)
{
if
(
nr_inliers
==
nr_inliers_best
)
{
...
...
@@ -784,7 +786,7 @@ int PlaneFitGroundDetector::FilterCandidates(
}
}
if
(
count
>
0
)
{
avg_z
/=
count
;
avg_z
/=
static_cast
<
float
>
(
count
)
;
ground_z_
[
r
][
c
].
first
=
avg_z
;
ground_z_
[
r
][
c
].
second
=
true
;
for
(
i
=
0
;
i
<
candi
->
Size
();
++
i
)
{
...
...
@@ -828,7 +830,8 @@ int PlaneFitGroundDetector::FitGridWithNeighbors(
}
GroundPlaneLiDAR
plane
;
int
kNr_iter
=
param_
.
nr_ransac_iter_threshold
+
neighbors
.
size
();
int
kNr_iter
=
param_
.
nr_ransac_iter_threshold
+
static_cast
<
int
>
(
neighbors
.
size
());
GroundPlaneLiDAR
hypothesis
[
kNr_iter
];
float
ptp_dist
=
0
;
int
best
=
-
1
;
...
...
@@ -841,7 +844,8 @@ int PlaneFitGroundDetector::FitGridWithNeighbors(
int
nr_samples
=
candi
.
Prune
(
param_
.
nr_samples_min_threshold
,
param_
.
nr_samples_max_threshold
);
int
nr_inliers_termi
=
IRound
(
nr_samples
*
param_
.
termi_inlier_percen_threshold
);
IRound
(
static_cast
<
float
>
(
nr_samples
)
*
param_
.
termi_inlier_percen_threshold
);
// 3x3 matrix stores: x, y, z; x, y, z; x, y, z;
float
samples
[
9
];
// copy 3D points
...
...
@@ -971,7 +975,7 @@ int PlaneFitGroundDetector::FitGridWithNeighbors(
}
const
auto
&
voxel_cur
=
(
*
vg_coarse_
)(
r
,
c
);
float
radius
=
voxel_cur
.
dim_x_
*
0.5
;
float
radius
=
voxel_cur
.
dim_x_
*
0.5
f
;
float
cx
=
voxel_cur
.
v_
[
0
]
+
radius
;
float
cy
=
voxel_cur
.
v_
[
1
]
+
radius
;
float
cz
=
-
(
groundplane
->
params
[
0
]
*
cx
+
groundplane
->
params
[
1
]
*
cy
+
...
...
@@ -1002,7 +1006,7 @@ float PlaneFitGroundDetector::CalculateAngleDist(
if
(
count
==
0
)
{
return
-
1
;
}
return
angle_dist
/
count
;
return
angle_dist
/
static_cast
<
float
>
(
count
)
;
}
int
PlaneFitGroundDetector
::
FitInOrder
()
{
...
...
@@ -1123,14 +1127,19 @@ int PlaneFitGroundDetector::CompleteGrid(const GroundPlaneSpherical <,
supports
[
1
]
=
rt
.
GetNrSupport
();
supports
[
2
]
=
up
.
GetNrSupport
();
supports
[
3
]
=
dn
.
GetNrSupport
();
int
support_sum
=
ISum4
(
supports
);
int
support_sum
=
0
;
support_sum
=
ISum4
(
supports
);
if
(
!
support_sum
)
{
return
0
;
}
weights
[
0
]
=
static_cast
<
float
>
(
supports
[
0
])
/
support_sum
;
weights
[
1
]
=
static_cast
<
float
>
(
supports
[
1
])
/
support_sum
;
weights
[
2
]
=
static_cast
<
float
>
(
supports
[
2
])
/
support_sum
;
weights
[
3
]
=
static_cast
<
float
>
(
supports
[
3
])
/
support_sum
;
weights
[
0
]
=
static_cast
<
float
>
(
supports
[
0
])
/
static_cast
<
float
>
(
support_sum
);
weights
[
1
]
=
static_cast
<
float
>
(
supports
[
1
])
/
static_cast
<
float
>
(
support_sum
);
weights
[
2
]
=
static_cast
<
float
>
(
supports
[
2
])
/
static_cast
<
float
>
(
support_sum
);
weights
[
3
]
=
static_cast
<
float
>
(
supports
[
3
])
/
static_cast
<
float
>
(
support_sum
);
// weighted average:
gp
->
theta
=
weights
[
0
]
*
lt
.
theta
+
weights
[
1
]
*
rt
.
theta
+
weights
[
2
]
*
up
.
theta
+
weights
[
3
]
*
dn
.
theta
;
...
...
@@ -1173,17 +1182,23 @@ int PlaneFitGroundDetector::SmoothGrid(const GroundPlaneSpherical &g,
supports
[
3
]
=
dn
.
GetNrSupport
();
}
supports
[
4
]
=
(
g
.
GetNrSupport
()
<<
2
);
int
support_sum
=
ISum4
(
supports
);
int
support_sum
=
0
;
support_sum
=
ISum4
(
supports
);
if
(
support_sum
==
0
)
{
*
gp
=
g
;
return
0
;
}
support_sum
+=
supports
[
4
];
weights
[
0
]
=
static_cast
<
float
>
(
supports
[
0
])
/
support_sum
;
weights
[
1
]
=
static_cast
<
float
>
(
supports
[
1
])
/
support_sum
;
weights
[
2
]
=
static_cast
<
float
>
(
supports
[
2
])
/
support_sum
;
weights
[
3
]
=
static_cast
<
float
>
(
supports
[
3
])
/
support_sum
;
weights
[
4
]
=
static_cast
<
float
>
(
supports
[
4
])
/
support_sum
;
weights
[
0
]
=
static_cast
<
float
>
(
supports
[
0
])
/
static_cast
<
float
>
(
support_sum
);
weights
[
1
]
=
static_cast
<
float
>
(
supports
[
1
])
/
static_cast
<
float
>
(
support_sum
);
weights
[
2
]
=
static_cast
<
float
>
(
supports
[
2
])
/
static_cast
<
float
>
(
support_sum
);
weights
[
3
]
=
static_cast
<
float
>
(
supports
[
3
])
/
static_cast
<
float
>
(
support_sum
);
weights
[
4
]
=
static_cast
<
float
>
(
supports
[
4
])
/
static_cast
<
float
>
(
support_sum
);
// weighted average:
gp
->
theta
=
weights
[
0
]
*
lt
.
theta
+
weights
[
1
]
*
rt
.
theta
+
weights
[
2
]
*
up
.
theta
+
weights
[
3
]
*
dn
.
theta
+
...
...
modules/perception/common/i_lib/pc/i_ground.h
浏览文件 @
85088842
...
...
@@ -199,7 +199,9 @@ struct PlaneFitPointCandIndices {
void
Clear
()
{
indices
.
clear
();
}
inline
void
PushIndex
(
int
i
)
{
indices
.
push_back
(
i
);
}
int
Prune
(
unsigned
int
min_nr_samples
,
unsigned
int
max_nr_samples
);
unsigned
int
Size
()
const
{
return
indices
.
size
();
}
unsigned
int
Size
()
const
{
return
static_cast
<
unsigned
int
>
(
indices
.
size
());
}
int
&
operator
[](
unsigned
int
i
)
{
assert
(
i
>=
0
&&
i
<
indices
.
size
());
return
indices
.
at
(
i
);
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录