提交 7e2fc764 编写于 作者: J jmtao 提交者: Xiangquan Xiao

planning: add obstacle data to learning data

上级 45bfddff
......@@ -112,8 +112,8 @@ void FeatureGenerator::OnPerceptionObstacle(
const apollo::perception::PerceptionObstacles& perception_obstacles) {
perception_obstacles_map_.clear();
for (int i = 0; i < perception_obstacles.perception_obstacle_size(); ++i) {
const auto& perception_obstale = perception_obstacles.perception_obstacle(i);
const auto& perception_obstale =
perception_obstacles.perception_obstacle(i);
const int obstacle_id = perception_obstale.id();
perception_obstacles_map_[obstacle_id].CopyFrom(perception_obstale);
}
......@@ -193,6 +193,35 @@ void FeatureGenerator::OnRoutingResponse(
}
}
void FeatureGenerator::GenerateObstacleData(
LearningDataFrame* learning_data_frame) {
for (const auto& m : perception_obstacles_map_) {
auto obstacle_feature = learning_data_frame->add_obstacle();
obstacle_feature->set_id(m.first);
obstacle_feature->set_length(m.second.length());
obstacle_feature->set_width(m.second.width());
obstacle_feature->set_height(m.second.height());
obstacle_feature->set_type(m.second.type());
const auto& obstacle_history = obstacle_history_map_[m.first];
for (const auto& obj_traj_point : obstacle_history) {
auto obstacle_trajectory_point =
obstacle_feature->add_obstacle_trajectory_point();
obstacle_trajectory_point->set_timestamp(obj_traj_point.timestamp());
obstacle_trajectory_point->mutable_position()->CopyFrom(
obj_traj_point.position());
obstacle_trajectory_point->set_theta(obj_traj_point.theta());
obstacle_trajectory_point->mutable_velocity()->CopyFrom(
obj_traj_point.velocity());
obstacle_trajectory_point->mutable_polygon_point()->CopyFrom(
obj_traj_point.polygon_point());
obstacle_trajectory_point->mutable_acceleration()->CopyFrom(
obj_traj_point.acceleration());
}
}
}
void FeatureGenerator::GenerateTrajectoryPoints(
const std::list<apollo::localization::LocalizationEstimate>&
localization_for_label,
......@@ -262,6 +291,9 @@ void FeatureGenerator::GenerateLearningDataFrame() {
routing_response->add_lane_id(lane_id);
}
// add obstacle
GenerateObstacleData(learning_data_frame);
// add trajectory_points
GenerateTrajectoryPoints(localization_for_label_, learning_data_frame);
}
......
......@@ -48,6 +48,8 @@ class FeatureGenerator {
void OnTafficLightDetection(
const apollo::perception::TrafficLightDetection& traffic_light_detection);
void GenerateObstacleData(LearningDataFrame* learning_data_frame);
void GenerateTrajectoryPoints(
const std::list<apollo::localization::LocalizationEstimate>&
localization_for_label,
......
......@@ -5,6 +5,7 @@ package apollo.planning;
import "modules/canbus/proto/chassis.proto";
import "modules/common/proto/geometry.proto";
import "modules/common/proto/pnc_point.proto";
import "modules/perception/proto/perception_obstacle.proto";
import "modules/perception/proto/traffic_light_detection.proto";
import "modules/routing/proto/routing.proto";
......@@ -75,17 +76,7 @@ message ObstacleFeature {
optional double length = 2; // obstacle length.
optional double width = 3; // obstacle width.
optional double height = 4; // obstacle height.
enum Type {
UNKNOWN = 0;
UNKNOWN_MOVABLE = 1;
UNKNOWN_UNMOVABLE = 2;
PEDESTRIAN = 3; // Pedestrian, usually determined by moving behavior.
BICYCLE = 4; // bike, motor bike
VEHICLE = 5; // Passenger car or truck.
};
optional Type type = 5; // obstacle type
optional apollo.perception.PerceptionObstacle.Type type = 5; // obstacle type
repeated ObstacleTrajectoryPoint obstacle_trajectory_point = 6;
}
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册