Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
c8262632
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 搜索 >>
提交
c8262632
编写于
7月 18, 2018
作者:
J
jiangyifei
提交者:
Yifei Jiang
7月 19, 2018
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
navi: added lidar based perception into navigation mode
上级
916697b6
变更
6
隐藏空白更改
内联
并排
Showing
6 changed file
with
40 addition
and
10 deletion
+40
-10
modules/dreamview/conf/hmi.conf
modules/dreamview/conf/hmi.conf
+6
-4
modules/map/relative_map/navigation_lane.cc
modules/map/relative_map/navigation_lane.cc
+20
-2
modules/perception/conf/adapter.conf
modules/perception/conf/adapter.conf
+5
-1
modules/perception/obstacle/fusion/probabilistic_fusion/probabilistic_fusion.cc
...tacle/fusion/probabilistic_fusion/probabilistic_fusion.cc
+1
-1
modules/perception/obstacle/onboard/lidar_process_subnode.cc
modules/perception/obstacle/onboard/lidar_process_subnode.cc
+3
-0
modules/perception/onboard/transform_input.cc
modules/perception/onboard/transform_input.cc
+5
-2
未找到文件。
modules/dreamview/conf/hmi.conf
浏览文件 @
c8262632
...
...
@@ -509,19 +509,21 @@ modes {
modes
{
key
:
"Navigation"
value
: {
live_modules
:
"navigation_camera"
live_modules
:
"navigation_perception"
live_modules
:
"mobileye"
live_modules
:
"third_party_perception"
live_modules
:
"velodyne"
live_modules
:
"perception"
live_modules
:
"canbus"
live_modules
:
"GPS"
live_modules
:
"mobileye"
live_modules
:
"radar"
live_modules
:
"navigation_camera"
live_modules
:
"navigation_localization"
live_modules
:
"relative_map"
live_modules
:
"navigation_planning"
live_modules
:
"navigation_prediction"
live_modules
:
"navigation_control"
live_modules
:
"guardian"
live_modules
:
"navigation_perception"
live_modules
:
"third_party_perception"
live_modules
:
"record_bag"
live_hardware
:
"GPS"
live_hardware
:
"CAN"
...
...
modules/map/relative_map/navigation_lane.cc
浏览文件 @
c8262632
...
...
@@ -668,8 +668,27 @@ bool NavigationLane::CreateMap(const MapGenerationParam &map_config,
}
}
// Set neighbor information for each lane
int
lane_num
=
hdmap
->
lane_size
();
// Set road boundary
auto
*
road
=
hdmap
->
add_road
();
road
->
mutable_id
()
->
set_id
(
"road_"
+
hdmap
->
lane
(
0
).
id
().
id
());
auto
*
section
=
road
->
add_section
();
for
(
int
i
=
0
;
i
<
lane_num
;
++
i
)
{
auto
*
lane_id
=
section
->
add_lane_id
();
lane_id
->
CopyFrom
(
hdmap
->
lane
(
0
).
id
());
}
auto
*
outer_polygon
=
section
->
mutable_boundary
()
->
mutable_outer_polygon
();
auto
*
left_edge
=
outer_polygon
->
add_edge
();
left_edge
->
set_type
(
apollo
::
hdmap
::
BoundaryEdge
::
LEFT_BOUNDARY
);
left_edge
->
mutable_curve
()
->
CopyFrom
(
hdmap
->
lane
(
0
).
left_boundary
().
curve
());
auto
*
right_edge
=
outer_polygon
->
add_edge
();
right_edge
->
set_type
(
apollo
::
hdmap
::
BoundaryEdge
::
RIGHT_BOUNDARY
);
right_edge
->
mutable_curve
()
->
CopyFrom
(
hdmap
->
lane
(
lane_num
-
1
).
right_boundary
().
curve
());
// Set neighbor information for each lane
if
(
lane_num
<
2
)
{
return
true
;
}
...
...
@@ -684,7 +703,6 @@ bool NavigationLane::CreateMap(const MapGenerationParam &map_config,
hdmap
->
lane
(
i
+
1
).
id
());
}
}
return
true
;
}
...
...
modules/perception/conf/adapter.conf
浏览文件 @
c8262632
...
...
@@ -61,5 +61,9 @@ config {
mode
:
PUBLISH_ONLY
message_history_limit
:
50
}
config
{
type
:
RELATIVE_MAP
mode
:
RECEIVE_ONLY
message_history_limit
:
1
}
is_ros
:
true
modules/perception/obstacle/fusion/probabilistic_fusion/probabilistic_fusion.cc
浏览文件 @
c8262632
...
...
@@ -284,7 +284,7 @@ void ProbabilisticFusion::FuseForegroundObjects(
sensor_type
,
sensor_id
,
timestamp
);
if
(
FLAGS_use_navigation_mode
)
{
if
(
is_camera
(
sensor_type
))
{
if
(
is_camera
(
sensor_type
)
||
is_lidar
(
sensor_type
)
)
{
CreateNewTracks
(
*
foreground_objects
,
unassigned_objects
);
}
}
else
{
...
...
modules/perception/obstacle/onboard/lidar_process_subnode.cc
浏览文件 @
c8262632
...
...
@@ -125,6 +125,9 @@ void LidarProcessSubnode::OnPointCloud(
// error_code_ = common::OK;
/// call hdmap to get ROI
if
(
FLAGS_use_navigation_mode
)
{
AdapterManager
::
Observe
();
}
HdmapStructPtr
hdmap
=
nullptr
;
if
(
hdmap_input_
)
{
PointD
velodyne_pose
=
{
0.0
,
0.0
,
0.0
,
0
};
// (0,0,0)
...
...
modules/perception/onboard/transform_input.cc
浏览文件 @
c8262632
...
...
@@ -83,8 +83,11 @@ bool GetVelodyneTrans(const double query_time, Eigen::Matrix4d* trans) {
Eigen
::
Affine3d
affine_localization_3d
;
tf
::
transformMsgToEigen
(
transform_stamped
.
transform
,
affine_localization_3d
);
Eigen
::
Matrix4d
novatel2world_trans
=
affine_localization_3d
.
matrix
();
*
trans
=
novatel2world_trans
*
lidar2novatel_trans
;
if
(
FLAGS_use_navigation_mode
)
{
*
trans
=
lidar2novatel_trans
;
}
else
{
*
trans
=
novatel2world_trans
*
lidar2novatel_trans
;
}
ADEBUG
<<
"get "
<<
FLAGS_lidar_tf2_frame_id
<<
" to "
<<
FLAGS_localization_tf2_child_frame_id
<<
" trans: "
<<
*
trans
;
return
true
;
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录