feature_output.cc 7.6 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18
/******************************************************************************
 * Copyright 2017 The Apollo Authors. All Rights Reserved.
 *
 * Licensed under the Apache License, Version 2.0 (the "License");
 * you may not use this file except in compliance with the License.
 * You may obtain a copy of the License at
 *
 * http://www.apache.org/licenses/LICENSE-2.0
 *
 * Unless required by applicable law or agreed to in writing, software
 * distributed under the License is distributed on an "AS IS" BASIS,
 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
 * See the License for the specific language governing permissions and
 * limitations under the License.
 *****************************************************************************/

#include "modules/prediction/common/feature_output.h"

P
panjiacheng 已提交
19
#include <vector>
20

21
#include "cyber/common/file.h"
K
kechxu 已提交
22
#include "modules/common/util/string_util.h"
23
#include "modules/prediction/common/prediction_system_gflags.h"
24 25 26 27

namespace apollo {
namespace prediction {

K
kechxu 已提交
28 29
using apollo::common::util::StrCat;

30
Features FeatureOutput::features_;
P
panjiacheng 已提交
31
ListDataForLearning FeatureOutput::list_data_for_learning_;
32
ListPredictionResult FeatureOutput::list_prediction_result_;
K
kechxu 已提交
33
ListFrameEnv FeatureOutput::list_frame_env_;
34
ListDataForTuning FeatureOutput::list_data_for_tuning_;
35 36
std::size_t FeatureOutput::idx_feature_ = 0;
std::size_t FeatureOutput::idx_learning_ = 0;
37
std::size_t FeatureOutput::idx_prediction_result_ = 0;
K
kechxu 已提交
38
std::size_t FeatureOutput::idx_frame_env_ = 0;
39
std::size_t FeatureOutput::idx_tuning_ = 0;
40

41 42
void FeatureOutput::Close() {
  ADEBUG << "Close feature output";
43 44 45
  switch (FLAGS_prediction_offline_mode) {
    case 1: {
      WriteFeatureProto();
K
kechxu 已提交
46
      break;
47 48 49
    }
    case 2: {
      WriteDataForLearning();
K
kechxu 已提交
50
      break;
51 52 53
    }
    case 3: {
      WritePredictionResult();
K
kechxu 已提交
54
      break;
55
    }
K
kechxu 已提交
56 57
    case 4: {
      WriteFrameEnv();
K
kechxu 已提交
58 59
      break;
    }
60 61 62 63
    case 5: {
      WriteDataForTuning();
      break;
    }
K
kechxu 已提交
64 65 66
    default: {
      // No data dump
      break;
K
kechxu 已提交
67
    }
68
  }
K
kechxu 已提交
69 70 71 72
  Clear();
}

void FeatureOutput::Clear() {
73 74
  idx_feature_ = 0;
  idx_learning_ = 0;
K
kechxu 已提交
75
  features_.Clear();
P
panjiacheng 已提交
76
  list_data_for_learning_.Clear();
77
}
78

C
Calvin Miao 已提交
79 80 81 82
bool FeatureOutput::Ready() {
  Clear();
  return true;
}
K
kechxu 已提交
83

84
void FeatureOutput::InsertFeatureProto(const Feature& feature) {
85 86 87
  features_.add_feature()->CopyFrom(feature);
}

P
panjiacheng 已提交
88
void FeatureOutput::InsertDataForLearning(
89
    const Feature& feature, const std::vector<double>& feature_values,
90
    const std::string& category, const LaneSequence* lane_sequence_ptr) {
P
panjiacheng 已提交
91
  const std::vector<std::string> dummy_string_feature_values;
92 93 94 95
  InsertDataForLearning(feature, feature_values, dummy_string_feature_values,
                        category, lane_sequence_ptr);
}

X
Xiangquan Xiao 已提交
96 97 98 99
void FeatureOutput::InsertDataForLearning(
    const Feature& feature, const std::vector<double>& feature_values,
    const std::vector<std::string>& string_feature_values,
    const std::string& category, const LaneSequence* lane_sequence_ptr) {
P
panjiacheng 已提交
100 101 102 103
  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());
P
panjiacheng 已提交
104 105 106 107
  *(data_for_learning->mutable_features_for_learning()) = {
      feature_values.begin(), feature_values.end()};
  *(data_for_learning->mutable_string_features_for_learning()) = {
      string_feature_values.begin(), string_feature_values.end()};
108
  data_for_learning->set_category(category);
X
 
Xiangquan Xiao 已提交
109 110
  ADEBUG << "Insert [" << category
         << "] data for learning with size = " << feature_values.size();
111 112 113 114
  if (lane_sequence_ptr != nullptr) {
    data_for_learning->set_lane_sequence_id(
        lane_sequence_ptr->lane_sequence_id());
  }
115 116
}

117
void FeatureOutput::InsertPredictionResult(
118
    const int obstacle_id, const PredictionObstacle& prediction_obstacle) {
119 120 121 122 123 124 125 126 127 128
  PredictionResult* prediction_result =
      list_prediction_result_.add_prediction_result();
  prediction_result->set_id(obstacle_id);
  prediction_result->set_timestamp(prediction_obstacle.timestamp());
  for (int i = 0; i < prediction_obstacle.trajectory_size(); ++i) {
    prediction_result->add_trajectory()->CopyFrom(
        prediction_obstacle.trajectory(i));
  }
}

K
kechxu 已提交
129 130 131 132
void FeatureOutput::InsertFrameEnv(const FrameEnv& frame_env) {
  list_frame_env_.add_frame_env()->CopyFrom(frame_env);
}

133 134
void FeatureOutput::InsertDataForTuning(
    const Feature& feature, const std::vector<double>& feature_values,
135
    const std::string& category, const LaneSequence& lane_sequence) {
A
Aaron Xiao 已提交
136
  DataForTuning* data_for_tuning = list_data_for_tuning_.add_data_for_tuning();
137 138
  data_for_tuning->set_id(feature.id());
  data_for_tuning->set_timestamp(feature.timestamp());
A
Aaron Xiao 已提交
139 140
  *data_for_tuning->mutable_values_for_tuning() = {feature_values.begin(),
                                                   feature_values.end()};
141 142 143
  data_for_tuning->set_category(category);
  ADEBUG << "Insert [" << category
         << "] data for tuning with size = " << feature_values.size();
144
  data_for_tuning->set_lane_sequence_id(lane_sequence.lane_sequence_id());
145 146
}

147
void FeatureOutput::WriteFeatureProto() {
K
kechxu 已提交
148 149
  if (features_.feature_size() <= 0) {
    ADEBUG << "Skip writing empty feature.";
150
  } else {
151 152
    const std::string file_name = StrCat(FLAGS_prediction_data_dir, "/feature.",
                                         std::to_string(idx_feature_), ".bin");
153
    cyber::common::SetProtoToBinaryFile(features_, file_name);
154
    features_.Clear();
155
    ++idx_feature_;
156
  }
157
}
158

159
void FeatureOutput::WriteDataForLearning() {
K
kechxu 已提交
160
  if (list_data_for_learning_.data_for_learning().empty()) {
161 162
    ADEBUG << "Skip writing empty data_for_learning.";
  } else {
163 164 165
    const std::string file_name =
        StrCat(FLAGS_prediction_data_dir, "/datalearn.",
               std::to_string(idx_learning_), ".bin");
166
    cyber::common::SetProtoToBinaryFile(list_data_for_learning_, file_name);
P
panjiacheng 已提交
167
    list_data_for_learning_.Clear();
168
    ++idx_learning_;
K
kechxu 已提交
169
  }
170
}
171

172
void FeatureOutput::WritePredictionResult() {
K
kechxu 已提交
173
  if (list_prediction_result_.prediction_result().empty()) {
174 175
    ADEBUG << "Skip writing empty prediction_result.";
  } else {
176 177 178
    const std::string file_name =
        StrCat(FLAGS_prediction_data_dir, "/prediction_result.",
               std::to_string(idx_prediction_result_), ".bin");
179
    cyber::common::SetProtoToBinaryFile(list_prediction_result_, file_name);
180 181 182 183 184
    list_prediction_result_.Clear();
    ++idx_prediction_result_;
  }
}

K
kechxu 已提交
185
void FeatureOutput::WriteFrameEnv() {
K
kechxu 已提交
186
  if (list_frame_env_.frame_env().empty()) {
K
kechxu 已提交
187 188
    ADEBUG << "Skip writing empty prediction_result.";
  } else {
189 190 191
    const std::string file_name =
        StrCat(FLAGS_prediction_data_dir, "/frame_env.",
               std::to_string(idx_frame_env_), ".bin");
K
kechxu 已提交
192
    cyber::common::SetProtoToBinaryFile(list_frame_env_, file_name);
K
kechxu 已提交
193 194 195 196 197
    list_frame_env_.Clear();
    ++idx_frame_env_;
  }
}

198 199 200 201 202 203 204 205 206 207 208 209 210
void FeatureOutput::WriteDataForTuning() {
  if (list_data_for_tuning_.data_for_tuning().empty()) {
    ADEBUG << "Skip writing empty data_for_tuning.";
    return;
  }
  const std::string file_name =
      StrCat(FLAGS_prediction_data_dir, "/datatuning.",
             std::to_string(idx_tuning_), ".bin");
  cyber::common::SetProtoToBinaryFile(list_data_for_tuning_, file_name);
  list_data_for_tuning_.Clear();
  ++idx_tuning_;
}

211 212
int FeatureOutput::Size() { return features_.feature_size(); }

213 214 215 216
int FeatureOutput::SizeOfDataForLearning() {
  return list_data_for_learning_.data_for_learning_size();
}

217 218 219 220
int FeatureOutput::SizeOfPredictionResult() {
  return list_prediction_result_.prediction_result_size();
}

221
int FeatureOutput::SizeOfFrameEnv() { return list_frame_env_.frame_env_size(); }
K
kechxu 已提交
222

223 224 225 226
int FeatureOutput::SizeOfDataForTuning() {
  return list_data_for_tuning_.data_for_tuning_size();
}

227 228
}  // namespace prediction
}  // namespace apollo