Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
85867d47
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,发现更多精彩内容 >>
提交
85867d47
编写于
5月 08, 2019
作者:
H
Hongyi
提交者:
Qi Luo
5月 09, 2019
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
Revert "planning: STBoundaryMapper remove buffer"
This reverts commit 7912ce004e1b4b115e2743eaba9655e2b7b5f51b.
上级
64117b0c
变更
1
隐藏空白更改
内联
并排
Showing
1 changed file
with
12 addition
and
23 deletion
+12
-23
modules/planning/tasks/deciders/speed_bounds_decider/st_boundary_mapper.cc
...tasks/deciders/speed_bounds_decider/st_boundary_mapper.cc
+12
-23
未找到文件。
modules/planning/tasks/deciders/speed_bounds_decider/st_boundary_mapper.cc
浏览文件 @
85867d47
...
...
@@ -48,6 +48,12 @@ using apollo::common::math::Box2d;
using
apollo
::
common
::
math
::
Vec2d
;
using
apollo
::
common
::
util
::
StrCat
;
namespace
{
// TODO(all): remove them; no buffer should be added here.
constexpr
double
boundary_t_buffer
=
0.1
;
constexpr
double
boundary_s_buffer
=
1.0
;
}
// namespace
StBoundaryMapper
::
StBoundaryMapper
(
const
SLBoundary
&
adc_sl_boundary
,
const
SpeedBoundsDeciderConfig
&
config
,
const
ReferenceLine
&
reference_line
,
...
...
@@ -212,7 +218,9 @@ Status StBoundaryMapper::MapWithoutDecision(Obstacle* obstacle) const {
return
Status
::
OK
();
}
auto
boundary
=
STBoundary
::
CreateInstance
(
lower_points
,
upper_points
);
auto
boundary
=
STBoundary
::
CreateInstance
(
lower_points
,
upper_points
)
.
ExpandByS
(
boundary_s_buffer
)
.
ExpandByT
(
boundary_t_buffer
);
boundary
.
set_id
(
obstacle
->
Id
());
const
auto
&
prev_st_boundary
=
obstacle
->
st_boundary
();
const
auto
&
ref_line_st_boundary
=
obstacle
->
reference_line_st_boundary
();
...
...
@@ -389,7 +397,9 @@ Status StBoundaryMapper::MapWithDecision(
lower_points
.
emplace_back
(
extend_lower_s
,
planning_time_
);
}
auto
boundary
=
STBoundary
::
CreateInstance
(
lower_points
,
upper_points
);
auto
boundary
=
STBoundary
::
CreateInstance
(
lower_points
,
upper_points
)
.
ExpandByS
(
boundary_s_buffer
)
.
ExpandByT
(
boundary_t_buffer
);
// get characteristic_length and boundary_type.
STBoundary
::
BoundaryType
b_type
=
STBoundary
::
BoundaryType
::
UNKNOWN
;
...
...
@@ -420,7 +430,6 @@ Status StBoundaryMapper::MapWithDecision(
bool
StBoundaryMapper
::
CheckOverlap
(
const
PathPoint
&
path_point
,
const
Box2d
&
obs_box
,
const
double
buffer
)
const
{
/**
// TODO(all): the code makes no sense; remove it.
double
left_delta_l
=
0.0
;
double
right_delta_l
=
0.0
;
...
...
@@ -451,26 +460,6 @@ bool StBoundaryMapper::CheckOverlap(const PathPoint& path_point,
vehicle_param_
.
length
()
+
2.0
*
buffer
,
vehicle_param_
.
width
()
+
2.0
*
buffer
);
return
obs_box
.
HasOverlap
(
adc_box
);
**/
// TODO(all): the code makes no sense; remove it.
Vec2d
ego_center_map_frame
(
(
vehicle_param_
.
front_edge_to_center
()
-
vehicle_param_
.
back_edge_to_center
())
*
0.5
,
(
vehicle_param_
.
left_edge_to_center
()
-
vehicle_param_
.
right_edge_to_center
())
*
0.5
);
ego_center_map_frame
.
SelfRotate
(
path_point
.
theta
());
ego_center_map_frame
.
set_x
(
ego_center_map_frame
.
x
()
+
path_point
.
x
());
ego_center_map_frame
.
set_y
(
ego_center_map_frame
.
y
()
+
path_point
.
y
());
Box2d
adc_box
(
ego_center_map_frame
,
path_point
.
theta
(),
vehicle_param_
.
length
(),
vehicle_param_
.
width
());
return
obs_box
.
HasOverlap
(
adc_box
);
}
}
// namespace planning
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录