Apollo 10.0
自动驾驶开放平台
apollo::prediction::JunctionMLPEvaluator类 参考

#include <junction_mlp_evaluator.h>

类 apollo::prediction::JunctionMLPEvaluator 继承关系图:
apollo::prediction::JunctionMLPEvaluator 的协作图:

Public 成员函数

 JunctionMLPEvaluator ()
 Constructor
 
virtual ~JunctionMLPEvaluator ()=default
 Destructor
 
void Clear ()
 Clear obstacle feature map
 
bool Evaluate (Obstacle *obstacle_ptr, ObstaclesContainer *obstacles_container) override
 Override Evaluate
 
void ExtractFeatureValues (Obstacle *obstacle_ptr, ObstaclesContainer *obstacles_container, std::vector< double > *feature_values)
 Extract feature vector
 
std::string GetName () override
 Get the name of evaluator.
 
- Public 成员函数 继承自 apollo::prediction::Evaluator
 Evaluator ()=default
 Constructor
 
virtual ~Evaluator ()=default
 Destructor
 
virtual bool Evaluate (Obstacle *obstacle, ObstaclesContainer *obstacles_container, std::vector< Obstacle * > dynamic_env)
 Evaluate an obstacle
 
virtual bool Evaluate (const ADCTrajectoryContainer *adc_trajectory_container, Obstacle *obstacle, ObstaclesContainer *obstacles_container)
 Evaluate an obstacle
 

额外继承的成员函数

- Protected 成员函数 继承自 apollo::prediction::Evaluator
std::pair< double, double > WorldCoordToObjCoord (std::pair< double, double > input_world_coord, std::pair< double, double > obj_world_coord, double obj_world_angle)
 
std::pair< double, double > WorldCoordToObjCoordNorth (std::pair< double, double > input_world_coord, std::pair< double, double > obj_world_coord, double obj_world_angle)
 
double WorldAngleToObjAngle (double input_world_angle, double obj_world_angle)
 
Eigen::MatrixXf VectorToMatrixXf (const std::vector< double > &nums, const int start_index, const int end_index)
 
Eigen::MatrixXf VectorToMatrixXf (const std::vector< double > &nums, const int start_index, const int end_index, const int output_num_row, const int output_num_col)
 
- Protected 属性 继承自 apollo::prediction::Evaluator
ObstacleConf::EvaluatorType evaluator_type_
 

详细描述

在文件 junction_mlp_evaluator.h31 行定义.

构造及析构函数说明

◆ JunctionMLPEvaluator()

apollo::prediction::JunctionMLPEvaluator::JunctionMLPEvaluator ( )

Constructor

在文件 junction_mlp_evaluator.cc58 行定义.

58 : device_(torch::kCPU) {
60 LoadModel();
61}
ObstacleConf::EvaluatorType evaluator_type_
Definition evaluator.h:156

◆ ~JunctionMLPEvaluator()

virtual apollo::prediction::JunctionMLPEvaluator::~JunctionMLPEvaluator ( )
virtualdefault

Destructor

成员函数说明

◆ Clear()

void apollo::prediction::JunctionMLPEvaluator::Clear ( )

Clear obstacle feature map

在文件 junction_mlp_evaluator.cc63 行定义.

63{}

◆ Evaluate()

bool apollo::prediction::JunctionMLPEvaluator::Evaluate ( Obstacle obstacle_ptr,
ObstaclesContainer obstacles_container 
)
overridevirtual

Override Evaluate

参数
Obstaclepointer
Obstaclescontainer

实现了 apollo::prediction::Evaluator.

在文件 junction_mlp_evaluator.cc65 行定义.

