Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
b5f59cb7
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,发现更多精彩内容 >>
提交
b5f59cb7
编写于
7月 24, 2017
作者:
C
Calvin Miao
提交者:
Jiangtao Hu
7月 24, 2017
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
Added is on lane check for obstacle
上级
9c6a6166
变更
3
隐藏空白更改
内联
并排
Showing
3 changed file
with
21 addition
and
2 deletion
+21
-2
modules/prediction/container/obstacles/obstacle.cc
modules/prediction/container/obstacles/obstacle.cc
+12
-0
modules/prediction/container/obstacles/obstacle.h
modules/prediction/container/obstacles/obstacle.h
+2
-0
modules/prediction/predictor/predictor_manager.cc
modules/prediction/predictor/predictor_manager.cc
+7
-2
未找到文件。
modules/prediction/container/obstacles/obstacle.cc
浏览文件 @
b5f59cb7
...
...
@@ -112,10 +112,22 @@ size_t Obstacle::history_size() const {
const
KalmanFilter
<
double
,
4
,
2
,
0
>&
Obstacle
::
kf_lane_tracker
(
const
std
::
string
&
lane_id
)
{
std
::
lock_guard
<
std
::
mutex
>
lock
(
mutex_
);
CHECK
(
kf_lane_trackers_
.
find
(
lane_id
)
!=
kf_lane_trackers_
.
end
());
return
kf_lane_trackers_
[
lane_id
];
}
bool
Obstacle
::
IsOnLane
()
{
std
::
lock_guard
<
std
::
mutex
>
lock
(
mutex_
);
if
(
feature_history_
.
size
()
>
0
)
{
if
(
feature_history_
.
front
().
has_lane
()
&&
feature_history_
.
front
().
lane
().
has_lane_feature
())
{
return
true
;
}
}
return
false
;
}
void
Obstacle
::
Insert
(
const
PerceptionObstacle
&
perception_obstacle
,
const
double
timestamp
)
{
std
::
lock_guard
<
std
::
mutex
>
lock
(
mutex_
);
...
...
modules/prediction/container/obstacles/obstacle.h
浏览文件 @
b5f59cb7
...
...
@@ -66,6 +66,8 @@ class Obstacle {
// TODO(author) void SetLaneGraphFeature(ObstacleClusters* p_cluster);
bool
IsOnLane
();
private:
apollo
::
common
::
ErrorCode
SetId
(
const
apollo
::
perception
::
PerceptionObstacle
&
perception_obstacle
,
...
...
modules/prediction/predictor/predictor_manager.cc
浏览文件 @
b5f59cb7
...
...
@@ -45,9 +45,15 @@ void PredictorManager::Run(
for
(
const
auto
&
perception_obstacle
:
perception_obstacles
.
perception_obstacle
())
{
int
id
=
perception_obstacle
.
id
();
Obstacle
*
obstacle
=
container
->
GetObstacle
(
id
);
CHECK_NOTNULL
(
obstacle
);
switch
(
perception_obstacle
.
type
())
{
case
PerceptionObstacle
::
VEHICLE
:
{
predictor
=
GetPredictor
(
ObstacleConf
::
LANE_SEQUENCE_PREDICTOR
);
if
(
obstacle
->
IsOnLane
())
{
predictor
=
GetPredictor
(
ObstacleConf
::
LANE_SEQUENCE_PREDICTOR
);
}
else
{
predictor
=
GetPredictor
(
ObstacleConf
::
FREE_MOVE_PREDICTOR
);
}
break
;
}
case
PerceptionObstacle
::
PEDESTRIAN
:
{
...
...
@@ -60,7 +66,6 @@ void PredictorManager::Run(
}
}
if
(
predictor
!=
nullptr
)
{
Obstacle
*
obstacle
=
container
->
GetObstacle
(
id
);
predictor
->
Predict
(
obstacle
);
PredictionObstacle
prediction_obstacle
;
prediction_obstacle
.
CopyFrom
(
predictor
->
prediction_obstacle
());
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录