Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
8602c01e
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 搜索 >>
提交
8602c01e
编写于
7月 20, 2020
作者:
J
Jiahao Chen
提交者:
Liu Jiaming
7月 21, 2020
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
Perception: simplify using Eigen
上级
e9346c64
变更
13
隐藏空白更改
内联
并排
Showing
13 changed file
with
62 addition
and
97 deletion
+62
-97
modules/common/util/eigen_defs.h
modules/common/util/eigen_defs.h
+7
-0
modules/perception/base/BUILD
modules/perception/base/BUILD
+3
-0
modules/perception/base/hdmap_struct.h
modules/perception/base/hdmap_struct.h
+5
-13
modules/perception/common/geometry/BUILD
modules/perception/common/geometry/BUILD
+1
-0
modules/perception/common/geometry/basic_test.cc
modules/perception/common/geometry/basic_test.cc
+2
-2
modules/perception/common/geometry/common.h
modules/perception/common/geometry/common.h
+5
-6
modules/perception/lidar/lib/classifier/fused_classifier/BUILD
...es/perception/lidar/lib/classifier/fused_classifier/BUILD
+2
-0
modules/perception/lidar/lib/classifier/fused_classifier/ccrf_type_fusion.h
.../lidar/lib/classifier/fused_classifier/ccrf_type_fusion.h
+8
-9
modules/perception/lidar/lib/classifier/fused_classifier/util.cc
.../perception/lidar/lib/classifier/fused_classifier/util.cc
+1
-3
modules/perception/lidar/lib/classifier/fused_classifier/util.h
...s/perception/lidar/lib/classifier/fused_classifier/util.h
+4
-5
modules/perception/lidar/lib/detection/lidar_point_pillars/point_pillars_detection.cc
.../detection/lidar_point_pillars/point_pillars_detection.cc
+2
-2
modules/perception/map/hdmap/hdmap_input.cc
modules/perception/map/hdmap/hdmap_input.cc
+11
-31
modules/perception/map/hdmap/hdmap_input.h
modules/perception/map/hdmap/hdmap_input.h
+11
-26
未找到文件。
modules/common/util/eigen_defs.h
浏览文件 @
8602c01e
...
...
@@ -16,7 +16,10 @@
#pragma once
#include <functional>
#include <map>
#include <vector>
#include <utility>
#include "Eigen/Geometry"
...
...
@@ -28,6 +31,10 @@ namespace common {
template
<
class
EigenType
>
using
EigenVector
=
std
::
vector
<
EigenType
,
Eigen
::
aligned_allocator
<
EigenType
>>
;
template
<
typename
T
,
class
EigenType
>
using
EigenMap
=
std
::
map
<
T
,
EigenType
,
std
::
less
<
T
>
,
Eigen
::
aligned_allocator
<
std
::
pair
<
const
T
,
EigenType
>>>
;
using
EigenVector3dVec
=
EigenVector
<
Eigen
::
Vector3d
>
;
using
EigenAffine3dVec
=
EigenVector
<
Eigen
::
Affine3d
>
;
...
...
modules/perception/base/BUILD
浏览文件 @
8602c01e
...
...
@@ -36,6 +36,9 @@ cc_library(
"sensor_meta.h"
,
"vehicle_struct.h"
,
],
deps
=
[
"//modules/common/util:eigen_defs"
,
],
)
cc_library
(
...
...
modules/perception/base/hdmap_struct.h
浏览文件 @
8602c01e
...
...
@@ -18,8 +18,7 @@
#include <memory>
#include <vector>
#include "Eigen/StdVector"
#include "modules/common/util/eigen_defs.h"
#include "modules/perception/base/point_cloud.h"
namespace
apollo
{
...
...
@@ -37,17 +36,10 @@ struct alignas(16) LaneBoundary {
};
struct
alignas
(
16
)
HdmapStruct
{
std
::
vector
<
RoadBoundary
,
Eigen
::
aligned_allocator
<
RoadBoundary
>
>
road_boundary
;
std
::
vector
<
PointCloud
<
PointD
>
,
Eigen
::
aligned_allocator
<
PointCloud
<
PointD
>
>
>
road_polygons
;
std
::
vector
<
PointCloud
<
PointD
>
,
Eigen
::
aligned_allocator
<
PointCloud
<
PointD
>
>
>
hole_polygons
;
std
::
vector
<
PointCloud
<
PointD
>
,
Eigen
::
aligned_allocator
<
PointCloud
<
PointD
>
>
>
junction_polygons
;
apollo
::
common
::
EigenVector
<
RoadBoundary
>
road_boundary
;
apollo
::
common
::
EigenVector
<
PointCloud
<
PointD
>>
road_polygons
;
apollo
::
common
::
EigenVector
<
PointCloud
<
PointD
>>
hole_polygons
;
apollo
::
common
::
EigenVector
<
PointCloud
<
PointD
>>
junction_polygons
;
};
using
HdmapStructPtr
=
std
::
shared_ptr
<
HdmapStruct
>
;
...
...
modules/perception/common/geometry/BUILD
浏览文件 @
8602c01e
...
...
@@ -16,6 +16,7 @@ cc_library(
name
=
"common"
,
hdrs
=
[
"common.h"
],
deps
=
[
"//modules/common/util:eigen_defs"
,
"//modules/perception/base:box"
,
"//modules/perception/base:point_cloud"
,
],
...
...
modules/perception/common/geometry/basic_test.cc
浏览文件 @
8602c01e
...
...
@@ -16,6 +16,7 @@
#include "modules/perception/common/geometry/basic.h"
#include "gtest/gtest.h"
#include "modules/common/util/eigen_defs.h"
#include "modules/perception/base/point_cloud.h"
#include "modules/perception/common/geometry/common.h"
...
...
@@ -347,8 +348,7 @@ TEST(GeometryCommonTest, calculate_dist_and_dir_to_boundary) {
TEST
(
GeometryCommonTest
,
calculate_dist_and_dir_to_boundary_lists
)
{
Eigen
::
Vector3f
pt
(
0.0
,
0.0
,
0.0
);
PointCloud
<
PointF
>
left
,
right
;
std
::
vector
<
PointCloud
<
PointF
>
,
Eigen
::
aligned_allocator
<
PointCloud
<
PointF
>>>
left_list
,
right_list
;
apollo
::
common
::
EigenVector
<
PointCloud
<
PointF
>>
left_list
,
right_list
;
base
::
PointF
temp
;
temp
.
x
=
10.
f
;
temp
.
y
=
0.
f
;
...
...
modules/perception/common/geometry/common.h
浏览文件 @
8602c01e
...
...
@@ -21,9 +21,12 @@
#include <vector>
#include "Eigen/Core"
#include "modules/common/util/eigen_defs.h"
#include "modules/perception/base/box.h"
#include "modules/perception/base/point_cloud.h"
using
apollo
::
common
::
EigenVector
;
namespace
apollo
{
namespace
perception
{
namespace
common
{
...
...
@@ -310,12 +313,8 @@ void CalculateDistAndDirToBoundary(
template
<
typename
PointT
>
void
CalculateDistAndDirToBoundary
(
const
Eigen
::
Matrix
<
typename
PointT
::
Type
,
3
,
1
>
&
pt
,
const
std
::
vector
<
base
::
PointCloud
<
PointT
>
,
Eigen
::
aligned_allocator
<
base
::
PointCloud
<
PointT
>>>
&
left_boundary
,
const
std
::
vector
<
base
::
PointCloud
<
PointT
>
,
Eigen
::
aligned_allocator
<
base
::
PointCloud
<
PointT
>>>
&
right_boundary
,
const
EigenVector
<
base
::
PointCloud
<
PointT
>>
&
left_boundary
,
const
EigenVector
<
base
::
PointCloud
<
PointT
>>
&
right_boundary
,
typename
PointT
::
Type
*
dist
,
Eigen
::
Matrix
<
typename
PointT
::
Type
,
3
,
1
>
*
dir
)
{
using
Type
=
typename
PointT
::
Type
;
...
...
modules/perception/lidar/lib/classifier/fused_classifier/BUILD
浏览文件 @
8602c01e
...
...
@@ -9,6 +9,7 @@ cc_library(
hdrs
=
[
"util.h"
],
deps
=
[
"//cyber"
,
"//modules/common/util:eigen_defs"
,
"//modules/perception/base:object"
,
"@eigen"
,
],
...
...
@@ -32,6 +33,7 @@ cc_library(
":type_fusion_interface"
,
":util"
,
"//cyber"
,
"//modules/common/util:eigen_defs"
,
"//modules/perception/base:object"
,
"//modules/perception/base:point_cloud"
,
"//modules/perception/lib/config_manager"
,
...
...
modules/perception/lidar/lib/classifier/fused_classifier/ccrf_type_fusion.h
浏览文件 @
8602c01e
...
...
@@ -18,14 +18,15 @@
#include <map>
#include <memory>
#include <string>
#include <utility>
#include <vector>
#include "Eigen/StdVector"
#include "modules/common/util/eigen_defs.h"
#include "modules/perception/lidar/lib/classifier/fused_classifier/type_fusion_interface.h"
#include "modules/perception/lidar/lib/classifier/fused_classifier/util.h"
using
apollo
::
common
::
EigenMap
;
using
apollo
::
common
::
EigenVector
;
namespace
apollo
{
namespace
perception
{
namespace
lidar
{
...
...
@@ -43,9 +44,7 @@ class CCRFOneShotTypeFusion : public BaseOneShotTypeFusion {
Vectord
*
log_prob
);
protected:
std
::
map
<
std
::
string
,
Matrixd
,
std
::
less
<
std
::
string
>
,
Eigen
::
aligned_allocator
<
std
::
pair
<
const
std
::
string
,
Matrixd
>>>
smooth_matrices_
;
EigenMap
<
std
::
string
,
Matrixd
>
smooth_matrices_
;
Matrixd
confidence_smooth_matrix_
;
};
...
...
@@ -82,9 +81,9 @@ class CCRFSequenceTypeFusion : public BaseSequenceTypeFusion {
Matrixd
transition_matrix_
;
// data member for window inference version
std
::
vector
<
Vectord
,
Eigen
::
aligned_allocator
<
Vectord
>
>
fused_oneshot_probs_
;
std
::
vector
<
Vectord
,
Eigen
::
aligned_allocator
<
Vectord
>
>
fused_sequence_probs_
;
std
::
vector
<
Vectori
,
Eigen
::
aligned_allocator
<
Vectori
>
>
state_back_trace_
;
EigenVector
<
Vectord
>
fused_oneshot_probs_
;
EigenVector
<
Vectord
>
fused_sequence_probs_
;
EigenVector
<
Vectori
>
state_back_trace_
;
protected:
double
s_alpha_
=
1.8
;
...
...
modules/perception/lidar/lib/classifier/fused_classifier/util.cc
浏览文件 @
8602c01e
...
...
@@ -104,9 +104,7 @@ bool LoadSingleMatrixFile(const std::string& filename, Matrixd* matrix) {
bool
LoadMultipleMatricesFile
(
const
std
::
string
&
filename
,
std
::
map
<
std
::
string
,
Matrixd
,
std
::
less
<
std
::
string
>
,
Eigen
::
aligned_allocator
<
std
::
pair
<
const
std
::
string
,
Matrixd
>
>
>*
matrices
)
{
EigenMap
<
std
::
string
,
Matrixd
>*
matrices
)
{
if
(
matrices
==
nullptr
)
{
return
false
;
}
...
...
modules/perception/lidar/lib/classifier/fused_classifier/util.h
浏览文件 @
8602c01e
...
...
@@ -19,13 +19,15 @@
#include <functional>
#include <map>
#include <string>
#include <utility>
#include <vector>
#include "Eigen/Dense"
#include "modules/common/util/eigen_defs.h"
#include "modules/perception/base/object_types.h"
using
apollo
::
common
::
EigenMap
;
namespace
apollo
{
namespace
perception
{
namespace
lidar
{
...
...
@@ -59,10 +61,7 @@ bool LoadSingleMatrix(std::ifstream& fin, Matrixd* matrix);
bool
LoadSingleMatrixFile
(
const
std
::
string
&
filename
,
Matrixd
*
matrix
);
bool
LoadMultipleMatricesFile
(
const
std
::
string
&
filename
,
std
::
map
<
std
::
string
,
Matrixd
,
std
::
less
<
std
::
string
>
,
Eigen
::
aligned_allocator
<
std
::
pair
<
const
std
::
string
,
Matrixd
>
>
>*
matrices
);
const
std
::
string
&
filename
,
EigenMap
<
std
::
string
,
Matrixd
>*
matrices
);
}
// namespace util
}
// namespace lidar
...
...
modules/perception/lidar/lib/detection/lidar_point_pillars/point_pillars_detection.cc
浏览文件 @
8602c01e
...
...
@@ -78,8 +78,8 @@ bool PointPillarsDetection::Detect(const DetectionOptions& options,
Timer
timer
;
int
num_points
;
// cur_cloud_ptr_ = std::make_shared<base::PointFCloud>(*original_cloud_);
cur_cloud_ptr_
=
original_cloud_
;
// TODO(chenjiahao): for emergency use
cur_cloud_ptr_
=
std
::
shared_ptr
<
base
::
PointFCloud
>
(
new
base
::
PointFCloud
(
*
original_cloud_
));
// down sample the point cloud through filtering beams
if
(
FLAGS_enable_downsample_beams
)
{
...
...
modules/perception/map/hdmap/hdmap_input.cc
浏览文件 @
8602c01e
...
...
@@ -130,8 +130,7 @@ bool HDMapInput::GetRoiHDMapStruct(
hdmap_struct_ptr
->
road_polygons
.
clear
();
// Merge boundary and junction
std
::
vector
<
base
::
RoadBoundary
,
Eigen
::
aligned_allocator
<
base
::
RoadBoundary
>
>
road_boundaries
;
EigenVector
<
base
::
RoadBoundary
>
road_boundaries
;
MergeBoundaryJunction
(
road_boundary_vec
,
junctions_vec
,
&
road_boundaries
,
&
(
hdmap_struct_ptr
->
road_polygons
),
&
(
hdmap_struct_ptr
->
junction_polygons
));
...
...
@@ -145,14 +144,9 @@ bool HDMapInput::GetRoiHDMapStruct(
void
HDMapInput
::
MergeBoundaryJunction
(
const
std
::
vector
<
apollo
::
hdmap
::
RoadRoiPtr
>&
boundary
,
const
std
::
vector
<
apollo
::
hdmap
::
JunctionInfoConstPtr
>&
junctions
,
std
::
vector
<
RoadBoundary
,
Eigen
::
aligned_allocator
<
RoadBoundary
>
>*
road_boundaries_ptr
,
std
::
vector
<
base
::
PointCloud
<
base
::
PointD
>
,
Eigen
::
aligned_allocator
<
base
::
PointCloud
<
base
::
PointD
>
>
>*
road_polygons_ptr
,
std
::
vector
<
base
::
PointCloud
<
base
::
PointD
>
,
Eigen
::
aligned_allocator
<
base
::
PointCloud
<
base
::
PointD
>
>
>*
junction_polygons_ptr
)
{
EigenVector
<
base
::
RoadBoundary
>*
road_boundaries_ptr
,
EigenVector
<
base
::
PointCloud
<
base
::
PointD
>>*
road_polygons_ptr
,
EigenVector
<
base
::
PointCloud
<
base
::
PointD
>>*
junction_polygons_ptr
)
{
const
int
boundary_size
=
static_cast
<
int
>
(
boundary
.
size
());
const
int
junctions_size
=
static_cast
<
int
>
(
junctions
.
size
());
const
int
polygon_size
=
boundary_size
;
...
...
@@ -234,23 +228,13 @@ void HDMapInput::MergeBoundaryJunction(
}
bool
HDMapInput
::
GetRoadBoundaryFilteredByJunctions
(
const
std
::
vector
<
base
::
RoadBoundary
,
Eigen
::
aligned_allocator
<
base
::
RoadBoundary
>
>&
road_boundaries
,
const
std
::
vector
<
base
::
PointCloud
<
base
::
PointD
>
,
Eigen
::
aligned_allocator
<
base
::
PointCloud
<
base
::
PointD
>
>
>&
junctions
,
std
::
vector
<
base
::
RoadBoundary
,
Eigen
::
aligned_allocator
<
base
::
RoadBoundary
>
>*
flt_road_boundaries_ptr
)
{
const
EigenVector
<
base
::
RoadBoundary
>&
road_boundaries
,
const
EigenVector
<
base
::
PointCloud
<
base
::
PointD
>>&
junctions
,
EigenVector
<
base
::
RoadBoundary
>*
flt_road_boundaries_ptr
)
{
for
(
size_t
n_rd
=
0
;
n_rd
<
road_boundaries
.
size
();
++
n_rd
)
{
const
base
::
RoadBoundary
&
temp_road_boundary
=
road_boundaries
[
n_rd
];
std
::
vector
<
base
::
PointCloud
<
base
::
PointD
>
,
Eigen
::
aligned_allocator
<
base
::
PointCloud
<
base
::
PointD
>
>
>
temp_left_boundary_vec
;
std
::
vector
<
base
::
PointCloud
<
base
::
PointD
>
,
Eigen
::
aligned_allocator
<
base
::
PointCloud
<
base
::
PointD
>
>
>
temp_right_boundary_vec
;
EigenVector
<
base
::
PointCloud
<
base
::
PointD
>>
temp_left_boundary_vec
;
EigenVector
<
base
::
PointCloud
<
base
::
PointD
>>
temp_right_boundary_vec
;
// Filter left boundary points
this
->
SplitBoundary
(
temp_road_boundary
.
left_boundary
,
junctions
,
&
temp_left_boundary_vec
);
...
...
@@ -324,12 +308,8 @@ void HDMapInput::DownsamplePoints(const base::PointDCloudPtr& raw_cloud_ptr,
void
HDMapInput
::
SplitBoundary
(
const
base
::
PointCloud
<
base
::
PointD
>&
boundary_line
,
const
std
::
vector
<
base
::
PointCloud
<
base
::
PointD
>
,
Eigen
::
aligned_allocator
<
base
::
PointCloud
<
base
::
PointD
>
>
>&
junctions
,
std
::
vector
<
base
::
PointCloud
<
base
::
PointD
>
,
Eigen
::
aligned_allocator
<
base
::
PointCloud
<
base
::
PointD
>
>
>*
boundary_line_vec_ptr
)
{
const
EigenVector
<
base
::
PointCloud
<
base
::
PointD
>>&
junctions
,
EigenVector
<
base
::
PointCloud
<
base
::
PointD
>>*
boundary_line_vec_ptr
)
{
std
::
vector
<
bool
>
boundary_flag
(
boundary_line
.
size
());
for
(
size_t
npt
=
0
;
npt
<
boundary_line
.
size
();
++
npt
)
{
const
PointD
&
pointd
=
boundary_line
[
npt
];
...
...
modules/perception/map/hdmap/hdmap_input.h
浏览文件 @
8602c01e
...
...
@@ -21,11 +21,14 @@
#include <vector>
#include "cyber/common/macros.h"
#include "modules/common/util/eigen_defs.h"
#include "modules/map/hdmap/hdmap.h"
#include "modules/map/hdmap/hdmap_common.h"
#include "modules/perception/base/hdmap_struct.h"
#include "modules/perception/lib/thread/mutex.h"
using
apollo
::
common
::
EigenVector
;
namespace
apollo
{
namespace
perception
{
namespace
map
{
...
...
@@ -49,27 +52,14 @@ class HDMapInput {
void
MergeBoundaryJunction
(
const
std
::
vector
<
apollo
::
hdmap
::
RoadRoiPtr
>&
boundary
,
const
std
::
vector
<
apollo
::
hdmap
::
JunctionInfoConstPtr
>&
junctions
,
std
::
vector
<
base
::
RoadBoundary
,
Eigen
::
aligned_allocator
<
base
::
RoadBoundary
>
>*
road_boundaries_ptr
,
std
::
vector
<
base
::
PointCloud
<
base
::
PointD
>
,
Eigen
::
aligned_allocator
<
base
::
PointCloud
<
base
::
PointD
>
>
>*
road_polygons_ptr
,
std
::
vector
<
base
::
PointCloud
<
base
::
PointD
>
,
Eigen
::
aligned_allocator
<
base
::
PointCloud
<
base
::
PointD
>
>
>*
junction_polygons_ptr
);
EigenVector
<
base
::
RoadBoundary
>*
road_boundaries_ptr
,
EigenVector
<
base
::
PointCloud
<
base
::
PointD
>>*
road_polygons_ptr
,
EigenVector
<
base
::
PointCloud
<
base
::
PointD
>>*
junction_polygons_ptr
);
bool
GetRoadBoundaryFilteredByJunctions
(
const
std
::
vector
<
base
::
RoadBoundary
,
Eigen
::
aligned_allocator
<
base
::
RoadBoundary
>
>&
road_boundaries
,
const
std
::
vector
<
base
::
PointCloud
<
base
::
PointD
>
,
Eigen
::
aligned_allocator
<
base
::
PointCloud
<
base
::
PointD
>
>
>&
junctions
,
std
::
vector
<
base
::
RoadBoundary
,
Eigen
::
aligned_allocator
<
base
::
RoadBoundary
>
>*
flt_road_boundaries_ptr
);
const
EigenVector
<
base
::
RoadBoundary
>&
road_boundaries
,
const
EigenVector
<
base
::
PointCloud
<
base
::
PointD
>>&
junctions
,
EigenVector
<
base
::
RoadBoundary
>*
flt_road_boundaries_ptr
);
void
DownsamplePoints
(
const
base
::
PointDCloudPtr
&
raw_cloud_ptr
,
base
::
PointCloud
<
base
::
PointD
>*
polygon_ptr
,
...
...
@@ -77,13 +67,8 @@ class HDMapInput {
void
SplitBoundary
(
const
base
::
PointCloud
<
base
::
PointD
>&
boundary_line
,
const
std
::
vector
<
base
::
PointCloud
<
base
::
PointD
>
,
Eigen
::
aligned_allocator
<
base
::
PointCloud
<
base
::
PointD
>
>
>&
junctions
,
std
::
vector
<
base
::
PointCloud
<
base
::
PointD
>
,
Eigen
::
aligned_allocator
<
base
::
PointCloud
<
base
::
PointD
>
>
>*
boundary_line_vec_ptr
);
const
EigenVector
<
base
::
PointCloud
<
base
::
PointD
>>&
junctions
,
EigenVector
<
base
::
PointCloud
<
base
::
PointD
>>*
boundary_line_vec_ptr
);
bool
GetSignalsFromHDMap
(
const
Eigen
::
Vector3d
&
pointd
,
double
forward_distance
,
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录