Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
dc101235
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,发现更多精彩内容 >>
提交
dc101235
编写于
12月 31, 2017
作者:
D
Dong Li
提交者:
Calvin Miao
12月 31, 2017
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
prediction: added performance profiling support
上级
d42ce3f9
变更
5
隐藏空白更改
内联
并排
Showing
5 changed file
with
29 addition
and
4 deletion
+29
-4
modules/common/apollo_app.cc
modules/common/apollo_app.cc
+12
-3
modules/prediction/common/prediction_gflags.cc
modules/prediction/common/prediction_gflags.cc
+5
-0
modules/prediction/common/prediction_gflags.h
modules/prediction/common/prediction_gflags.h
+3
-0
modules/prediction/prediction.cc
modules/prediction/prediction.cc
+7
-0
modules/prediction/prediction.h
modules/prediction/prediction.h
+2
-1
未找到文件。
modules/common/apollo_app.cc
浏览文件 @
dc101235
...
...
@@ -17,6 +17,7 @@
#include "modules/common/apollo_app.h"
#include <csignal>
#include <memory>
#include <string>
#include <vector>
...
...
@@ -44,7 +45,7 @@ void ApolloApp::ExportFlags() const {
std
::
vector
<
gflags
::
CommandLineFlagInfo
>
flags
;
gflags
::
GetAllFlags
(
&
flags
);
for
(
const
auto
&
flag
:
flags
)
{
for
(
const
auto
&
flag
:
flags
)
{
fout
<<
"# "
<<
flag
.
type
<<
", default="
<<
flag
.
default_value
<<
"
\n
"
<<
"# "
<<
flag
.
description
<<
"
\n
"
<<
"--"
<<
flag
.
name
<<
"="
<<
flag
.
current_value
<<
"
\n
"
...
...
@@ -53,7 +54,11 @@ void ApolloApp::ExportFlags() const {
}
int
ApolloApp
::
Spin
()
{
ros
::
AsyncSpinner
spinner
(
callback_thread_num_
);
std
::
unique_ptr
<
ros
::
AsyncSpinner
>
spinner
;
if
(
callback_thread_num_
>
1
)
{
spinner
=
std
::
unique_ptr
<
ros
::
AsyncSpinner
>
(
new
ros
::
AsyncSpinner
(
callback_thread_num_
));
}
auto
status
=
Init
();
if
(
!
status
.
ok
())
{
AERROR
<<
Name
()
<<
" Init failed: "
<<
status
;
...
...
@@ -65,7 +70,11 @@ int ApolloApp::Spin() {
return
-
2
;
}
ExportFlags
();
spinner
.
start
();
if
(
spinner
)
{
spinner
->
start
();
}
else
{
ros
::
spin
();
}
ros
::
waitForShutdown
();
Stop
();
AINFO
<<
Name
()
<<
" exited."
;
...
...
modules/prediction/common/prediction_gflags.cc
浏览文件 @
dc101235
...
...
@@ -27,6 +27,11 @@ DEFINE_string(prediction_conf_file,
DEFINE_string
(
prediction_adapter_config_filename
,
"modules/prediction/conf/adapter.conf"
,
"Default conf file for prediction"
);
DEFINE_bool
(
prediction_test_mode
,
false
,
"Set prediction to test mode"
);
DEFINE_double
(
prediction_test_duration
,
-
1.0
,
"The runtime duration in test mode (in seconds). Negative value will not "
"restrict the runtime duration."
);
DEFINE_double
(
prediction_duration
,
5.0
,
"Prediction duration (in seconds)"
);
DEFINE_double
(
prediction_period
,
0.1
,
"Prediction period (in seconds"
);
...
...
modules/prediction/common/prediction_gflags.h
浏览文件 @
dc101235
...
...
@@ -24,6 +24,9 @@ DECLARE_string(prediction_module_name);
DECLARE_string
(
prediction_conf_file
);
DECLARE_string
(
prediction_adapter_config_filename
);
DECLARE_bool
(
prediction_test_mode
);
DECLARE_double
(
prediction_test_duration
);
DECLARE_double
(
prediction_duration
);
DECLARE_double
(
prediction_period
);
DECLARE_double
(
double_precision
);
...
...
modules/prediction/prediction.cc
浏览文件 @
dc101235
...
...
@@ -48,6 +48,8 @@ using ::apollo::perception::PerceptionObstacles;
std
::
string
Prediction
::
Name
()
const
{
return
FLAGS_prediction_module_name
;
}
Status
Prediction
::
Init
()
{
start_time_
=
Clock
::
NowInSeconds
();
// Load prediction conf
prediction_conf_
.
Clear
();
if
(
!
common
::
util
::
GetProtoFromFile
(
FLAGS_prediction_conf_file
,
...
...
@@ -129,6 +131,11 @@ void Prediction::OnPlanning(const planning::ADCTrajectory& adc_trajectory) {
}
void
Prediction
::
RunOnce
(
const
PerceptionObstacles
&
perception_obstacles
)
{
if
(
FLAGS_prediction_test_mode
&&
FLAGS_prediction_test_duration
>
0
&&
(
Clock
::
NowInSeconds
()
-
start_time_
>
FLAGS_prediction_test_duration
))
{
AINFO
<<
"Prediction finished running in test mode"
;
ros
::
shutdown
();
}
ADEBUG
<<
"Received a perception message ["
<<
perception_obstacles
.
ShortDebugString
()
<<
"]."
;
...
...
modules/prediction/prediction.h
浏览文件 @
dc101235
...
...
@@ -80,12 +80,13 @@ class Prediction : public PredictionInterface {
void
OnLocalization
(
const
localization
::
LocalizationEstimate
&
localization
);
void
OnPlanning
(
const
planning
::
ADCTrajectory
&
adc_trajectory
);
void
OnPlanning
(
const
planning
::
ADCTrajectory
&
adc_trajectory
);
bool
IsValidTrajectoryPoint
(
const
::
apollo
::
common
::
TrajectoryPoint
&
trajectory_point
);
private:
double
start_time_
=
0.0
;
PredictionConf
prediction_conf_
;
common
::
adapter
::
AdapterManagerConfig
adapter_conf_
;
};
...
...
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录