提交 d66e76ee 编写于 作者: J jmtao 提交者: Yifei Jiang

planning: update learning_data proto to avoid naming conflict in...

planning: update learning_data proto to avoid naming conflict in TrajectoryPoint when being introduced to online training
上级 16a53324
......@@ -100,10 +100,11 @@ void Evaluator::WriteOutData(
void Evaluator::EvaluateTrajectoryByTime(
const int frame_num,
const std::string& obstacle_id,
const std::vector<std::pair<double, TrajectoryPointFeature>>& trajectory,
const std::vector<std::pair<double, CommonTrajectoryPointFeature>>&
trajectory,
const double start_point_timestamp_sec,
const double delta_time,
std::vector<TrajectoryPoint>* evaluated_trajectory) {
std::vector<TrajectoryPointFeature>* evaluated_trajectory) {
if (trajectory.empty() ||
fabs(trajectory.front().first - trajectory.back().first) <
FLAGS_trajectory_delta_t) {
......@@ -112,7 +113,7 @@ void Evaluator::EvaluateTrajectoryByTime(
std::vector<apollo::common::TrajectoryPoint> updated_trajectory;
for (const auto& tp : trajectory) {
// TrajectoryPointFeature => common::Trajectory
// CommonTrajectoryPointFeature => common::TrajectoryPoint
apollo::common::TrajectoryPoint trajectory_point;
auto path_point = trajectory_point.mutable_path_point();
path_point->set_x(tp.second.path_point().x());
......@@ -164,8 +165,8 @@ void Evaluator::EvaluateTrajectoryByTime(
double relative_time = i * delta_time;
auto tp = discretized_trajectory.Evaluate(relative_time);
// common::TrajectoryPoint => TrajectoryPoint
TrajectoryPoint trajectory_point;
// common::TrajectoryPoint => TrajectoryPointFeature
TrajectoryPointFeature trajectory_point;
trajectory_point.set_timestamp_sec(timestamp_sec);
auto path_point =
trajectory_point.mutable_trajectory_point()->mutable_path_point();
......@@ -189,7 +190,7 @@ void Evaluator::EvaluateTrajectoryByTime(
void Evaluator::EvaluateADCTrajectory(
const double start_point_timestamp_sec,
LearningDataFrame* learning_data_frame) {
std::vector<std::pair<double, TrajectoryPointFeature>> trajectory;
std::vector<std::pair<double, CommonTrajectoryPointFeature>> trajectory;
for (int i = 0; i < learning_data_frame->adc_trajectory_point_size(); i++) {
ADCTrajectoryPoint adc_tp =
learning_data_frame->adc_trajectory_point(i);
......@@ -225,7 +226,7 @@ void Evaluator::EvaluateADCTrajectory(
return;
}
std::vector<TrajectoryPoint> evaluated_trajectory;
std::vector<TrajectoryPointFeature> evaluated_trajectory;
EvaluateTrajectoryByTime(learning_data_frame->frame_num(),
"adc_trajectory",
trajectory,
......@@ -260,10 +261,10 @@ void Evaluator::EvaluateADCTrajectory(
void Evaluator::EvaluateADCFutureTrajectory(
const double start_point_timestamp_sec,
LearningDataFrame* learning_data_frame) {
std::vector<std::pair<double, TrajectoryPointFeature>> trajectory;
std::vector<std::pair<double, CommonTrajectoryPointFeature>> trajectory;
for (int i = 0; i <
learning_data_frame->output().adc_future_trajectory_point_size(); i++) {
ADCTrajectoryPoint adc_tp =
TrajectoryPointFeature adc_tp =
learning_data_frame->output().adc_future_trajectory_point(i);
trajectory.push_back(std::make_pair(adc_tp.timestamp_sec(),
adc_tp.trajectory_point()));
......@@ -304,7 +305,7 @@ void Evaluator::EvaluateADCFutureTrajectory(
return;
}
std::vector<TrajectoryPoint> evaluated_trajectory;
std::vector<TrajectoryPointFeature> evaluated_trajectory;
EvaluateTrajectoryByTime(learning_data_frame->frame_num(),
"adc_future_trajectory",
trajectory,
......@@ -365,13 +366,13 @@ void Evaluator::EvaluateObstacleTrajectory(
const int obstacle_id = learning_data_frame->obstacle(i).id();
const auto obstacle_trajectory =
learning_data_frame->obstacle(i).obstacle_trajectory();
std::vector<std::pair<double, TrajectoryPointFeature>> trajectory;
std::vector<std::pair<double, CommonTrajectoryPointFeature>> trajectory;
for (int j = 0; j <
obstacle_trajectory.perception_obstacle_history_size(); ++j) {
const auto perception_obstacle =
obstacle_trajectory.perception_obstacle_history(j);
TrajectoryPointFeature trajectory_point;
CommonTrajectoryPointFeature trajectory_point;
trajectory_point.mutable_path_point()->set_x(
perception_obstacle.position().x());
trajectory_point.mutable_path_point()->set_y(
......@@ -408,7 +409,7 @@ void Evaluator::EvaluateObstacleTrajectory(
continue;
}
std::vector<TrajectoryPoint> evaluated_trajectory;
std::vector<TrajectoryPointFeature> evaluated_trajectory;
EvaluateTrajectoryByTime(learning_data_frame->frame_num(),
std::to_string(obstacle_id),
trajectory,
......@@ -448,7 +449,7 @@ void Evaluator::EvaluateObstaclePredictionTrajectory(
const auto obstacle_prediction_trajectory =
obstacle_prediction.trajectory(j);
std::vector<std::pair<double, TrajectoryPointFeature>> trajectory;
std::vector<std::pair<double, CommonTrajectoryPointFeature>> trajectory;
for (int k = 0; k <
obstacle_prediction_trajectory.trajectory_point_size(); ++k) {
const double timestamp_sec = obstacle_prediction.timestamp_sec() +
......@@ -470,7 +471,7 @@ void Evaluator::EvaluateObstaclePredictionTrajectory(
continue;
}
std::vector<TrajectoryPoint> evaluated_trajectory;
std::vector<TrajectoryPointFeature> evaluated_trajectory;
EvaluateTrajectoryByTime(learning_data_frame->frame_num(),
std::to_string(obstacle_id),
trajectory,
......
......@@ -38,10 +38,11 @@ class Evaluator {
void EvaluateTrajectoryByTime(
const int frame_num,
const std::string& obstacle_id,
const std::vector<std::pair<double, TrajectoryPointFeature>>& trajectory,
const std::vector<std::pair<double, CommonTrajectoryPointFeature>>&
trajectory,
const double start_point_timestamp_sec,
const double delta_time,
std::vector<TrajectoryPoint>* evaluated_trajectory);
std::vector<TrajectoryPointFeature>* evaluated_trajectory);
void EvaluateADCTrajectory(const double start_point_timestamp_sec,
LearningDataFrame* learning_data_frame);
......
......@@ -74,7 +74,7 @@ message LocalizationFeature {
}
// based on apollo.common.PathPoint
message PathPointFeature {
message CommonPathPointFeature {
// coordinates
optional double x = 1;
optional double y = 2;
......@@ -89,9 +89,9 @@ message PathPointFeature {
}
// based on apollo.commom.TrajectoryPoint
message TrajectoryPointFeature {
message CommonTrajectoryPointFeature {
// path point
optional PathPointFeature path_point = 1;
optional CommonPathPointFeature path_point = 1;
// linear velocity
optional double v = 2; // in [m/s]
// linear acceleration
......@@ -102,9 +102,9 @@ message TrajectoryPointFeature {
optional apollo.common.GaussianInfo gaussian_info = 5;
}
message TrajectoryPoint {
message TrajectoryPointFeature {
optional double timestamp_sec = 1;
optional TrajectoryPointFeature trajectory_point = 2;
optional CommonTrajectoryPointFeature trajectory_point = 2;
}
// based on apollo.perception.PerceptionObstacle
......@@ -129,13 +129,13 @@ message PerceptionObstacleFeature {
message ObstacleTrajectoryFeature {
repeated PerceptionObstacleFeature perception_obstacle_history = 1;
repeated TrajectoryPoint evaluated_trajectory_point = 2;
repeated TrajectoryPointFeature evaluated_trajectory_point = 2;
}
// based on apollo.prediction.Trajectory
message PredictionTrajectoryFeature {
optional double probability = 1; // probability of this trajectory
repeated TrajectoryPoint trajectory_point = 2;
repeated TrajectoryPointFeature trajectory_point = 2;
}
// based on apollo.prediction.PredictionObstacle
......@@ -183,11 +183,11 @@ message TrafficLightDetectionFeature {
message ADCTrajectoryPoint {
optional double timestamp_sec = 1; // localization measurement_time
optional PlanningTag planning_tag = 2;
optional TrajectoryPointFeature trajectory_point = 3;
optional CommonTrajectoryPointFeature trajectory_point = 3;
}
message LearningOutput {
repeated ADCTrajectoryPoint adc_future_trajectory_point = 1;
repeated TrajectoryPointFeature adc_future_trajectory_point = 1;
}
message LearningDataFrame {
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册