Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
5ad3c061
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 搜索 >>
提交
5ad3c061
编写于
12月 08, 2019
作者:
K
kechxu
提交者:
Xiangquan Xiao
12月 08, 2019
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
Prediction: use absl time for submodules
上级
1e7b700a
变更
7
隐藏空白更改
内联
并排
Showing
7 changed file
with
20 addition
and
12 deletion
+20
-12
modules/prediction/prediction_component.cc
modules/prediction/prediction_component.cc
+1
-1
modules/prediction/prediction_component.h
modules/prediction/prediction_component.h
+2
-0
modules/prediction/submodules/BUILD
modules/prediction/submodules/BUILD
+1
-0
modules/prediction/submodules/evaluator_submodule.cc
modules/prediction/submodules/evaluator_submodule.cc
+1
-1
modules/prediction/submodules/predictor_submodule.cc
modules/prediction/submodules/predictor_submodule.cc
+6
-5
modules/prediction/submodules/submodule_output.cc
modules/prediction/submodules/submodule_output.cc
+4
-2
modules/prediction/submodules/submodule_output.h
modules/prediction/submodules/submodule_output.h
+5
-3
未找到文件。
modules/prediction/prediction_component.cc
浏览文件 @
5ad3c061
...
...
@@ -110,7 +110,7 @@ bool PredictionComponent::Proc(
bool
PredictionComponent
::
ContainerSubmoduleProcess
(
const
std
::
shared_ptr
<
PerceptionObstacles
>&
perception_obstacles
)
{
const
double
frame_start_time
=
apollo
::
cyber
::
Time
::
Now
().
ToNanosecond
();
const
auto
frame_start_time
=
absl
::
Now
();
// Read localization info. and call OnLocalization to update
// the PoseContainer.
localization_reader_
->
Observe
();
...
...
modules/prediction/prediction_component.h
浏览文件 @
5ad3c061
...
...
@@ -24,6 +24,8 @@
#include <string>
#include <utility>
#include "absl/time/time.h"
#include "cyber/component/component.h"
#include "modules/prediction/common/message_process.h"
#include "modules/prediction/container/adc_trajectory/adc_trajectory_container.h"
...
...
modules/prediction/submodules/BUILD
浏览文件 @
5ad3c061
...
...
@@ -14,6 +14,7 @@ cc_library(
"//modules/perception/proto:perception_proto"
,
"//modules/prediction/common:prediction_gflags"
,
"//modules/prediction/container/obstacles:obstacle"
,
"@com_google_absl//absl/time"
,
],
)
...
...
modules/prediction/submodules/evaluator_submodule.cc
浏览文件 @
5ad3c061
...
...
@@ -46,7 +46,7 @@ bool EvaluatorSubmodule::Init() {
bool
EvaluatorSubmodule
::
Proc
(
const
std
::
shared_ptr
<
SubmoduleOutput
>&
container_output
)
{
const
double
frame_start_time
=
container_output
->
frame_start_time
();
const
auto
frame_start_time
=
container_output
->
frame_start_time
();
ObstaclesContainer
obstacles_container
(
*
container_output
);
EvaluatorManager
::
Instance
()
->
Run
(
&
obstacles_container
);
SubmoduleOutput
submodule_output
=
obstacles_container
.
GetSubmoduleOutput
();
...
...
modules/prediction/submodules/predictor_submodule.cc
浏览文件 @
5ad3c061
...
...
@@ -18,6 +18,8 @@
#include <utility>
#include "absl/time/time.h"
#include "modules/common/adapters/adapter_gflags.h"
#include "modules/common/adapters/proto/adapter_config.pb.h"
#include "modules/common/time/time.h"
...
...
@@ -54,7 +56,7 @@ bool PredictorSubmodule::Proc(
perception_obstacles
->
header
();
const
apollo
::
common
::
ErrorCode
&
perception_error_code
=
perception_obstacles
->
error_code
();
const
double
frame_start_time
=
submodule_output
->
frame_start_time
();
const
absl
::
Time
&
frame_start_time
=
submodule_output
->
frame_start_time
();
ObstaclesContainer
obstacles_container
(
*
submodule_output
);
PredictorManager
::
Instance
()
->
Run
(
*
perception_obstacles
,
adc_trajectory_container
.
get
(),
...
...
@@ -70,15 +72,14 @@ bool PredictorSubmodule::Proc(
prediction_obstacles
.
mutable_header
()
->
set_radar_timestamp
(
perception_header
.
radar_timestamp
());
prediction_obstacles
.
set_perception_error_code
(
perception_error_code
);
prediction_obstacles
.
set_start_timestamp
(
frame_start_time
);
common
::
util
::
FillHeader
(
node_
->
Name
(),
&
prediction_obstacles
);
predictor_writer_
->
Write
(
std
::
make_shared
<
PredictionObstacles
>
(
prediction_obstacles
));
double
end_time
=
apollo
::
cyber
::
Time
::
Now
().
ToNanosecond
();
double
start_time
=
submodule_output
->
frame_start_time
();
ADEBUG
<<
"End to end time = "
<<
(
end_time
-
start_time
)
/
1e6
<<
" ms"
;
const
absl
::
Time
&
end_time
=
absl
::
Now
();
ADEBUG
<<
"End to end time = "
<<
absl
::
ToDoubleMilliseconds
(
end_time
-
frame_start_time
)
<<
" ms"
;
return
true
;
}
...
...
modules/prediction/submodules/submodule_output.cc
浏览文件 @
5ad3c061
...
...
@@ -43,7 +43,7 @@ void SubmoduleOutput::set_curr_frame_considered_obstacle_ids(
curr_frame_considered_obstacle_ids_
=
curr_frame_considered_obstacle_ids
;
}
void
SubmoduleOutput
::
set_frame_start_time
(
const
double
frame_start_time
)
{
void
SubmoduleOutput
::
set_frame_start_time
(
const
absl
::
Time
&
frame_start_time
)
{
frame_start_time_
=
frame_start_time
;
}
...
...
@@ -65,7 +65,9 @@ std::vector<int> SubmoduleOutput::curr_frame_considered_obstacle_ids() const {
return
curr_frame_considered_obstacle_ids_
;
}
double
SubmoduleOutput
::
frame_start_time
()
const
{
return
frame_start_time_
;
}
const
absl
::
Time
&
SubmoduleOutput
::
frame_start_time
()
const
{
return
frame_start_time_
;
}
}
// namespace prediction
}
// namespace apollo
modules/prediction/submodules/submodule_output.h
浏览文件 @
5ad3c061
...
...
@@ -23,6 +23,8 @@
#include <vector>
#include "absl/time/time.h"
#include "modules/common/util/lru_cache.h"
#include "modules/perception/proto/perception_obstacle.pb.h"
#include "modules/prediction/container/obstacles/obstacle.h"
...
...
@@ -55,7 +57,7 @@ class SubmoduleOutput {
void
set_curr_frame_considered_obstacle_ids
(
const
std
::
vector
<
int
>&
curr_frame_considered_obstacle_ids
);
void
set_frame_start_time
(
const
double
frame_start_time
);
void
set_frame_start_time
(
const
absl
::
Time
&
frame_start_time
);
const
std
::
vector
<
Obstacle
>&
curr_frame_obstacles
()
const
;
...
...
@@ -70,7 +72,7 @@ class SubmoduleOutput {
std
::
vector
<
int
>
curr_frame_considered_obstacle_ids
()
const
;
double
frame_start_time
()
const
;
const
absl
::
Time
&
frame_start_time
()
const
;
protected:
std
::
vector
<
Obstacle
>
curr_frame_obstacles_
;
...
...
@@ -78,7 +80,7 @@ class SubmoduleOutput {
std
::
vector
<
int
>
curr_frame_movable_obstacle_ids_
;
std
::
vector
<
int
>
curr_frame_unmovable_obstacle_ids_
;
std
::
vector
<
int
>
curr_frame_considered_obstacle_ids_
;
doubl
e
frame_start_time_
;
absl
::
Tim
e
frame_start_time_
;
};
}
// namespace prediction
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录