Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
e9dbd25d
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,发现更多精彩内容 >>
提交
e9dbd25d
编写于
5月 09, 2019
作者:
Y
Yajia Zhang
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
planning: remove unused parameter for STBoundaryMapper
上级
654f176e
变更
4
隐藏空白更改
内联
并排
Showing
4 changed file
with
25 addition
and
29 deletion
+25
-29
modules/planning/tasks/deciders/speed_bounds_decider/speed_bounds_decider.cc
...sks/deciders/speed_bounds_decider/speed_bounds_decider.cc
+2
-3
modules/planning/tasks/deciders/speed_bounds_decider/st_boundary_mapper.cc
...tasks/deciders/speed_bounds_decider/st_boundary_mapper.cc
+9
-11
modules/planning/tasks/deciders/speed_bounds_decider/st_boundary_mapper.h
.../tasks/deciders/speed_bounds_decider/st_boundary_mapper.h
+12
-13
modules/planning/tasks/deciders/speed_bounds_decider/st_boundary_mapper_test.cc
.../deciders/speed_bounds_decider/st_boundary_mapper_test.cc
+2
-2
未找到文件。
modules/planning/tasks/deciders/speed_bounds_decider/speed_bounds_decider.cc
浏览文件 @
e9dbd25d
...
...
@@ -72,11 +72,10 @@ Status SpeedBoundsDecider::Process(
}
// 2. Map obstacles into st graph
S
t
BoundaryMapper
boundary_mapper
(
adc_sl_boundary
,
speed_bounds_config_
,
S
T
BoundaryMapper
boundary_mapper
(
adc_sl_boundary
,
speed_bounds_config_
,
reference_line
,
path_data
,
speed_bounds_config_
.
total_path_length
(),
speed_bounds_config_
.
total_time
(),
reference_line_info_
->
IsChangeLanePath
());
speed_bounds_config_
.
total_time
());
path_decision
->
EraseStBoundaries
();
if
(
boundary_mapper
.
CreateStBoundary
(
path_decision
).
code
()
==
...
...
modules/planning/tasks/deciders/speed_bounds_decider/st_boundary_mapper.cc
浏览文件 @
e9dbd25d
...
...
@@ -48,23 +48,21 @@ using apollo::common::math::Box2d;
using
apollo
::
common
::
math
::
Vec2d
;
using
apollo
::
common
::
util
::
StrCat
;
S
tBoundaryMapper
::
St
BoundaryMapper
(
const
SLBoundary
&
adc_sl_boundary
,
S
TBoundaryMapper
::
ST
BoundaryMapper
(
const
SLBoundary
&
adc_sl_boundary
,
const
SpeedBoundsDeciderConfig
&
config
,
const
ReferenceLine
&
reference_line
,
const
PathData
&
path_data
,
const
double
planning_distance
,
const
double
planning_time
,
bool
is_change_lane
)
const
double
planning_time
)
:
adc_sl_boundary_
(
adc_sl_boundary
),
speed_bounds_config_
(
config
),
reference_line_
(
reference_line
),
path_data_
(
path_data
),
vehicle_param_
(
common
::
VehicleConfigHelper
::
GetConfig
().
vehicle_param
()),
planning_distance_
(
planning_distance
),
planning_time_
(
planning_time
),
is_change_lane_
(
is_change_lane
)
{}
planning_time_
(
planning_time
)
{}
Status
S
t
BoundaryMapper
::
CreateStBoundary
(
PathDecision
*
path_decision
)
const
{
Status
S
T
BoundaryMapper
::
CreateStBoundary
(
PathDecision
*
path_decision
)
const
{
const
auto
&
obstacles
=
path_decision
->
obstacles
();
if
(
planning_time_
<
0.0
)
{
...
...
@@ -155,7 +153,7 @@ Status StBoundaryMapper::CreateStBoundary(PathDecision* path_decision) const {
return
Status
::
OK
();
}
bool
S
t
BoundaryMapper
::
MapStopDecision
(
bool
S
T
BoundaryMapper
::
MapStopDecision
(
Obstacle
*
stop_obstacle
,
const
ObjectDecisionType
&
stop_decision
)
const
{
DCHECK
(
stop_decision
.
has_stop
())
<<
"Must have stop decision"
;
...
...
@@ -203,7 +201,7 @@ bool StBoundaryMapper::MapStopDecision(
return
true
;
}
Status
S
t
BoundaryMapper
::
MapWithoutDecision
(
Obstacle
*
obstacle
)
const
{
Status
S
T
BoundaryMapper
::
MapWithoutDecision
(
Obstacle
*
obstacle
)
const
{
std
::
vector
<
STPoint
>
lower_points
;
std
::
vector
<
STPoint
>
upper_points
;
...
...
@@ -227,7 +225,7 @@ Status StBoundaryMapper::MapWithoutDecision(Obstacle* obstacle) const {
return
Status
::
OK
();
}
bool
S
t
BoundaryMapper
::
GetOverlapBoundaryPoints
(
bool
S
T
BoundaryMapper
::
GetOverlapBoundaryPoints
(
const
std
::
vector
<
PathPoint
>&
path_points
,
const
Obstacle
&
obstacle
,
std
::
vector
<
STPoint
>*
upper_points
,
std
::
vector
<
STPoint
>*
lower_points
)
const
{
...
...
@@ -362,7 +360,7 @@ bool StBoundaryMapper::GetOverlapBoundaryPoints(
return
(
lower_points
->
size
()
>
1
&&
upper_points
->
size
()
>
1
);
}
Status
S
t
BoundaryMapper
::
MapWithDecision
(
Status
S
T
BoundaryMapper
::
MapWithDecision
(
Obstacle
*
obstacle
,
const
ObjectDecisionType
&
decision
)
const
{
DCHECK
(
decision
.
has_follow
()
||
decision
.
has_yield
()
||
decision
.
has_overtake
())
...
...
@@ -418,7 +416,7 @@ Status StBoundaryMapper::MapWithDecision(
return
Status
::
OK
();
}
bool
S
t
BoundaryMapper
::
CheckOverlap
(
const
PathPoint
&
path_point
,
bool
S
T
BoundaryMapper
::
CheckOverlap
(
const
PathPoint
&
path_point
,
const
Box2d
&
obs_box
,
const
double
buffer
)
const
{
Vec2d
ego_center_map_frame
(
...
...
modules/planning/tasks/deciders/speed_bounds_decider/st_boundary_mapper.h
浏览文件 @
e9dbd25d
...
...
@@ -36,22 +36,22 @@
namespace
apollo
{
namespace
planning
{
class
S
t
BoundaryMapper
{
class
S
T
BoundaryMapper
{
public:
S
t
BoundaryMapper
(
const
SLBoundary
&
adc_sl_boundary
,
S
T
BoundaryMapper
(
const
SLBoundary
&
adc_sl_boundary
,
const
SpeedBoundsDeciderConfig
&
config
,
const
ReferenceLine
&
reference_line
,
const
PathData
&
path_data
,
const
double
planning_distance
,
const
double
planning_time
,
const
bool
is_change_lane
);
const
double
planning_time
);
virtual
~
S
t
BoundaryMapper
()
=
default
;
virtual
~
S
T
BoundaryMapper
()
=
default
;
apollo
::
common
::
Status
CreateStBoundary
(
PathDecision
*
path_decision
)
const
;
common
::
Status
CreateStBoundary
(
PathDecision
*
path_decision
)
const
;
private:
FRIEND_TEST
(
StBoundaryMapperTest
,
check_overlap_test
);
bool
CheckOverlap
(
const
apollo
::
common
::
PathPoint
&
path_point
,
const
apollo
::
common
::
math
::
Box2d
&
obs_box
,
bool
CheckOverlap
(
const
common
::
PathPoint
&
path_point
,
const
common
::
math
::
Box2d
&
obs_box
,
const
double
buffer
)
const
;
/**
...
...
@@ -60,27 +60,26 @@ class StBoundaryMapper {
* upper_points.size() = lower_points.size()
*/
bool
GetOverlapBoundaryPoints
(
const
std
::
vector
<
apollo
::
common
::
PathPoint
>&
path_points
,
const
std
::
vector
<
common
::
PathPoint
>&
path_points
,
const
Obstacle
&
obstacle
,
std
::
vector
<
STPoint
>*
upper_points
,
std
::
vector
<
STPoint
>*
lower_points
)
const
;
apollo
::
common
::
Status
MapWithoutDecision
(
Obstacle
*
obstacle
)
const
;
common
::
Status
MapWithoutDecision
(
Obstacle
*
obstacle
)
const
;
bool
MapStopDecision
(
Obstacle
*
stop_obstacle
,
const
ObjectDecisionType
&
decision
)
const
;
apollo
::
common
::
Status
MapWithDecision
(
Obstacle
*
obstacle
,
const
ObjectDecisionType
&
decision
)
const
;
common
::
Status
MapWithDecision
(
Obstacle
*
obstacle
,
const
ObjectDecisionType
&
decision
)
const
;
private:
const
SLBoundary
&
adc_sl_boundary_
;
const
SpeedBoundsDeciderConfig
&
speed_bounds_config_
;
const
ReferenceLine
&
reference_line_
;
const
PathData
&
path_data_
;
const
apollo
::
common
::
VehicleParam
&
vehicle_param_
;
const
common
::
VehicleParam
&
vehicle_param_
;
const
double
planning_distance_
;
const
double
planning_time_
;
bool
is_change_lane_
=
false
;
};
}
// namespace planning
...
...
modules/planning/tasks/deciders/speed_bounds_decider/st_boundary_mapper_test.cc
浏览文件 @
e9dbd25d
...
...
@@ -81,8 +81,8 @@ TEST_F(StBoundaryMapperTest, check_overlap_test) {
double
planning_distance
=
70.0
;
double
planning_time
=
10.0
;
SLBoundary
adc_sl_boundary
;
S
t
BoundaryMapper
mapper
(
adc_sl_boundary
,
config
,
*
reference_line_
,
path_data_
,
planning_distance
,
planning_time
,
false
);
S
T
BoundaryMapper
mapper
(
adc_sl_boundary
,
config
,
*
reference_line_
,
path_data_
,
planning_distance
,
planning_time
);
common
::
PathPoint
path_point
;
path_point
.
set_x
(
1.0
);
path_point
.
set_y
(
1.0
);
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录