Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
a9e662c3
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 搜索 >>
提交
a9e662c3
编写于
9月 24, 2018
作者:
L
Liangliang Zhang
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
Perception: fixed multiple coding issues in base and common folders.
上级
401d0772
变更
9
隐藏空白更改
内联
并排
Showing
9 changed file
with
664 addition
and
18 deletion
+664
-18
apollo.sh
apollo.sh
+2
-2
modules/perception/base/BUILD
modules/perception/base/BUILD
+29
-0
modules/perception/base/point_cloud.h
modules/perception/base/point_cloud.h
+1
-0
modules/perception/base/point_cloud_types.h
modules/perception/base/point_cloud_types.h
+0
-8
modules/perception/common/geometry/BUILD
modules/perception/common/geometry/BUILD
+12
-0
modules/perception/common/graph/BUILD
modules/perception/common/graph/BUILD
+184
-0
modules/perception/common/graph/conditional_clustering_test.cc
...es/perception/common/graph/conditional_clustering_test.cc
+10
-8
modules/perception/common/point_cloud_processing/BUILD
modules/perception/common/point_cloud_processing/BUILD
+30
-0
modules/perception/common/point_cloud_processing/common_test.cc
...s/perception/common/point_cloud_processing/common_test.cc
+396
-0
未找到文件。
apollo.sh
浏览文件 @
a9e662c3
...
...
@@ -117,7 +117,7 @@ function generate_build_targets() {
`
bazel query //modules/localization/msf/local_tool/local_visualization/...
`
//modules/map/...
//modules/monitor/...
//modules/perception/...
//modules/perception/
proto/
...
//modules/planning/...
//modules/prediction/...
//modules/routing/...
...
...
@@ -223,7 +223,7 @@ function cibuild() {
`
bazel query //modules/localization/msf/... except //modules/localization/msf/local_tool/...
`
`
bazel query //modules/localization/msf/local_tool/local_visualization/...
`
//modules/map/...
//modules/perception/...
//modules/perception/
proto/
...
//modules/planning/...
//modules/prediction/...
//modules/routing/...
...
...
modules/perception/base/BUILD
0 → 100644
浏览文件 @
a9e662c3
load
(
"//tools:cpplint.bzl"
,
"cpplint"
)
package
(
default_visibility
=
[
"//visibility:public"
])
cc_library
(
name
=
"point_cloud"
,
hdrs
=
[
"point.h"
,
"point_cloud.h"
,
"point_cloud_types.h"
,
],
deps
=
[
"@eigen"
,
],
)
cc_test
(
name
=
"point_cloud_test"
,
size
=
"small"
,
srcs
=
[
"point_cloud_test.cc"
,
],
deps
=
[
":point_cloud"
,
"@gtest//:main"
,
],
)
cpplint
()
modules/perception/base/point_cloud.h
浏览文件 @
a9e662c3
...
...
@@ -33,6 +33,7 @@ namespace base {
template
<
class
PointT
>
class
PointCloud
{
public:
using
PointType
=
PointT
;
// @brief default constructor
PointCloud
()
=
default
;
// @brief copy constructor
...
...
modules/perception/base/point_cloud_types.h
浏览文件 @
a9e662c3
...
...
@@ -29,14 +29,6 @@ namespace base {
using
PointF
=
PointXYZIF
;
using
PointD
=
PointXYZID
;
// point cloud
using
PointFCloud
=
AttributePointCloud
<
PointXYZIF
>
;
using
PointDCloud
=
AttributePointCloud
<
PointXYZID
>
;
// polygon
using
PolygonFType
=
PointCloud
<
PointF
>
;
using
PolygonDType
=
PointCloud
<
PointD
>
;
}
// namespace base
}
// namespace perception
}
// namespace apollo
...
...
modules/perception/common/geometry/BUILD
0 → 100644
浏览文件 @
a9e662c3
load
(
"//tools:cpplint.bzl"
,
"cpplint"
)
package
(
default_visibility
=
[
"//visibility:public"
])
cc_library
(
name
=
"basic"
,
hdrs
=
[
"basic.h"
,
],
)
cpplint
()
modules/perception/common/graph/BUILD
0 → 100644
浏览文件 @
a9e662c3
load
(
"//tools:cpplint.bzl"
,
"cpplint"
)
package
(
default_visibility
=
[
"//visibility:public"
])
cc_library
(
name
=
"graph"
,
deps
=
[
":disjoint_set"
,
":graph_segmentor"
,
":secure_matrix"
,
":hungarian_optimizer"
,
":connected_component_analysis"
,
":conditional_clustering"
,
":gated_hungarian_bigraph_matcher"
,
],
)
cc_library
(
name
=
"disjoint_set"
,
srcs
=
[
"disjoint_set.cc"
,
],
hdrs
=
[
"disjoint_set.h"
,
],
)
cc_test
(
name
=
"disjoint_set_test"
,
size
=
"small"
,
srcs
=
[
"disjoint_set_test.cc"
,
],
deps
=
[
":disjoint_set"
,
"@gtest//:main"
,
],
)
cc_library
(
name
=
"graph_segmentor"
,
srcs
=
[
"graph_segmentor.cc"
,
],
hdrs
=
[
"graph_segmentor.h"
,
],
deps
=
[
"//framework:cybertron"
,
":disjoint_set"
,
],
)
cc_test
(
name
=
"graph_segmentor_test"
,
size
=
"small"
,
srcs
=
[
"graph_segmentor_test.cc"
,
],
deps
=
[
":graph_segmentor"
,
"@gtest//:main"
,
],
)
cc_library
(
name
=
"secure_matrix"
,
hdrs
=
[
"secure_matrix.h"
,
],
deps
=
[
"@eigen"
,
],
)
cc_test
(
name
=
"secure_matrix_test"
,
size
=
"small"
,
srcs
=
[
"secure_matrix_test.cc"
,
],
deps
=
[
":secure_matrix"
,
"@gtest//:main"
,
"@eigen"
,
],
)
cc_library
(
name
=
"hungarian_optimizer"
,
hdrs
=
[
"hungarian_optimizer.h"
,
],
deps
=
[
"@eigen"
,
],
)
cc_test
(
name
=
"hungarian_optimizer_test"
,
size
=
"small"
,
srcs
=
[
"hungarian_optimizer_test.cc"
,
],
deps
=
[
":hungarian_optimizer"
,
":secure_matrix"
,
"@gtest//:main"
,
],
)
cc_library
(
name
=
"connected_component_analysis"
,
hdrs
=
[
"connected_component_analysis.h"
,
],
deps
=
[
"//framework:cybertron"
,
],
)
cc_test
(
name
=
"connected_component_analysis_test"
,
size
=
"small"
,
srcs
=
[
"connected_component_analysis_test.cc"
,
],
deps
=
[
":connected_component_analysis"
,
"@eigen"
,
"@gtest//:main"
,
],
)
cc_library
(
name
=
"conditional_clustering"
,
hdrs
=
[
"conditional_clustering.h"
,
],
deps
=
[
"//modules/perception/base:point_cloud"
,
"//modules/perception/common/geometry:basic"
,
"@eigen"
,
],
)
cc_test
(
name
=
"conditional_clustering_test"
,
size
=
"small"
,
srcs
=
[
"conditional_clustering_test.cc"
,
],
deps
=
[
":conditional_clustering"
,
"@gtest//:main"
,
],
)
cc_library
(
name
=
"gated_hungarian_bigraph_matcher"
,
hdrs
=
[
"gated_hungarian_bigraph_matcher.h"
,
],
deps
=
[
"//framework:cybertron"
,
":connected_component_analysis"
,
":hungarian_optimizer"
,
":secure_matrix"
,
],
)
cc_test
(
name
=
"gated_hungarian_bigraph_matcher_test"
,
size
=
"small"
,
srcs
=
[
"gated_hungarian_bigraph_matcher_test.cc"
,
],
deps
=
[
":gated_hungarian_bigraph_matcher"
,
"@gtest//:main"
,
],
)
cpplint
()
modules/perception/common/graph/conditional_clustering_test.cc
浏览文件 @
a9e662c3
...
...
@@ -62,14 +62,16 @@ bool EasyConditionFalse(const base::PointF& p1, const base::PointF& p2,
}
// namespace
using
IndicesClusters
=
std
::
vector
<
base
::
PointIndices
>
;
using
base
::
PointCloud
;
using
base
::
PointF
;
TEST
(
ConditionalClusteringTest
,
conditional_clustering_test
)
{
ConditionClustering
<
base
::
PointF
>
condition_clustering
=
ConditionClustering
<
base
::
PointF
>
(
false
);
std
::
shared_ptr
<
base
::
PolygonFType
>
polygon_in_ptr
=
std
::
shared_ptr
<
base
::
PolygonFType
>
(
new
base
::
PolygonFType
(
16
,
16
,
base
::
PointF
()));
base
::
PolygonFType
polygon_out
;
std
::
shared_ptr
<
PointCloud
<
PointF
>
>
polygon_in_ptr
=
std
::
shared_ptr
<
PointCloud
<
PointF
>
>
(
new
PointCloud
<
PointF
>
(
16
,
16
,
base
::
PointF
()));
PointCloud
<
PointF
>
polygon_out
;
base
::
PointF
tmp_pt
;
size_t
i
,
j
;
for
(
i
=
0
;
i
<
8
;
++
i
)
{
...
...
@@ -127,10 +129,10 @@ TEST(ConditionalClusteringTest, conditional_clustering_test) {
TEST
(
ConditionalClusteringTest
,
conditional_clustering_test1
)
{
ConditionClustering
<
base
::
PointF
>
condition_clustering
=
ConditionClustering
<
base
::
PointF
>
(
true
);
std
::
shared_ptr
<
base
::
PolygonFType
>
polygon_in_ptr
=
std
::
shared_ptr
<
base
::
PolygonFType
>
(
new
base
::
PolygonFType
(
16
,
16
,
base
::
PointF
()));
base
::
PolygonFType
polygon_out
;
std
::
shared_ptr
<
PointCloud
<
PointF
>
>
polygon_in_ptr
=
std
::
shared_ptr
<
PointCloud
<
PointF
>
>
(
new
PointCloud
<
PointF
>
(
16
,
16
,
base
::
PointF
()));
PointCloud
<
PointF
>
polygon_out
;
base
::
PointF
tmp_pt
;
size_t
i
,
j
;
for
(
i
=
0
;
i
<
8
;
++
i
)
{
...
...
modules/perception/common/point_cloud_processing/BUILD
0 → 100644
浏览文件 @
a9e662c3
load
(
"//tools:cpplint.bzl"
,
"cpplint"
)
package
(
default_visibility
=
[
"//visibility:public"
])
cc_library
(
name
=
"point_cloud_processing"
,
hdrs
=
[
"common.h"
,
"downsampling.h"
,
],
deps
=
[
"//framework:cybertron"
,
"//modules/perception/base:point_cloud"
,
"//modules/perception/common/geometry:basic"
,
],
)
cc_library
(
name
=
"point_cloud_processing_test"
,
srcs
=
[
"common_test.cc"
,
],
deps
=
[
":point_cloud_processing"
,
"@gtest//:main"
,
],
)
cpplint
()
modules/perception/common/point_cloud_processing/common_test.cc
0 → 100644
浏览文件 @
a9e662c3
/******************************************************************************
* Copyright 2018 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/perception/common/point_cloud_processing/common.h"
#include <limits>
#include "gtest/gtest.h"
namespace
apollo
{
namespace
perception
{
namespace
common
{
using
base
::
AttributePointCloud
;
using
base
::
PointF
;
TEST
(
PointCloudProcessingCommonTest
,
transform_point_test
)
{
PointF
pt_in
;
pt_in
.
x
=
10.
f
;
pt_in
.
y
=
10.
f
;
pt_in
.
z
=
5.
f
;
PointF
pt_out
;
Eigen
::
Affine3d
pose
=
Eigen
::
Affine3d
::
Identity
();
TransformPoint
(
pt_in
,
pose
,
&
pt_out
);
EXPECT_NEAR
(
pt_in
.
x
,
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
pt_in
.
y
,
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
pt_in
.
z
,
5.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
}
TEST
(
PointCloudProcessingCommonTest
,
transform_point_cloud_test1
)
{
AttributePointCloud
<
PointF
>
cloud_in
,
cloud_out
;
PointF
temp
;
temp
.
x
=
10.
f
;
temp
.
y
=
10.
f
;
temp
.
z
=
5.
f
;
cloud_in
.
push_back
(
temp
);
temp
.
x
=
20.
f
;
temp
.
y
=
-
10.
f
;
temp
.
z
=
15.
f
;
cloud_in
.
push_back
(
temp
);
Eigen
::
Affine3d
pose
=
Eigen
::
Affine3d
::
Identity
();
TransformPointCloud
<
PointF
>
(
cloud_in
,
pose
,
&
cloud_out
);
EXPECT_NEAR
(
cloud_out
[
0
].
x
,
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
cloud_out
[
0
].
y
,
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
cloud_out
[
0
].
z
,
5.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
cloud_out
[
1
].
x
,
20.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
cloud_out
[
1
].
y
,
-
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
cloud_out
[
1
].
z
,
15.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
}
TEST
(
PointCloudProcessingCommonTest
,
transform_point_cloud_test2
)
{
std
::
shared_ptr
<
AttributePointCloud
<
PointF
>>
cloud_in
(
new
AttributePointCloud
<
PointF
>
);
std
::
shared_ptr
<
AttributePointCloud
<
PointF
>>
cloud_out
(
new
AttributePointCloud
<
PointF
>
);
PointF
temp
;
temp
.
x
=
10.
f
;
temp
.
y
=
10.
f
;
temp
.
z
=
5.
f
;
cloud_in
->
push_back
(
temp
);
temp
.
x
=
20.
f
;
temp
.
y
=
-
10.
f
;
temp
.
z
=
15.
f
;
cloud_in
->
push_back
(
temp
);
Eigen
::
Affine3d
pose
=
Eigen
::
Affine3d
::
Identity
();
TransformPointCloud
<
PointF
>
(
*
cloud_in
,
pose
,
cloud_out
.
get
());
EXPECT_NEAR
(
cloud_out
->
at
(
0
).
x
,
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
cloud_out
->
at
(
0
).
y
,
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
cloud_out
->
at
(
0
).
z
,
5.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
cloud_out
->
at
(
1
).
x
,
20.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
cloud_out
->
at
(
1
).
y
,
-
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
cloud_out
->
at
(
1
).
z
,
15.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
}
TEST
(
PointCloudProcessingCommonTest
,
transform_point_cloud_test3
)
{
AttributePointCloud
<
PointF
>
cloud_in_out
;
PointF
temp
;
temp
.
x
=
10.
f
;
temp
.
y
=
10.
f
;
temp
.
z
=
5.
f
;
cloud_in_out
.
push_back
(
temp
);
temp
.
x
=
20.
f
;
temp
.
y
=
-
10.
f
;
temp
.
z
=
15.
f
;
cloud_in_out
.
push_back
(
temp
);
Eigen
::
Affine3d
pose
=
Eigen
::
Affine3d
::
Identity
();
TransformPointCloud
<
PointF
>
(
pose
,
&
cloud_in_out
);
EXPECT_NEAR
(
cloud_in_out
[
0
].
x
,
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
cloud_in_out
[
0
].
y
,
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
cloud_in_out
[
0
].
z
,
5.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
cloud_in_out
[
1
].
x
,
20.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
cloud_in_out
[
1
].
y
,
-
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
cloud_in_out
[
1
].
z
,
15.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
}
TEST
(
PointCloudProcessingCommonTest
,
transform_point_cloud_test4
)
{
std
::
shared_ptr
<
AttributePointCloud
<
PointF
>>
cloud_in_out
(
new
AttributePointCloud
<
PointF
>
);
PointF
temp
;
temp
.
x
=
10.
f
;
temp
.
y
=
10.
f
;
temp
.
z
=
5.
f
;
cloud_in_out
->
push_back
(
temp
);
temp
.
x
=
20.
f
;
temp
.
y
=
-
10.
f
;
temp
.
z
=
15.
f
;
cloud_in_out
->
push_back
(
temp
);
Eigen
::
Affine3d
pose
=
Eigen
::
Affine3d
::
Identity
();
TransformPointCloud
<
PointF
>
(
pose
,
cloud_in_out
.
get
());
EXPECT_NEAR
(
cloud_in_out
->
at
(
0
).
x
,
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
cloud_in_out
->
at
(
0
).
y
,
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
cloud_in_out
->
at
(
0
).
z
,
5.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
cloud_in_out
->
at
(
1
).
x
,
20.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
cloud_in_out
->
at
(
1
).
y
,
-
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
cloud_in_out
->
at
(
1
).
z
,
15.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
}
TEST
(
PointCloudProcessingCommonTest
,
extract_indiced_cloud_test
)
{
std
::
shared_ptr
<
AttributePointCloud
<
PointF
>>
cloud_in
(
new
AttributePointCloud
<
PointF
>
);
std
::
shared_ptr
<
AttributePointCloud
<
PointF
>>
cloud_out
(
new
AttributePointCloud
<
PointF
>
);
PointF
temp
;
temp
.
x
=
10.
f
;
temp
.
y
=
10.
f
;
temp
.
z
=
5.
f
;
cloud_in
->
push_back
(
temp
);
temp
.
x
=
20.
f
;
temp
.
y
=
-
10.
f
;
temp
.
z
=
15.
f
;
cloud_in
->
push_back
(
temp
);
std
::
vector
<
int
>
indices
;
indices
.
push_back
(
1
);
ExtractIndicedCloud
<
AttributePointCloud
<
PointF
>>
(
cloud_in
,
indices
,
cloud_out
);
EXPECT_NEAR
(
cloud_out
->
at
(
0
).
x
,
20.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
cloud_out
->
at
(
0
).
y
,
-
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
cloud_out
->
at
(
0
).
z
,
15.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
}
TEST
(
PointCloudProcessingCommonTest
,
get_min_max_in_3d_test
)
{
PointF
temp
;
std
::
shared_ptr
<
AttributePointCloud
<
PointF
>>
cloud
(
new
AttributePointCloud
<
PointF
>
);
temp
.
x
=
10.
f
;
temp
.
y
=
10.
f
;
temp
.
z
=
10.
f
;
cloud
->
push_back
(
temp
);
temp
.
x
=
20.
f
;
temp
.
y
=
-
10.
f
;
temp
.
z
=
5.
f
;
cloud
->
push_back
(
temp
);
temp
.
x
=
-
10.
f
;
temp
.
y
=
0.
f
;
temp
.
z
=
15.
f
;
cloud
->
push_back
(
temp
);
base
::
PointIndices
indices
;
indices
.
indices
.
push_back
(
0
);
indices
.
indices
.
push_back
(
2
);
Eigen
::
Vector4f
min_pt
,
max_pt
;
GetMinMaxIn3D
<
PointF
>
(
*
cloud
,
indices
,
&
min_pt
,
&
max_pt
);
EXPECT_NEAR
(
min_pt
(
0
),
-
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
min_pt
(
1
),
0.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
min_pt
(
2
),
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
min_pt
(
3
),
0.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
0
),
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
1
),
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
2
),
15.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
3
),
0.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
temp
.
x
=
std
::
numeric_limits
<
float
>::
quiet_NaN
();
temp
.
y
=
10.
f
;
temp
.
z
=
10.
f
;
cloud
->
push_back
(
temp
);
temp
.
x
=
10.
f
;
temp
.
y
=
std
::
numeric_limits
<
float
>::
quiet_NaN
();
temp
.
z
=
10.
f
;
cloud
->
push_back
(
temp
);
temp
.
x
=
10.
f
;
temp
.
y
=
10.
f
;
temp
.
z
=
std
::
numeric_limits
<
float
>::
quiet_NaN
();
cloud
->
push_back
(
temp
);
indices
.
indices
.
push_back
(
3
);
indices
.
indices
.
push_back
(
4
);
indices
.
indices
.
push_back
(
5
);
GetMinMaxIn3D
<
PointF
>
(
*
cloud
,
indices
,
&
min_pt
,
&
max_pt
);
EXPECT_NEAR
(
min_pt
(
0
),
-
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
min_pt
(
1
),
0.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
min_pt
(
2
),
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
min_pt
(
3
),
0.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
0
),
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
1
),
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
2
),
15.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
3
),
0.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
}
TEST
(
PointCloudProcessingCommonTest
,
get_min_max_in_3d_test2
)
{
PointF
temp
;
std
::
shared_ptr
<
AttributePointCloud
<
PointF
>>
cloud
(
new
AttributePointCloud
<
PointF
>
);
temp
.
x
=
10.
f
;
temp
.
y
=
10.
f
;
temp
.
z
=
10.
f
;
cloud
->
push_back
(
temp
);
temp
.
x
=
20.
f
;
temp
.
y
=
-
10.
f
;
temp
.
z
=
5.
f
;
cloud
->
push_back
(
temp
);
temp
.
x
=
-
10.
f
;
temp
.
y
=
0.
f
;
temp
.
z
=
15.
f
;
cloud
->
push_back
(
temp
);
base
::
PointIndices
indices
;
indices
.
indices
.
push_back
(
0
);
indices
.
indices
.
push_back
(
2
);
Eigen
::
Vector4f
min_pt
,
max_pt
;
GetMinMaxIn3D
<
PointF
>
(
*
cloud
,
&
min_pt
,
&
max_pt
);
EXPECT_NEAR
(
min_pt
(
0
),
-
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
min_pt
(
1
),
-
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
min_pt
(
2
),
5.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
min_pt
(
3
),
0.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
0
),
20.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
1
),
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
2
),
15.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
3
),
0.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
temp
.
x
=
std
::
numeric_limits
<
float
>::
quiet_NaN
();
temp
.
y
=
10.
f
;
temp
.
z
=
10.
f
;
cloud
->
push_back
(
temp
);
temp
.
x
=
10.
f
;
temp
.
y
=
std
::
numeric_limits
<
float
>::
quiet_NaN
();
temp
.
z
=
10.
f
;
cloud
->
push_back
(
temp
);
temp
.
x
=
10.
f
;
temp
.
y
=
10.
f
;
temp
.
z
=
std
::
numeric_limits
<
float
>::
quiet_NaN
();
cloud
->
push_back
(
temp
);
GetMinMaxIn3D
<
PointF
>
(
*
cloud
,
&
min_pt
,
&
max_pt
);
EXPECT_NEAR
(
min_pt
(
0
),
-
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
min_pt
(
1
),
-
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
min_pt
(
2
),
5.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
min_pt
(
3
),
0.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
0
),
20.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
1
),
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
2
),
15.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
3
),
0.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
}
TEST
(
PointCloudProcessingCommonTest
,
get_min_max_in_3d_test3
)
{
PointF
temp
;
AttributePointCloud
<
PointF
>
cloud
;
temp
.
x
=
10.
f
;
temp
.
y
=
10.
f
;
temp
.
z
=
10.
f
;
cloud
.
push_back
(
temp
);
temp
.
x
=
20.
f
;
temp
.
y
=
-
10.
f
;
temp
.
z
=
5.
f
;
cloud
.
push_back
(
temp
);
temp
.
x
=
-
10.
f
;
temp
.
y
=
0.
f
;
temp
.
z
=
15.
f
;
cloud
.
push_back
(
temp
);
base
::
PointIndices
indices
;
indices
.
indices
.
push_back
(
0
);
indices
.
indices
.
push_back
(
2
);
Eigen
::
Vector4f
min_pt
,
max_pt
;
GetMinMaxIn3D
<
PointF
>
(
cloud
,
indices
,
&
min_pt
,
&
max_pt
);
EXPECT_NEAR
(
min_pt
(
0
),
-
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
min_pt
(
1
),
0.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
min_pt
(
2
),
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
min_pt
(
3
),
0.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
0
),
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
1
),
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
2
),
15.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
3
),
0.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
temp
.
x
=
std
::
numeric_limits
<
float
>::
quiet_NaN
();
temp
.
y
=
10.
f
;
temp
.
z
=
10.
f
;
cloud
.
push_back
(
temp
);
temp
.
x
=
10.
f
;
temp
.
y
=
std
::
numeric_limits
<
float
>::
quiet_NaN
();
temp
.
z
=
10.
f
;
cloud
.
push_back
(
temp
);
temp
.
x
=
10.
f
;
temp
.
y
=
10.
f
;
temp
.
z
=
std
::
numeric_limits
<
float
>::
quiet_NaN
();
cloud
.
push_back
(
temp
);
indices
.
indices
.
push_back
(
3
);
indices
.
indices
.
push_back
(
4
);
indices
.
indices
.
push_back
(
5
);
GetMinMaxIn3D
<
PointF
>
(
cloud
,
indices
,
&
min_pt
,
&
max_pt
);
EXPECT_NEAR
(
min_pt
(
0
),
-
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
min_pt
(
1
),
0.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
min_pt
(
2
),
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
min_pt
(
3
),
0.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
0
),
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
1
),
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
2
),
15.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
3
),
0.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
}
TEST
(
PointCloudProcessingCommonTest
,
get_min_max_in_3d_test4
)
{
PointF
temp
;
AttributePointCloud
<
PointF
>
cloud
;
temp
.
x
=
10.
f
;
temp
.
y
=
10.
f
;
temp
.
z
=
10.
f
;
cloud
.
push_back
(
temp
);
temp
.
x
=
20.
f
;
temp
.
y
=
-
10.
f
;
temp
.
z
=
5.
f
;
cloud
.
push_back
(
temp
);
temp
.
x
=
-
10.
f
;
temp
.
y
=
0.
f
;
temp
.
z
=
15.
f
;
cloud
.
push_back
(
temp
);
base
::
PointIndices
indices
;
indices
.
indices
.
push_back
(
0
);
indices
.
indices
.
push_back
(
2
);
Eigen
::
Vector4f
min_pt
,
max_pt
;
GetMinMaxIn3D
<
PointF
>
(
cloud
,
&
min_pt
,
&
max_pt
);
EXPECT_NEAR
(
min_pt
(
0
),
-
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
min_pt
(
1
),
-
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
min_pt
(
2
),
5.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
min_pt
(
3
),
0.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
0
),
20.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
1
),
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
2
),
15.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
3
),
0.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
temp
.
x
=
std
::
numeric_limits
<
float
>::
quiet_NaN
();
temp
.
y
=
10.
f
;
temp
.
z
=
10.
f
;
cloud
.
push_back
(
temp
);
temp
.
x
=
10.
f
;
temp
.
y
=
std
::
numeric_limits
<
float
>::
quiet_NaN
();
temp
.
z
=
10.
f
;
cloud
.
push_back
(
temp
);
temp
.
x
=
10.
f
;
temp
.
y
=
10.
f
;
temp
.
z
=
std
::
numeric_limits
<
float
>::
quiet_NaN
();
cloud
.
push_back
(
temp
);
GetMinMaxIn3D
<
PointF
>
(
cloud
,
&
min_pt
,
&
max_pt
);
EXPECT_NEAR
(
min_pt
(
0
),
-
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
min_pt
(
1
),
-
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
min_pt
(
2
),
5.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
min_pt
(
3
),
0.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
0
),
20.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
1
),
10.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
2
),
15.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
max_pt
(
3
),
0.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
}
TEST
(
PointCloudProcessingCommonTest
,
calculate_centroid_test
)
{
std
::
shared_ptr
<
AttributePointCloud
<
PointF
>>
cloud
(
new
AttributePointCloud
<
PointF
>
);
PointF
temp
;
temp
.
x
=
10.
f
;
temp
.
y
=
10.
f
;
temp
.
z
=
5.
f
;
cloud
->
push_back
(
temp
);
temp
.
x
=
15.
f
;
temp
.
y
=
-
10.
f
;
temp
.
z
=
15.
f
;
cloud
->
push_back
(
temp
);
temp
.
x
=
-
10.
f
;
temp
.
y
=
15.
f
;
temp
.
z
=
-
5.
f
;
cloud
->
push_back
(
temp
);
Eigen
::
Matrix
<
float
,
3
,
1
>
result
=
CalculateCentroid
<
float
>
(
*
cloud
);
EXPECT_NEAR
(
result
(
0
),
5.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
result
(
1
),
5.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
EXPECT_NEAR
(
result
(
2
),
5.
f
,
std
::
numeric_limits
<
float
>::
epsilon
());
}
}
// namespace common
}
// namespace perception
}
// namespace apollo
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录