Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
f8421403
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 搜索 >>
提交
f8421403
编写于
3月 16, 2020
作者:
S
sjiang2018
提交者:
Qi Luo
3月 16, 2020
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
Planning: using parking_info instead of parking_space for valet parking.
上级
4c750920
变更
3
显示空白变更内容
内联
并排
Showing
3 changed file
with
20 addition
and
12 deletion
+20
-12
modules/planning/scenarios/park/valet_parking/stage_approaching_parking_spot.cc
...rios/park/valet_parking/stage_approaching_parking_spot.cc
+7
-5
modules/planning/scenarios/park/valet_parking/valet_parking_scenario.cc
...ng/scenarios/park/valet_parking/valet_parking_scenario.cc
+9
-4
modules/planning/tasks/deciders/open_space_decider/open_space_roi_decider.cc
...sks/deciders/open_space_decider/open_space_roi_decider.cc
+4
-3
未找到文件。
modules/planning/scenarios/park/valet_parking/stage_approaching_parking_spot.cc
浏览文件 @
f8421403
...
...
@@ -33,13 +33,15 @@ Stage::StageStatus StageApproachingParkingSpot::Process(
ADEBUG
<<
"stage: StageApproachingParkingSpot"
;
CHECK_NOTNULL
(
frame
);
GetContext
()
->
target_parking_spot_id
.
clear
();
if
(
frame
->
local_view
().
routing
->
routing_request
().
has_parking_space
()
&&
frame
->
local_view
().
routing
->
routing_request
().
parking_space
().
has_id
())
{
if
(
frame
->
local_view
().
routing
->
routing_request
().
has_parking_info
()
&&
frame
->
local_view
()
.
routing
->
routing_request
()
.
parking_info
()
.
has_parking_space_id
())
{
GetContext
()
->
target_parking_spot_id
=
frame
->
local_view
()
.
routing
->
routing_request
()
.
parking_space
()
.
id
()
.
id
();
.
parking_info
()
.
parking_space_id
();
}
else
{
AERROR
<<
"No parking space id from routing"
;
return
StageStatus
::
ERROR
;
...
...
modules/planning/scenarios/park/valet_parking/valet_parking_scenario.cc
浏览文件 @
f8421403
...
...
@@ -97,10 +97,15 @@ bool ValetParkingScenario::IsTransferable(const Frame& frame,
const
double
parking_start_range
)
{
// TODO(all) Implement available parking spot detection by preception results
std
::
string
target_parking_spot_id
;
if
(
frame
.
local_view
().
routing
->
routing_request
().
has_parking_space
()
&&
frame
.
local_view
().
routing
->
routing_request
().
parking_space
().
has_id
())
{
target_parking_spot_id
=
frame
.
local_view
().
routing
->
routing_request
().
parking_space
().
id
().
id
();
if
(
frame
.
local_view
().
routing
->
routing_request
().
has_parking_info
()
&&
frame
.
local_view
()
.
routing
->
routing_request
()
.
parking_info
()
.
has_parking_space_id
())
{
target_parking_spot_id
=
frame
.
local_view
()
.
routing
->
routing_request
()
.
parking_info
()
.
parking_space_id
();
}
else
{
ADEBUG
<<
"No parking space id from routing"
;
return
false
;
...
...
modules/planning/tasks/deciders/open_space_decider/open_space_roi_decider.cc
浏览文件 @
f8421403
...
...
@@ -68,9 +68,10 @@ Status OpenSpaceRoiDecider::Process(Frame *frame) {
const
auto
&
routing_request
=
frame
->
local_view
().
routing
->
routing_request
();
if
(
routing_request
.
has_parking_space
()
&&
!
routing_request
.
parking_space
().
id
().
id
().
empty
())
{
target_parking_spot_id_
=
routing_request
.
parking_space
().
id
().
id
();
if
(
routing_request
.
has_parking_info
()
&&
routing_request
.
parking_info
().
has_parking_space_id
())
{
target_parking_spot_id_
=
routing_request
.
parking_info
().
parking_space_id
();
}
else
{
const
std
::
string
msg
=
"Failed to get parking space id from routing"
;
AERROR
<<
msg
;
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录