Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
7271f6d4
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 搜索 >>
提交
7271f6d4
编写于
1月 15, 2020
作者:
X
Xiangquan Xiao
提交者:
Calvin Miao
1月 16, 2020
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
Localization: Refactor unit tests with EXPECT_ instead of ASSERT_.
上级
1886a747
变更
13
隐藏空白更改
内联
并排
Showing
13 changed file
with
68 addition
and
171 deletion
+68
-171
modules/localization/msf/common/io/BUILD
modules/localization/msf/common/io/BUILD
+0
-11
modules/localization/msf/common/io/velodyne_utility_test.cc
modules/localization/msf/common/io/velodyne_utility_test.cc
+0
-38
modules/localization/msf/common/util/compression_test.cc
modules/localization/msf/common/util/compression_test.cc
+2
-11
modules/localization/msf/common/util/frame_transform_test.cc
modules/localization/msf/common/util/frame_transform_test.cc
+8
-16
modules/localization/msf/common/util/rect2d_test.cc
modules/localization/msf/common/util/rect2d_test.cc
+11
-20
modules/localization/msf/common/util/system_utility_test.cc
modules/localization/msf/common/util/system_utility_test.cc
+12
-21
modules/localization/msf/local_map/base_map/map_node_index_test.cc
...ocalization/msf/local_map/base_map/map_node_index_test.cc
+14
-25
modules/localization/msf/local_map/lossless_map/lossless_map_config_test.cc
...on/msf/local_map/lossless_map/lossless_map_config_test.cc
+4
-4
modules/localization/msf/local_map/lossless_map/map_pool_test.cc
.../localization/msf/local_map/lossless_map/map_pool_test.cc
+2
-2
modules/localization/msf/local_map/lossy_map/lossy_map_config_2d_test.cc
...ation/msf/local_map/lossy_map/lossy_map_config_2d_test.cc
+4
-4
modules/localization/ndt/localization_pose_buffer_test.cc
modules/localization/ndt/localization_pose_buffer_test.cc
+3
-3
modules/localization/ndt/ndt_localization_test.cc
modules/localization/ndt/ndt_localization_test.cc
+2
-2
modules/localization/ndt/ndt_locator/lidar_locator_ndt_test.cc
...es/localization/ndt/ndt_locator/lidar_locator_ndt_test.cc
+6
-14
未找到文件。
modules/localization/msf/common/io/BUILD
浏览文件 @
7271f6d4
...
...
@@ -14,15 +14,4 @@ cc_library(
],
)
cc_test
(
name
=
"localization_msf_velodyne_utility_test"
,
size
=
"small"
,
timeout
=
"short"
,
srcs
=
[
"velodyne_utility_test.cc"
],
deps
=
[
"//modules/localization/msf/common/io:localization_msf_common_io"
,
"@com_google_googletest//:gtest_main"
,
],
)
cpplint
()
modules/localization/msf/common/io/velodyne_utility_test.cc
已删除
100644 → 0
浏览文件 @
1886a747
/******************************************************************************
* Copyright 2017 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/localization/msf/common/io/velodyne_utility.h"
#include "gtest/gtest.h"
namespace
apollo
{
namespace
localization
{
namespace
msf
{
class
VelodyneUtilityTestSuite
:
public
::
testing
::
Test
{
protected:
VelodyneUtilityTestSuite
()
{}
virtual
~
VelodyneUtilityTestSuite
()
{}
virtual
void
SetUp
()
{}
virtual
void
TearDown
()
{}
};
/**@brief Test . */
TEST_F
(
VelodyneUtilityTestSuite
,
test
)
{
ASSERT_TRUE
(
true
);
}
}
// namespace msf
}
// namespace localization
}
// namespace apollo
modules/localization/msf/common/util/compression_test.cc
浏览文件 @
7271f6d4
...
...
@@ -22,16 +22,7 @@ namespace apollo {
namespace
localization
{
namespace
msf
{
class
CompressionTestSuite
:
public
::
testing
::
Test
{
protected:
CompressionTestSuite
()
{}
virtual
~
CompressionTestSuite
()
{}
virtual
void
SetUp
()
{}
virtual
void
TearDown
()
{}
};
/**@brief ZlibStrategyTest. */
TEST_F
(
CompressionTestSuite
,
ZlibStrategyTest
)
{
TEST
(
CompressionTestSuite
,
ZlibStrategyTest
)
{
ZlibStrategy
zlib
;
std
::
vector
<
unsigned
char
>
buf_uncompressed
;
std
::
vector
<
unsigned
char
>
buf_compressed
;
...
...
@@ -44,7 +35,7 @@ TEST_F(CompressionTestSuite, ZlibStrategyTest) {
zlib
.
Decode
(
&
buf_compressed
,
&
buf_uncompressed2
);
for
(
int
i
=
0
;
i
<
255
;
i
++
)
{
ASSER
T_EQ
(
buf_uncompressed2
[
i
],
(
unsigned
char
)
i
);
EXPEC
T_EQ
(
buf_uncompressed2
[
i
],
(
unsigned
char
)
i
);
}
}
...
...
modules/localization/msf/common/util/frame_transform_test.cc
浏览文件 @
7271f6d4
...
...
@@ -22,32 +22,24 @@ namespace apollo {
namespace
localization
{
namespace
msf
{
class
FrameTransformTestSuite
:
public
::
testing
::
Test
{
protected:
FrameTransformTestSuite
()
{}
virtual
~
FrameTransformTestSuite
()
{}
virtual
void
SetUp
()
{}
virtual
void
TearDown
()
{}
};
TEST_F
(
FrameTransformTestSuite
,
LatlonToUtmXYTest
)
{
TEST
(
FrameTransformTestSuite
,
LatlonToUtmXYTest
)
{
double
lon_rad
=
-
2.129343746458001
;
double
lat_rad
=
0.6530018835651807
;
UTMCoor
utm_xy
;
ASSER
T_TRUE
(
FrameTransform
::
LatlonToUtmXY
(
lon_rad
,
lat_rad
,
&
utm_xy
));
ASSER
T_LT
(
std
::
fabs
(
utm_xy
.
x
-
588278.9834174265
),
1e-5
);
ASSER
T_LT
(
std
::
fabs
(
utm_xy
.
y
-
4141295.255870659
),
1e-5
);
EXPEC
T_TRUE
(
FrameTransform
::
LatlonToUtmXY
(
lon_rad
,
lat_rad
,
&
utm_xy
));
EXPEC
T_LT
(
std
::
fabs
(
utm_xy
.
x
-
588278.9834174265
),
1e-5
);
EXPEC
T_LT
(
std
::
fabs
(
utm_xy
.
y
-
4141295.255870659
),
1e-5
);
}
TEST
_F
(
FrameTransformTestSuite
,
UtmXYToLatlonTest
)
{
TEST
(
FrameTransformTestSuite
,
UtmXYToLatlonTest
)
{
double
x
=
588278.9834174265
;
double
y
=
4141295.255870659
;
int
zone
=
10
;
bool
southhemi
=
false
;
WGS84Corr
latlon
;
ASSER
T_TRUE
(
FrameTransform
::
UtmXYToLatlon
(
x
,
y
,
zone
,
southhemi
,
&
latlon
));
ASSER
T_LT
(
std
::
fabs
(
latlon
.
log
+
2.129343746458001
),
1e-5
);
ASSER
T_LT
(
std
::
fabs
(
latlon
.
lat
-
0.6530018835651807
),
1e-5
);
EXPEC
T_TRUE
(
FrameTransform
::
UtmXYToLatlon
(
x
,
y
,
zone
,
southhemi
,
&
latlon
));
EXPEC
T_LT
(
std
::
fabs
(
latlon
.
log
+
2.129343746458001
),
1e-5
);
EXPEC
T_LT
(
std
::
fabs
(
latlon
.
lat
-
0.6530018835651807
),
1e-5
);
}
}
// namespace msf
...
...
modules/localization/msf/common/util/rect2d_test.cc
浏览文件 @
7271f6d4
...
...
@@ -22,38 +22,29 @@ namespace apollo {
namespace
localization
{
namespace
msf
{
class
Rect2DTestSuite
:
public
::
testing
::
Test
{
protected:
Rect2DTestSuite
()
{}
virtual
~
Rect2DTestSuite
()
{}
virtual
void
SetUp
()
{}
virtual
void
TearDown
()
{}
};
/**@brief Rect2DTest. */
TEST_F
(
Rect2DTestSuite
,
Rect2DTest
)
{
TEST
(
Rect2DTestSuite
,
Rect2DTest
)
{
Rect2D
<
double
>
rect_a
(
0.5
,
0.5
,
1.0
,
1.0
);
double
min_x
=
rect_a
.
GetMinX
();
double
min_y
=
rect_a
.
GetMinY
();
double
max_x
=
rect_a
.
GetMaxX
();
double
max_y
=
rect_a
.
GetMaxY
();
ASSER
T_LT
(
std
::
abs
(
min_x
-
0.5
),
1e-5
);
ASSER
T_LT
(
std
::
abs
(
min_y
-
0.5
),
1e-5
);
ASSER
T_LT
(
std
::
abs
(
max_x
-
1.0
),
1e-5
);
ASSER
T_LT
(
std
::
abs
(
max_y
-
1.0
),
1e-5
);
EXPEC
T_LT
(
std
::
abs
(
min_x
-
0.5
),
1e-5
);
EXPEC
T_LT
(
std
::
abs
(
min_y
-
0.5
),
1e-5
);
EXPEC
T_LT
(
std
::
abs
(
max_x
-
1.0
),
1e-5
);
EXPEC
T_LT
(
std
::
abs
(
max_y
-
1.0
),
1e-5
);
Eigen
::
Matrix
<
double
,
2
,
1
>
lt_corner
=
rect_a
.
GetLeftTopCorner
();
Eigen
::
Matrix
<
double
,
2
,
1
>
rb_corner
=
rect_a
.
GetRightBottomCorner
();
ASSER
T_LT
(
std
::
abs
(
lt_corner
(
0
)
-
0.5
),
1e-5
);
ASSER
T_LT
(
std
::
abs
(
lt_corner
(
1
)
-
0.5
),
1e-5
);
ASSER
T_LT
(
std
::
abs
(
rb_corner
(
0
)
-
1.0
),
1e-5
);
ASSER
T_LT
(
std
::
abs
(
rb_corner
(
1
)
-
1.0
),
1e-5
);
EXPEC
T_LT
(
std
::
abs
(
lt_corner
(
0
)
-
0.5
),
1e-5
);
EXPEC
T_LT
(
std
::
abs
(
lt_corner
(
1
)
-
0.5
),
1e-5
);
EXPEC
T_LT
(
std
::
abs
(
rb_corner
(
0
)
-
1.0
),
1e-5
);
EXPEC
T_LT
(
std
::
abs
(
rb_corner
(
1
)
-
1.0
),
1e-5
);
Rect2D
<
double
>
rect_b
(
rect_a
);
ASSER
T_LT
(
std
::
abs
(
rect_b
.
GetMinX
()
-
0.5
),
1e-5
);
EXPEC
T_LT
(
std
::
abs
(
rect_b
.
GetMinX
()
-
0.5
),
1e-5
);
Rect2D
<
double
>
rect_c
=
rect_b
;
ASSER
T_LT
(
std
::
abs
(
rect_c
.
GetMinX
()
-
0.5
),
1e-5
);
EXPEC
T_LT
(
std
::
abs
(
rect_c
.
GetMinX
()
-
0.5
),
1e-5
);
}
}
// namespace msf
...
...
modules/localization/msf/common/util/system_utility_test.cc
浏览文件 @
7271f6d4
...
...
@@ -23,54 +23,45 @@ namespace apollo {
namespace
localization
{
namespace
msf
{
class
SystemUtilityTestSuite
:
public
::
testing
::
Test
{
protected:
SystemUtilityTestSuite
()
{}
virtual
~
SystemUtilityTestSuite
()
{}
virtual
void
SetUp
()
{}
virtual
void
TearDown
()
{}
};
/**@brief Rect2DTest. */
TEST_F
(
SystemUtilityTestSuite
,
SystemTest
)
{
TEST
(
SystemUtilityTestSuite
,
SystemTest
)
{
bool
flag
=
system
::
IsExists
(
"/apollo/modules/localization/msf/common/test_data/test_folder/"
"file1.txt"
);
ASSER
T_TRUE
(
flag
);
EXPEC
T_TRUE
(
flag
);
flag
=
system
::
IsExists
(
"/apollo/modules/localization/msf/common/test_data/file4.txt"
);
ASSER
T_FALSE
(
flag
);
EXPEC
T_FALSE
(
flag
);
flag
=
system
::
IsDirectory
(
"/apollo/modules/localization/msf/common/test_data"
);
ASSER
T_TRUE
(
flag
);
EXPEC
T_TRUE
(
flag
);
flag
=
system
::
IsDirectory
(
"/apollo/modules/localization/msf/common/test"
);
ASSER
T_FALSE
(
flag
);
EXPEC
T_FALSE
(
flag
);
flag
=
system
::
CreateDirectory
(
"/apollo/modules/localization/msf/common/test_data/tem"
);
ASSER
T_TRUE
(
flag
);
EXPEC
T_TRUE
(
flag
);
unsigned
int
size
;
flag
=
system
::
GetFileSize
(
"/apollo/modules/localization/msf/common/test_data/test_folder/file1.txt"
,
&
size
);
ASSER
T_TRUE
(
flag
);
ASSER
T_EQ
(
size
,
1
);
EXPEC
T_TRUE
(
flag
);
EXPEC
T_EQ
(
size
,
1
);
flag
=
system
::
CopyFile
(
"/apollo/modules/localization/msf/common/test_data/test_folder/file1.txt"
,
"/apollo/modules/localization/msf/common/test_data/tem/file1.txt"
);
ASSER
T_TRUE
(
flag
);
EXPEC
T_TRUE
(
flag
);
std
::
vector
<
std
::
string
>
ret1
;
system
::
GetFilesInFolderRecursive
(
"/apollo/modules/localization/msf/common/test_data"
,
".txt"
,
&
ret1
);
ASSER
T_EQ
(
ret1
.
size
(),
4
);
EXPEC
T_EQ
(
ret1
.
size
(),
4
);
std
::
vector
<
std
::
string
>
ret2
;
system
::
GetFilesInFolder
(
"/apollo/modules/localization/msf/common/test_data/test_folder"
,
".txt"
,
&
ret2
);
ASSER
T_EQ
(
ret2
.
size
(),
3
);
EXPEC
T_EQ
(
ret2
.
size
(),
3
);
std
::
vector
<
std
::
string
>
ret3
;
system
::
GetFoldersInFolder
(
"/apollo/modules/localization/msf/common/test_data/"
,
&
ret3
);
ASSER
T_EQ
(
ret3
.
size
(),
2
);
EXPEC
T_EQ
(
ret3
.
size
(),
2
);
boost
::
filesystem
::
remove_all
(
"/apollo/modules/localization/msf/common/test_data/tem"
);
}
...
...
modules/localization/msf/local_map/base_map/map_node_index_test.cc
浏览文件 @
7271f6d4
...
...
@@ -22,21 +22,13 @@ namespace apollo {
namespace
localization
{
namespace
msf
{
class
BaseMapNodeIndexTestSuite
:
public
::
testing
::
Test
{
protected:
BaseMapNodeIndexTestSuite
()
{}
virtual
~
BaseMapNodeIndexTestSuite
()
{}
virtual
void
SetUp
()
{}
virtual
void
TearDown
()
{}
};
/**@brief Test the get method. */
TEST
_F
(
BaseMapNodeIndexTestSuite
,
GetMethodTest
)
{
TEST
(
BaseMapNodeIndexTestSuite
,
GetMethodTest
)
{
MapNodeIndex
node_index
;
ASSER
T_EQ
(
node_index
.
resolution_id_
,
0
);
ASSER
T_EQ
(
node_index
.
zone_id_
,
50
);
ASSER
T_EQ
(
node_index
.
m_
,
0
);
ASSER
T_EQ
(
node_index
.
n_
,
0
);
EXPEC
T_EQ
(
node_index
.
resolution_id_
,
0
);
EXPEC
T_EQ
(
node_index
.
zone_id_
,
50
);
EXPEC
T_EQ
(
node_index
.
m_
,
0
);
EXPEC
T_EQ
(
node_index
.
n_
,
0
);
BaseMapConfig
option
;
option
.
map_resolutions_
.
push_back
(
0.125
);
...
...
@@ -49,32 +41,29 @@ TEST_F(BaseMapNodeIndexTestSuite, GetMethodTest) {
MapNodeIndex
node_index2
=
MapNodeIndex
::
GetMapNodeIndex
(
option
,
coordinate2d
,
0
,
50
);
ASSER
T_TRUE
(
node_index1
==
node_index2
);
EXPEC
T_TRUE
(
node_index1
==
node_index2
);
}
/**@brief Test the operators. */
TEST
_F
(
BaseMapNodeIndexTestSuite
,
OperatorTest
)
{
TEST
(
BaseMapNodeIndexTestSuite
,
OperatorTest
)
{
MapNodeIndex
node_index1
;
ASSER
T_EQ
(
node_index1
.
resolution_id_
,
0
);
ASSER
T_EQ
(
node_index1
.
zone_id_
,
50
);
ASSER
T_EQ
(
node_index1
.
m_
,
0
);
ASSER
T_EQ
(
node_index1
.
n_
,
0
);
EXPEC
T_EQ
(
node_index1
.
resolution_id_
,
0
);
EXPEC
T_EQ
(
node_index1
.
zone_id_
,
50
);
EXPEC
T_EQ
(
node_index1
.
m_
,
0
);
EXPEC
T_EQ
(
node_index1
.
n_
,
0
);
MapNodeIndex
node_index2
;
node_index2
.
n_
=
1
;
bool
res
=
node_index1
<
node_index2
;
ASSER
T_TRUE
(
res
);
EXPEC
T_TRUE
(
res
);
res
=
node_index1
!=
node_index2
;
ASSER
T_TRUE
(
res
);
EXPEC
T_TRUE
(
res
);
node_index2
.
n_
=
0
;
res
=
node_index1
==
node_index2
;
ASSERT_TRUE
(
res
);
std
::
cout
<<
node_index2
<<
std
::
endl
;
ASSERT_TRUE
(
true
);
EXPECT_TRUE
(
res
);
}
}
// namespace msf
...
...
modules/localization/msf/local_map/lossless_map/lossless_map_config_test.cc
浏览文件 @
7271f6d4
...
...
@@ -25,11 +25,11 @@ namespace msf {
/**@brief Test load and set methods in LosslessMapConfig. */
TEST
(
LosslessMapConfigTestSuite
,
LoadSetTest
)
{
BaseMapConfig
config
(
"lossless_map"
);
ASSER
T_TRUE
(
EXPEC
T_TRUE
(
config
.
Load
(
"/apollo/modules/localization/msf/local_map/"
"test_data/lossless_single_map/config.xml"
));
config
.
SetMultiResolutions
();
ASSER
T_EQ
(
config
.
map_resolutions_
.
size
(),
10
);
EXPEC
T_EQ
(
config
.
map_resolutions_
.
size
(),
10
);
EXPECT_DOUBLE_EQ
(
config
.
map_resolutions_
[
0
],
0.03125
);
config
.
ResizeMapRange
();
...
...
@@ -39,7 +39,7 @@ TEST(LosslessMapConfigTestSuite, LoadSetTest) {
EXPECT_DOUBLE_EQ
(
config
.
map_range_
.
GetMaxY
(),
630.0
*
16.0
*
1024
);
config
.
SetSingleResolutions
();
ASSER
T_EQ
(
config
.
map_resolutions_
.
size
(),
1
);
EXPEC
T_EQ
(
config
.
map_resolutions_
.
size
(),
1
);
EXPECT_DOUBLE_EQ
(
config
.
map_resolutions_
[
0
],
0.125
);
BaseMapConfig
config2
;
...
...
@@ -51,7 +51,7 @@ TEST(LosslessMapConfigTestSuite, LoadSetTest) {
/**@brief Test save method. */
TEST
(
LosslessMapConfigTestSuite
,
SaveTest
)
{
BaseMapConfig
config
(
"lossless_map"
);
ASSER
T_TRUE
(
EXPEC
T_TRUE
(
config
.
Load
(
"/apollo/modules/localization/msf/local_map/"
"test_data/lossless_single_map/config.xml"
));
EXPECT_TRUE
(
config
.
Save
(
"/tmp/temp_output_file.xml"
));
...
...
modules/localization/msf/local_map/lossless_map/map_pool_test.cc
浏览文件 @
7271f6d4
...
...
@@ -48,11 +48,11 @@ TEST_F(BaseMapPoolTestSuite, MapNodePoolTest) {
pool
.
FreeMapNodeTask
(
node3
);
unsigned
int
pool_size
=
pool
.
GetPoolSize
();
ASSER
T_EQ
(
pool_size
,
3
);
EXPEC
T_EQ
(
pool_size
,
3
);
pool
.
Release
();
pool_size
=
pool
.
GetPoolSize
();
ASSER
T_EQ
(
pool_size
,
0
);
EXPEC
T_EQ
(
pool_size
,
0
);
}
}
// namespace msf
...
...
modules/localization/msf/local_map/lossy_map/lossy_map_config_2d_test.cc
浏览文件 @
7271f6d4
...
...
@@ -25,11 +25,11 @@ namespace msf {
/**@brief Test load and set methods in LossyMapConfig2D. */
TEST
(
LossyMapConfig2DTestSuite
,
LoadSetTest
)
{
BaseMapConfig
config
(
"lossy_map"
);
ASSER
T_TRUE
(
EXPEC
T_TRUE
(
config
.
Load
(
"/apollo/modules/localization/msf/local_map/"
"test_data/lossy_single_map/config.xml"
));
config
.
SetMultiResolutions
();
ASSER
T_EQ
(
config
.
map_resolutions_
.
size
(),
10
);
EXPEC
T_EQ
(
config
.
map_resolutions_
.
size
(),
10
);
EXPECT_DOUBLE_EQ
(
config
.
map_resolutions_
[
0
],
0.03125
);
config
.
ResizeMapRange
();
...
...
@@ -39,7 +39,7 @@ TEST(LossyMapConfig2DTestSuite, LoadSetTest) {
EXPECT_DOUBLE_EQ
(
config
.
map_range_
.
GetMaxY
(),
630.0
*
16.0
*
1024
);
config
.
SetSingleResolutions
();
ASSER
T_EQ
(
config
.
map_resolutions_
.
size
(),
1
);
EXPEC
T_EQ
(
config
.
map_resolutions_
.
size
(),
1
);
EXPECT_DOUBLE_EQ
(
config
.
map_resolutions_
[
0
],
0.125
);
BaseMapConfig
config2
;
...
...
@@ -51,7 +51,7 @@ TEST(LossyMapConfig2DTestSuite, LoadSetTest) {
/**@brief Test save method. */
TEST
(
LossyMapConfig2DTestSuite
,
SaveTest
)
{
BaseMapConfig
config
(
"lossy_map"
);
ASSER
T_TRUE
(
EXPEC
T_TRUE
(
config
.
Load
(
"/apollo/modules/localization/msf/local_map/"
"test_data/lossy_single_map/config.xml"
));
EXPECT_TRUE
(
config
.
Save
(
"/tmp/temp_output_file.xml"
));
...
...
modules/localization/ndt/localization_pose_buffer_test.cc
浏览文件 @
7271f6d4
...
...
@@ -44,8 +44,8 @@ TEST_F(NDTLocalizationTest, UpdateLidarPose) {
pose_buffer_ptr_
->
UpdateLidarPose
(
time_now
,
lidar_pose
,
odometry_pose
);
time_now
=
apollo
::
common
::
time
::
Clock
::
NowInSeconds
();
pose_buffer_ptr_
->
UpdateLidarPose
(
time_now
,
lidar_pose
,
odometry_pose
);
ASSER
T_EQ
(
pose_buffer_ptr_
->
GetUsedBufferSize
(),
2
);
ASSER
T_EQ
(
pose_buffer_ptr_
->
GetHeadIndex
(),
0
);
EXPEC
T_EQ
(
pose_buffer_ptr_
->
GetUsedBufferSize
(),
2
);
EXPEC
T_EQ
(
pose_buffer_ptr_
->
GetHeadIndex
(),
0
);
}
TEST_F
(
NDTLocalizationTest
,
UpdateOdometryPose
)
{
...
...
@@ -62,7 +62,7 @@ TEST_F(NDTLocalizationTest, UpdateOdometryPose) {
time_now
=
apollo
::
common
::
time
::
Clock
::
NowInSeconds
();
Eigen
::
Affine3d
pose
=
pose_buffer_ptr_
->
UpdateOdometryPose
(
time_now
,
odometry_pose
);
ASSER
T_LE
(
std
::
abs
(
pose
.
translation
()[
0
]
-
1.0
),
1e-5
);
EXPEC
T_LE
(
std
::
abs
(
pose
.
translation
()[
0
]
-
1.0
),
1e-5
);
}
}
// namespace ndt
...
...
modules/localization/ndt/ndt_localization_test.cc
浏览文件 @
7271f6d4
...
...
@@ -41,8 +41,8 @@ TEST_F(NDTLocalizationTest, Init) {
FLAGS_local_utm_zone_id
=
10
;
FLAGS_online_resolution
=
0.25
;
ndt_localization_ptr_
->
Init
();
ASSER
T_EQ
(
ndt_localization_ptr_
->
GetZoneId
(),
10
);
ASSER
T_LE
(
std
::
abs
(
ndt_localization_ptr_
->
GetOnlineResolution
()
-
0.25
),
EXPEC
T_EQ
(
ndt_localization_ptr_
->
GetZoneId
(),
10
);
EXPEC
T_LE
(
std
::
abs
(
ndt_localization_ptr_
->
GetOnlineResolution
()
-
0.25
),
0.01
);
}
...
...
modules/localization/ndt/ndt_locator/lidar_locator_ndt_test.cc
浏览文件 @
7271f6d4
...
...
@@ -31,15 +31,7 @@ namespace apollo {
namespace
localization
{
namespace
ndt
{
class
LidarLocatorNdtTestSuite
:
public
::
testing
::
Test
{
protected:
LidarLocatorNdtTestSuite
()
{}
virtual
~
LidarLocatorNdtTestSuite
()
{}
virtual
void
SetUp
()
{}
virtual
void
TearDown
()
{}
};
TEST_F
(
LidarLocatorNdtTestSuite
,
LidarLocatorNdt
)
{
TEST
(
LidarLocatorNdtTestSuite
,
LidarLocatorNdt
)
{
const
std
::
string
map_folder
=
"/apollo/modules/localization/ndt/test_data/ndt_map"
;
const
std
::
string
poses_file
=
...
...
@@ -90,14 +82,14 @@ TEST_F(LidarLocatorNdtTestSuite, LidarLocatorNdt) {
lidar_frame
.
intensities
.
push_back
(
intensities
[
i
]);
}
int
ret
=
locator
.
Update
(
0
,
poses
[
frame_idx
],
lidar_frame
);
ASSER
T_LE
(
std
::
fabs
(
ret
-
0
),
1e-6
);
EXPEC
T_LE
(
std
::
fabs
(
ret
-
0
),
1e-6
);
location
=
locator
.
GetPose
();
}
ASSER
T_LE
(
std
::
fabs
(
location
.
translation
()[
0
]
-
588349.337377345
),
0.1
);
ASSER
T_LE
(
std
::
fabs
(
location
.
translation
()[
1
]
-
4141239.53859664
),
0.1
);
ASSER
T_LE
(
std
::
fabs
(
location
.
translation
()[
2
]
+
30.0964486966756
),
0.1
);
ASSER
T_EQ
(
frame_idx
,
2
);
EXPEC
T_LE
(
std
::
fabs
(
location
.
translation
()[
0
]
-
588349.337377345
),
0.1
);
EXPEC
T_LE
(
std
::
fabs
(
location
.
translation
()[
1
]
-
4141239.53859664
),
0.1
);
EXPEC
T_LE
(
std
::
fabs
(
location
.
translation
()[
2
]
+
30.0964486966756
),
0.1
);
EXPEC
T_EQ
(
frame_idx
,
2
);
}
}
// namespace ndt
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录