提交 6e8f8cc6 编写于 作者: K kechxu 提交者: Kecheng Xu

Prediction: Implement Insert feature and write to file

上级 2c1d36a7
...@@ -74,8 +74,10 @@ cc_library( ...@@ -74,8 +74,10 @@ cc_library(
deps = [ deps = [
"//modules/prediction/proto:feature_proto", "//modules/prediction/proto:feature_proto",
"//modules/prediction/proto:offline_features_proto", "//modules/prediction/proto:offline_features_proto",
"//modules/prediction/common:prediction_gflags",
"//modules/common:log", "//modules/common:log",
"//modules/common:macro", "//modules/common:macro",
"//modules/common/util:util",
] ]
) )
......
...@@ -16,24 +16,41 @@ ...@@ -16,24 +16,41 @@
#include "modules/prediction/common/feature_output.h" #include "modules/prediction/common/feature_output.h"
#include <string>
#include "modules/common/log.h" #include "modules/common/log.h"
#include "modules/common/util/file.h"
#include "modules/prediction/common/prediction_gflags.h"
namespace apollo { namespace apollo {
namespace prediction { namespace prediction {
FeatureOutput::FeatureOutput() {} FeatureOutput::FeatureOutput() {}
FeatureOutput::~FeatureOutput() {}
bool FeatureOutput::Open() { return true; } 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 prediction
} // namespace apollo } // namespace apollo
...@@ -61,7 +61,7 @@ class FeatureOutput { ...@@ -61,7 +61,7 @@ class FeatureOutput {
private: private:
Features features_; Features features_;
size_t count = 0; size_t count_ = 0;
DECLARE_SINGLETON(FeatureOutput); DECLARE_SINGLETON(FeatureOutput);
}; };
......
...@@ -27,6 +27,9 @@ DEFINE_string(prediction_conf_file, ...@@ -27,6 +27,9 @@ DEFINE_string(prediction_conf_file,
DEFINE_string(prediction_adapter_config_filename, DEFINE_string(prediction_adapter_config_filename,
"modules/prediction/conf/adapter.conf", "modules/prediction/conf/adapter.conf",
"Default conf file for prediction"); "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_bool(prediction_test_mode, false, "Set prediction to test mode");
DEFINE_double( DEFINE_double(
prediction_test_duration, -1.0, prediction_test_duration, -1.0,
......
...@@ -23,6 +23,7 @@ ...@@ -23,6 +23,7 @@
DECLARE_string(prediction_module_name); DECLARE_string(prediction_module_name);
DECLARE_string(prediction_conf_file); DECLARE_string(prediction_conf_file);
DECLARE_string(prediction_adapter_config_filename); DECLARE_string(prediction_adapter_config_filename);
DECLARE_string(prediction_data_file_prefix);
DECLARE_bool(prediction_test_mode); DECLARE_bool(prediction_test_mode);
DECLARE_double(prediction_test_duration); DECLARE_double(prediction_test_duration);
......
...@@ -3,6 +3,7 @@ ...@@ -3,6 +3,7 @@
--enable_adjust_velocity_heading --enable_adjust_velocity_heading
--noenable_kf_tracking --noenable_kf_tracking
--prediction_offline_mode
--enable_trim_prediction_trajectory --enable_trim_prediction_trajectory
--lane_change_dist=50.0 --lane_change_dist=50.0
......
...@@ -84,6 +84,10 @@ void MLPEvaluator::Evaluate(Obstacle* obstacle_ptr) { ...@@ -84,6 +84,10 @@ void MLPEvaluator::Evaluate(Obstacle* obstacle_ptr) {
double probability = ComputeProbability(feature_values); double probability = ComputeProbability(feature_values);
lane_sequence_ptr->set_probability(probability); lane_sequence_ptr->set_probability(probability);
} }
if (FLAGS_prediction_offline_mode) {
FeatureOutput::instance()->Insert(*latest_feature_ptr);
}
} }
void MLPEvaluator::ExtractFeatureValues(Obstacle* obstacle_ptr, void MLPEvaluator::ExtractFeatureValues(Obstacle* obstacle_ptr,
......
...@@ -5,5 +5,5 @@ package apollo.prediction; ...@@ -5,5 +5,5 @@ package apollo.prediction;
import "modules/prediction/proto/feature.proto"; import "modules/prediction/proto/feature.proto";
message Features { message Features {
repeated Feature features = 1; repeated Feature feature = 1;
} }
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册