66 {
67 // Sanity checks.
68 omp_set_num_threads(1);
69 Clear();
70 CHECK_NOTNULL(obstacle_ptr);
71
72 obstacle_ptr->SetEvaluatorType(evaluator_type_);
73
74 int id = obstacle_ptr->id();
75 if (!obstacle_ptr->latest_feature().IsInitialized()) {
76 AERROR << "Obstacle [" << id << "] has no latest feature.";
77 return false;
78 }
79 Feature* latest_feature_ptr = obstacle_ptr->mutable_latest_feature();
80 CHECK_NOTNULL(latest_feature_ptr);
81
82 // Assume obstacle is NOT closed to any junction exit
83 if (!latest_feature_ptr->has_junction_feature() ||
84 latest_feature_ptr->junction_feature().junction_exit_size() < 1) {
85 ADEBUG << "Obstacle [" << id << "] has no junction_exit.";
86 return false;
87 }
88
89 std::vector<double> feature_values;
90 ExtractFeatureValues(obstacle_ptr, obstacles_container, &feature_values);
91
92 // Insert features to DataForLearning
93 if (FLAGS_prediction_offline_mode ==
95 FeatureOutput::InsertDataForLearning(*latest_feature_ptr, feature_values,
96 "junction", nullptr);
97 ADEBUG << "Save extracted features for learning locally.";
98 return true; // Skip Compute probability for offline mode
99 }
100 std::vector<torch::jit::IValue> torch_inputs;
101 int input_dim = static_cast<int>(
102 OBSTACLE_FEATURE_SIZE + EGO_VEHICLE_FEATURE_SIZE + JUNCTION_FEATURE_SIZE);
103 torch::Tensor torch_input = torch::zeros({1, input_dim});
104 for (size_t i = 0; i < feature_values.size(); ++i) {
105 torch_input[0][i] = static_cast<float>(feature_values[i]);
106 }
107 torch_inputs.push_back(std::move(torch_input.to(device_)));
108 std::vector<double> probability;
109 if (latest_feature_ptr->junction_feature().junction_exit_size() > 1) {
110 at::Tensor torch_output_tensor =
111 torch_model_.forward(torch_inputs).toTensor().to(torch::kCPU);
112 auto torch_output = torch_output_tensor.accessor<float, 2>();
113 for (int i = 0; i < torch_output.size(1); ++i) {
114 probability.push_back(static_cast<double>(torch_output[0][i]));
115 }
116 } else {
117 for (int i = 0; i < 12; ++i) {
118 probability.push_back(feature_values[OBSTACLE_FEATURE_SIZE +
119 EGO_VEHICLE_FEATURE_SIZE + 8 * i]);
120 }
121 }
122 for (double prob : probability) {
123 latest_feature_ptr->mutable_junction_feature()
124 ->add_junction_mlp_probability(prob);
125 }
126 // assign all lane_sequence probability
127 LaneGraph* lane_graph_ptr =
128 latest_feature_ptr->mutable_lane()->mutable_lane_graph();
129 CHECK_NOTNULL(lane_graph_ptr);
130 if (lane_graph_ptr->lane_sequence().empty()) {
131 AERROR << "Obstacle [" << id << "] has no lane sequences.";
132 return false;
133 }
134
135 std::unordered_map<std::string, double> junction_exit_prob;
136 for (const JunctionExit& junction_exit :
137 latest_feature_ptr->junction_feature().junction_exit()) {
138 double x =
139 junction_exit.exit_position().x() - latest_feature_ptr->position().x();
140 double y =
141 junction_exit.exit_position().y() - latest_feature_ptr->position().y();
142 double angle =
143 std::atan2(y, x) - std::atan2(latest_feature_ptr->raw_velocity().y(),
144 latest_feature_ptr->raw_velocity().x());
145 double d_idx = (angle / (2.0 * M_PI) + 1.0 / 24.0) * 12.0;
146 int idx = static_cast<int>(floor(d_idx >= 0 ? d_idx : d_idx + 12));
147 junction_exit_prob[junction_exit.exit_lane_id()] = probability[idx];
148 }
149
150 for (int i = 0; i < lane_graph_ptr->lane_sequence_size(); ++i) {
151 LaneSequence* lane_sequence_ptr = lane_graph_ptr->mutable_lane_sequence(i);
152 CHECK_NOTNULL(lane_sequence_ptr);
153 for (const LaneSegment& lane_segment : lane_sequence_ptr->lane_segment()) {
154 if (junction_exit_prob.find(lane_segment.lane_id()) !=
155 junction_exit_prob.end()) {
156 lane_sequence_ptr->set_probability(
157 junction_exit_prob[lane_segment.lane_id()]);
158 }
159 }
160 }
161 return true;
162}
static void InsertDataForLearning(const Feature &feature, const std::vector< double > &feature_values, const std::string &category, const LaneSequence *lane_sequence_ptr)
Insert a data_for_learning
void ExtractFeatureValues(Obstacle *obstacle_ptr, ObstaclesContainer *obstacles_container, std::vector< double > *feature_values)
Extract feature vector
#define ADEBUG
Definition log.h:41
#define AERROR
Definition log.h:44

◆ ExtractFeatureValues()

void apollo::prediction::JunctionMLPEvaluator::ExtractFeatureValues ( Obstacle obstacle_ptr,
ObstaclesContainer obstacles_container,
std::vector< double > *  feature_values 
)

Extract feature vector

参数
Obstaclepointer
Obstaclescontainer
Featurecontainer in a vector for receiving the feature values

在文件 junction_mlp_evaluator.cc164 行定义.

166 {
167 CHECK_NOTNULL(obstacle_ptr);
168 int id = obstacle_ptr->id();
169
170 std::vector<double> obstacle_feature_values;
171 SetObstacleFeatureValues(obstacle_ptr, &obstacle_feature_values);
172
173 if (obstacle_feature_values.size() != OBSTACLE_FEATURE_SIZE) {
174 AERROR << "Obstacle [" << id << "] has fewer than "
175 << "expected obstacle feature_values "
176 << obstacle_feature_values.size() << ".";
177 return;
178 }
179
180 std::vector<double> ego_vehicle_feature_values;
181 SetEgoVehicleFeatureValues(obstacle_ptr, obstacles_container,
182 &ego_vehicle_feature_values);
183 if (ego_vehicle_feature_values.size() != EGO_VEHICLE_FEATURE_SIZE) {
184 AERROR << "Obstacle [" << id << "] has fewer than "
185 << "expected ego vehicle feature_values"
186 << ego_vehicle_feature_values.size() << ".";
187 return;
188 }
189
190 std::vector<double> junction_feature_values;
191 SetJunctionFeatureValues(obstacle_ptr, &junction_feature_values);
192 if (junction_feature_values.size() != JUNCTION_FEATURE_SIZE) {
193 AERROR << "Obstacle [" << id << "] has fewer than "
194 << "expected junction feature_values"
195 << junction_feature_values.size() << ".";
196 return;
197 }
198
199 feature_values->insert(feature_values->end(), obstacle_feature_values.begin(),
200 obstacle_feature_values.end());
201 feature_values->insert(feature_values->end(),
202 ego_vehicle_feature_values.begin(),
203 ego_vehicle_feature_values.end());
204 feature_values->insert(feature_values->end(), junction_feature_values.begin(),
205 junction_feature_values.end());
206}

◆ GetName()

std::string apollo::prediction::JunctionMLPEvaluator::GetName ( )
inlineoverridevirtual

Get the name of evaluator.

实现了 apollo::prediction::Evaluator.

在文件 junction_mlp_evaluator.h69 行定义.

69{ return "JUNCTION_MLP_EVALUATOR"; }

该类的文档由以下文件生成: