提交 dd046544 编写于 作者: P panjiacheng 提交者: Kecheng Xu

Prediction: bug fixes and updates.

上级 eb7a5a24
...@@ -17,6 +17,7 @@ ...@@ -17,6 +17,7 @@
#include "modules/prediction/common/feature_output.h" #include "modules/prediction/common/feature_output.h"
#include <string> #include <string>
#include <vector>
#include "modules/common/util/file.h" #include "modules/common/util/file.h"
#include "modules/prediction/common/prediction_system_gflags.h" #include "modules/prediction/common/prediction_system_gflags.h"
...@@ -25,7 +26,7 @@ namespace apollo { ...@@ -25,7 +26,7 @@ namespace apollo {
namespace prediction { namespace prediction {
Features FeatureOutput::features_; Features FeatureOutput::features_;
DataForLearning FeatureOutput::data_for_learning_; ListDataForLearning FeatureOutput::list_data_for_learning_;
std::size_t FeatureOutput::index_ = 0; std::size_t FeatureOutput::index_ = 0;
void FeatureOutput::Close() { void FeatureOutput::Close() {
...@@ -37,7 +38,7 @@ void FeatureOutput::Close() { ...@@ -37,7 +38,7 @@ void FeatureOutput::Close() {
void FeatureOutput::Clear() { void FeatureOutput::Clear() {
index_ = 0; index_ = 0;
features_.Clear(); features_.Clear();
data_for_learning_.Clear(); list_data_for_learning_.Clear();
} }
bool FeatureOutput::Ready() { bool FeatureOutput::Ready() {
...@@ -49,9 +50,15 @@ void FeatureOutput::Insert(const Feature& feature) { ...@@ -49,9 +50,15 @@ void FeatureOutput::Insert(const Feature& feature) {
features_.add_feature()->CopyFrom(feature); features_.add_feature()->CopyFrom(feature);
} }
void FeatureOutput::InsertIntoLearningData(const Feature& feature) { void FeatureOutput::InsertDataForLearning(
data_for_learning_.set_id(feature.id()); const Feature& feature, const std::vector<double>& feature_values) {
data_for_learning_.set_timestamp(feature.timestamp()); DataForLearning* data_for_learning =
list_data_for_learning_.add_data_for_learning();
data_for_learning->set_id(feature.id());
data_for_learning->set_timestamp(feature.timestamp());
for (size_t i = 0; i < feature_values.size(); ++i) {
data_for_learning->add_features_for_learning(feature_values[i]);
}
} }
void FeatureOutput::Write() { void FeatureOutput::Write() {
...@@ -66,14 +73,14 @@ void FeatureOutput::Write() { ...@@ -66,14 +73,14 @@ void FeatureOutput::Write() {
++index_; ++index_;
} }
if (!data_for_learning_.has_id()) { if (!list_data_for_learning_.data_for_learning_size() <= 0) {
ADEBUG << "Skip writing empty data_for_learning."; ADEBUG << "Skip writing empty data_for_learning.";
} else { } else {
const std::string file_name = const std::string file_name =
FLAGS_prediction_data_dir + "/datalearn." + FLAGS_prediction_data_dir + "/datalearn." +
std::to_string(index_) + ".bin"; std::to_string(index_) + ".bin";
common::util::SetProtoToBinaryFile(data_for_learning_, file_name); common::util::SetProtoToBinaryFile(list_data_for_learning_, file_name);
data_for_learning_.Clear(); list_data_for_learning_.Clear();
} }
} }
......
...@@ -16,6 +16,8 @@ ...@@ -16,6 +16,8 @@
#pragma once #pragma once
#include <vector>
#include "modules/prediction/proto/offline_features.pb.h" #include "modules/prediction/proto/offline_features.pb.h"
namespace apollo { namespace apollo {
...@@ -54,7 +56,8 @@ class FeatureOutput { ...@@ -54,7 +56,8 @@ class FeatureOutput {
* @brief Insert a data_for_learning * @brief Insert a data_for_learning
* @param A feature in proto * @param A feature in proto
*/ */
static void InsertIntoLearningData(const Feature& feature); static void InsertDataForLearning(
const Feature& feature, const std::vector<double>& feature_values);
/** /**
* @brief Write features to a file * @brief Write features to a file
...@@ -69,7 +72,7 @@ class FeatureOutput { ...@@ -69,7 +72,7 @@ class FeatureOutput {
private: private:
static Features features_; static Features features_;
static DataForLearning data_for_learning_; static ListDataForLearning list_data_for_learning_;
static std::size_t index_; static std::size_t index_;
}; };
......
...@@ -1143,11 +1143,14 @@ void Obstacle::BuildLaneGraphFromLeftToRight() { ...@@ -1143,11 +1143,14 @@ void Obstacle::BuildLaneGraphFromLeftToRight() {
// Treat the most probable lane_segment as the center, put its left // Treat the most probable lane_segment as the center, put its left
// and right neighbors into a vector following the left-to-right order. // and right neighbors into a vector following the left-to-right order.
if (!feature->has_lane() || !feature->lane().has_lane_feature()) {
return;
}
std::shared_ptr<const LaneInfo> center_lane_info = std::shared_ptr<const LaneInfo> center_lane_info =
PredictionMap::LaneById(feature->lane().lane_feature().lane_id()); PredictionMap::LaneById(feature->lane().lane_feature().lane_id());
std::vector<std::string> lane_ids_ordered; std::vector<std::string> lane_ids_ordered;
for (int i = center_lane_info->lane().left_neighbor_forward_lane_id().size() for (int i = center_lane_info->lane().left_neighbor_forward_lane_id().size()
- 1; i >= 0; i --) { - 1; i >= 0; --i) {
if (center_lane_info->lane().left_neighbor_forward_lane_id(i).has_id()) { if (center_lane_info->lane().left_neighbor_forward_lane_id(i).has_id()) {
lane_ids_ordered.push_back( lane_ids_ordered.push_back(
center_lane_info->lane().left_neighbor_forward_lane_id(i).id()); center_lane_info->lane().left_neighbor_forward_lane_id(i).id());
...@@ -1165,7 +1168,7 @@ void Obstacle::BuildLaneGraphFromLeftToRight() { ...@@ -1165,7 +1168,7 @@ void Obstacle::BuildLaneGraphFromLeftToRight() {
// Build lane_graph for every lane_segment and update it into proto. // Build lane_graph for every lane_segment and update it into proto.
int seq_id = 0; int seq_id = 0;
for (size_t i = 0; i < lane_ids_ordered.size(); i ++) { for (size_t i = 0; i < lane_ids_ordered.size(); ++i) {
// Construct the local lane_graph based on the current lane_segment. // Construct the local lane_graph based on the current lane_segment.
bool vehicle_is_on_lane = (lane_ids_ordered[i] == bool vehicle_is_on_lane = (lane_ids_ordered[i] ==
center_lane_info->lane().id().id()); center_lane_info->lane().id().id());
......
...@@ -25,8 +25,6 @@ ...@@ -25,8 +25,6 @@
#include "modules/prediction/common/prediction_system_gflags.h" #include "modules/prediction/common/prediction_system_gflags.h"
#include "modules/prediction/container/obstacles/obstacle_clusters.h" #include "modules/prediction/container/obstacles/obstacle_clusters.h"
#define ADEBUG AINFO
namespace apollo { namespace apollo {
namespace prediction { namespace prediction {
......
...@@ -83,9 +83,9 @@ void LaneScanningEvaluator::Evaluate(Obstacle* obstacle_ptr) { ...@@ -83,9 +83,9 @@ void LaneScanningEvaluator::Evaluate(Obstacle* obstacle_ptr) {
// - if in online mode, pass it through trained model to evaluate. // - if in online mode, pass it through trained model to evaluate.
std::vector<double> feature_values; std::vector<double> feature_values;
ExtractFeatures(obstacle_ptr, lane_graph_ptr, &feature_values); ExtractFeatures(obstacle_ptr, lane_graph_ptr, &feature_values);
// TODO(jiacheng): sanity check of extracted feature_values:
if (FLAGS_prediction_offline_mode) { if (FLAGS_prediction_offline_mode) {
// TODO(jiacheng): save the extracted features locally for offline training. FeatureOutput::InsertDataForLearning(*latest_feature_ptr, feature_values);
ADEBUG << "Save extracted features for learning locally.";
} else { } else {
// TODO(jiacheng): once the model is trained, implement this online part. // TODO(jiacheng): once the model is trained, implement this online part.
} }
...@@ -122,10 +122,16 @@ bool LaneScanningEvaluator::ExtractFeatures( ...@@ -122,10 +122,16 @@ bool LaneScanningEvaluator::ExtractFeatures(
ADEBUG << "Failed to extract static environmental features around obs_id = " ADEBUG << "Failed to extract static environmental features around obs_id = "
<< id; << id;
} }
// TODO(jiacheng): sanity check of extracted static env features: if (static_feature_values.size() %
(SINGLE_LANE_FEATURE_SIZE * LANE_POINTS_SIZE) != 0) {
ADEBUG << "Obstacle [" << id << "] has incorrect static env feature size: "
<< static_feature_values.size() << ".";
return false;
}
feature_values->insert(feature_values->end(), feature_values->insert(feature_values->end(),
static_feature_values.begin(), static_feature_values.begin(),
static_feature_values.end()); static_feature_values.end());
return true; return true;
} }
......
...@@ -74,7 +74,7 @@ class LaneScanningEvaluator : public Evaluator { ...@@ -74,7 +74,7 @@ class LaneScanningEvaluator : public Evaluator {
static const size_t OBSTACLE_FEATURE_SIZE = 5 * 9; static const size_t OBSTACLE_FEATURE_SIZE = 5 * 9;
static const size_t INTERACTION_FEATURE_SIZE = 8; static const size_t INTERACTION_FEATURE_SIZE = 8;
static const size_t SINGLE_LANE_FEATURE_SIZE = 4; static const size_t SINGLE_LANE_FEATURE_SIZE = 4;
static const size_t LANE_POINTS_SIZE = 20; static const size_t LANE_POINTS_SIZE = 100; // (100 * 0.2m = 20m)
}; };
} // namespace prediction } // namespace prediction
......
...@@ -29,4 +29,4 @@ message DataForLearning { ...@@ -29,4 +29,4 @@ message DataForLearning {
message ListDataForLearning { message ListDataForLearning {
repeated DataForLearning data_for_learning = 1; repeated DataForLearning data_for_learning = 1;
} }
\ No newline at end of file
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册