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

planning: add timestamp to every adc trajectory point in learning data

上级 1cb8748a
......@@ -135,7 +135,7 @@ void FeatureGenerator::OnPerceptionObstacle(
for (const auto& m : perception_obstacles_map_) {
const auto& perception_obstale = m.second;
ObstacleTrajectoryPoint obstacle_trajectory_point;
obstacle_trajectory_point.set_timestamp(perception_obstale.timestamp());
obstacle_trajectory_point.set_timestamp_sec(perception_obstale.timestamp());
obstacle_trajectory_point.mutable_position()->CopyFrom(
perception_obstale.position());
obstacle_trajectory_point.set_theta(perception_obstale.theta());
......@@ -219,7 +219,8 @@ void FeatureGenerator::GenerateObstacleData(
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->set_timestamp_sec(
obj_traj_point.timestamp_sec());
// convert position to relative coordinate
const auto& relative_posistion =
......@@ -272,8 +273,7 @@ void FeatureGenerator::GenerateObstacleData(
}
}
void FeatureGenerator::GenerateTrajectoryPoints(
void FeatureGenerator::GenerateADCTrajectoryPoints(
const std::list<apollo::localization::LocalizationEstimate>&
localization_for_label,
LearningDataFrame* learning_data_frame) {
......@@ -287,7 +287,10 @@ void FeatureGenerator::GenerateTrajectoryPoints(
if ((i % localization_sample_interval_for_trajectory_point) != 0) {
continue;
}
auto trajectory_point = learning_data_frame->add_trajectory_point();
auto adc_trajectory_point = learning_data_frame->add_adc_trajectory_point();
adc_trajectory_point->set_timestamp_sec(le.measurement_time());
auto trajectory_point = adc_trajectory_point->mutable_trajectory_point();
auto& pose = le.pose();
trajectory_point->mutable_path_point()->set_x(pose.position().x());
trajectory_point->mutable_path_point()->set_y(pose.position().y());
......@@ -346,7 +349,7 @@ void FeatureGenerator::GenerateLearningDataFrame() {
GenerateObstacleData(learning_data_frame);
// add trajectory_points
GenerateTrajectoryPoints(localization_for_label_, learning_data_frame);
GenerateADCTrajectoryPoints(localization_for_label_, learning_data_frame);
}
void FeatureGenerator::ProcessOfflineData(const std::string& record_filename) {
......
......@@ -51,7 +51,7 @@ class FeatureGenerator {
void GenerateObstacleData(LearningDataFrame* learning_data_frame);
void GenerateTrajectoryPoints(
void GenerateADCTrajectoryPoints(
const std::list<apollo::localization::LocalizationEstimate>&
localization_for_label,
LearningDataFrame* learning_data_frame);
......
......@@ -45,7 +45,7 @@ void GenerateDataForLearning() {
AINFO << "For input " << input << ", found " << offline_bags.size()
<< " rosbags to process";
for (std::size_t i = 0; i < offline_bags.size(); ++i) {
AINFO << "\tProcessing: [ " << i << " / " << offline_bags.size()
AINFO << "\tProcessing: [ " << i + 1 << " / " << offline_bags.size()
<< " ]: " << offline_bags[i];
feature_generator.ProcessOfflineData(offline_bags[i]);
}
......
......@@ -53,7 +53,7 @@ message LocalizationFeature {
}
message ObstacleTrajectoryPoint {
optional double timestamp = 1; // GPS time in seconds.
optional double timestamp_sec = 1;
// obstacle position in the OBJECT coordinate system
optional apollo.common.Point3D position = 2;
......@@ -89,12 +89,15 @@ message TrafficLightFeature {
optional apollo.perception.TrafficLight.Color color = 2;
}
message ADCTrajectoryPoint {
optional double timestamp_sec = 1; // localization measurement_time
optional apollo.common.TrajectoryPoint trajectory_point = 2;
}
message LearningDataFrame {
// Message publishing time in seconds.
// localization message publishing time in seconds.
optional double timestamp_sec = 1;
// Sequence number for each frame
// sequence_num, always starting from 1.
optional uint32 frame_num = 2;
// Features from chassis
......@@ -113,7 +116,7 @@ message LearningDataFrame {
repeated TrafficLightFeature traffic_light = 7;
// ADC ground-truth label trajectory
repeated apollo.common.TrajectoryPoint trajectory_point = 8;
repeated ADCTrajectoryPoint adc_trajectory_point = 8;
}
message LearningData {
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册