Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
6e8f8cc6
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,发现更多精彩内容 >>
提交
6e8f8cc6
编写于
1月 25, 2018
作者:
K
kechxu
提交者:
Kecheng Xu
1月 25, 2018
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
Prediction: Implement Insert feature and write to file
上级
2c1d36a7
变更
8
隐藏空白更改
内联
并排
Showing
8 changed file
with
36 addition
and
8 deletion
+36
-8
modules/prediction/common/BUILD
modules/prediction/common/BUILD
+2
-0
modules/prediction/common/feature_output.cc
modules/prediction/common/feature_output.cc
+23
-6
modules/prediction/common/feature_output.h
modules/prediction/common/feature_output.h
+1
-1
modules/prediction/common/prediction_gflags.cc
modules/prediction/common/prediction_gflags.cc
+3
-0
modules/prediction/common/prediction_gflags.h
modules/prediction/common/prediction_gflags.h
+1
-0
modules/prediction/conf/prediction.conf
modules/prediction/conf/prediction.conf
+1
-0
modules/prediction/evaluator/vehicle/mlp_evaluator.cc
modules/prediction/evaluator/vehicle/mlp_evaluator.cc
+4
-0
modules/prediction/proto/offline_features.proto
modules/prediction/proto/offline_features.proto
+1
-1
未找到文件。
modules/prediction/common/BUILD
浏览文件 @
6e8f8cc6
...
...
@@ -74,8 +74,10 @@ cc_library(
deps
=
[
"//modules/prediction/proto:feature_proto"
,
"//modules/prediction/proto:offline_features_proto"
,
"//modules/prediction/common:prediction_gflags"
,
"//modules/common:log"
,
"//modules/common:macro"
,
"//modules/common/util:util"
,
]
)
...
...
modules/prediction/common/feature_output.cc
浏览文件 @
6e8f8cc6
...
...
@@ -16,24 +16,41 @@
#include "modules/prediction/common/feature_output.h"
#include <string>
#include "modules/common/log.h"
#include "modules/common/util/file.h"
#include "modules/prediction/common/prediction_gflags.h"
namespace
apollo
{
namespace
prediction
{
FeatureOutput
::
FeatureOutput
()
{}
FeatureOutput
::~
FeatureOutput
()
{}
bool
FeatureOutput
::
Open
()
{
return
true
;
}
void
FeatureOutput
::
Close
()
{
ADEBUG
<<
"Close feature output"
;
}
FeatureOutput
::~
FeatureOutput
()
{
count_
=
0
;
}
bool
FeatureOutput
::
Ready
()
{
return
Open
();
}
void
FeatureOutput
::
Close
()
{
ADEBUG
<<
"Close feature output"
;
Write
();
}
void
FeatureOutput
::
Insert
(
const
Feature
&
feature
)
{
}
bool
FeatureOutput
::
Ready
()
{
return
Open
();
}
void
FeatureOutput
::
Write
()
{}
void
FeatureOutput
::
Insert
(
const
Feature
&
feature
)
{
features_
.
add_feature
()
->
CopyFrom
(
feature
);
}
void
FeatureOutput
::
Write
()
{
std
::
string
file_name
=
FLAGS_prediction_data_file_prefix
+
std
::
to_string
(
count_
)
+
".bin"
;
apollo
::
common
::
util
::
SetProtoToBinaryFile
(
features_
,
file_name
);
features_
.
Clear
();
++
count_
;
}
}
// namespace prediction
}
// namespace apollo
modules/prediction/common/feature_output.h
浏览文件 @
6e8f8cc6
...
...
@@ -61,7 +61,7 @@ class FeatureOutput {
private:
Features
features_
;
size_t
count
=
0
;
size_t
count
_
=
0
;
DECLARE_SINGLETON
(
FeatureOutput
);
};
...
...
modules/prediction/common/prediction_gflags.cc
浏览文件 @
6e8f8cc6
...
...
@@ -27,6 +27,9 @@ DEFINE_string(prediction_conf_file,
DEFINE_string
(
prediction_adapter_config_filename
,
"modules/prediction/conf/adapter.conf"
,
"Default conf file for prediction"
);
DEFINE_string
(
prediction_data_file_prefix
,
"data/prediction_data/feature_"
,
"Prefix of files to store feature data"
);
DEFINE_bool
(
prediction_test_mode
,
false
,
"Set prediction to test mode"
);
DEFINE_double
(
prediction_test_duration
,
-
1.0
,
...
...
modules/prediction/common/prediction_gflags.h
浏览文件 @
6e8f8cc6
...
...
@@ -23,6 +23,7 @@
DECLARE_string
(
prediction_module_name
);
DECLARE_string
(
prediction_conf_file
);
DECLARE_string
(
prediction_adapter_config_filename
);
DECLARE_string
(
prediction_data_file_prefix
);
DECLARE_bool
(
prediction_test_mode
);
DECLARE_double
(
prediction_test_duration
);
...
...
modules/prediction/conf/prediction.conf
浏览文件 @
6e8f8cc6
...
...
@@ -3,6 +3,7 @@
--
enable_adjust_velocity_heading
--
noenable_kf_tracking
--
prediction_offline_mode
--
enable_trim_prediction_trajectory
--
lane_change_dist
=
50
.
0
...
...
modules/prediction/evaluator/vehicle/mlp_evaluator.cc
浏览文件 @
6e8f8cc6
...
...
@@ -84,6 +84,10 @@ void MLPEvaluator::Evaluate(Obstacle* obstacle_ptr) {
double
probability
=
ComputeProbability
(
feature_values
);
lane_sequence_ptr
->
set_probability
(
probability
);
}
if
(
FLAGS_prediction_offline_mode
)
{
FeatureOutput
::
instance
()
->
Insert
(
*
latest_feature_ptr
);
}
}
void
MLPEvaluator
::
ExtractFeatureValues
(
Obstacle
*
obstacle_ptr
,
...
...
modules/prediction/proto/offline_features.proto
浏览文件 @
6e8f8cc6
...
...
@@ -5,5 +5,5 @@ package apollo.prediction;
import
"modules/prediction/proto/feature.proto"
;
message
Features
{
repeated
Feature
feature
s
=
1
;
repeated
Feature
feature
=
1
;
}
编辑
预览
Markdown
is supported
0%
请重试
或
添加新附件
.
添加附件
取消
You are about to add
0
people
to the discussion. Proceed with caution.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录