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

#include <mlp_evaluator.h>

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

Public 成员函数

 MLPEvaluator ()
 Constructor
 
virtual ~MLPEvaluator ()=default
 Destructor
 
bool Evaluate (Obstacle *obstacle_ptr, ObstaclesContainer *obstacles_container) override
 Override Evaluate
 
void ExtractFeatureValues (Obstacle *obstacle_ptr, LaneSequence *lane_sequence_ptr, std::vector< double > *feature_values)
 Extract feature vector
 
std::string GetName () override
 Get the name of evaluator.
 
void Clear ()
 Clear obstacle feature map
 
- 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_
 

详细描述

在文件 mlp_evaluator.h30 行定义.

构造及析构函数说明

◆ MLPEvaluator()

apollo::prediction::MLPEvaluator::MLPEvaluator ( )

Constructor

在文件 mlp_evaluator.cc47 行定义.

47 {
49 LoadModel(FLAGS_evaluator_vehicle_mlp_file);
50}
ObstacleConf::EvaluatorType evaluator_type_
Definition evaluator.h:156

◆ ~MLPEvaluator()

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

Destructor

成员函数说明

◆ Clear()

void apollo::prediction::MLPEvaluator::Clear ( )

Clear obstacle feature map

在文件 mlp_evaluator.cc52 行定义.

52{}

◆ Evaluate()

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

Override Evaluate

参数
Obstaclepointer
Obstaclescontainer

实现了 apollo::prediction::Evaluator.

在文件 mlp_evaluator.cc54 行定义.

55 {
56 Clear();
57 CHECK_NOTNULL(obstacle_ptr);
58 CHECK_LE(LANE_FEATURE_SIZE, 4 * FLAGS_max_num_lane_point);
59
60 obstacle_ptr->SetEvaluatorType(evaluator_type_);
61
62 int id = obstacle_ptr->id();
63 if (!obstacle_ptr->latest_feature().IsInitialized()) {
64 AERROR << "Obstacle [" << id << "] has no latest feature.";
65 return false;
66 }
67
68 Feature* latest_feature_ptr = obstacle_ptr->mutable_latest_feature();
69 CHECK_NOTNULL(latest_feature_ptr);
70 if (!latest_feature_ptr->has_lane() ||
71 !latest_feature_ptr->lane().has_lane_graph()) {
72 ADEBUG << "Obstacle [" << id << "] has no lane graph.";
73 return false;
74 }
75
76 double speed = latest_feature_ptr->speed();
77
78 LaneGraph* lane_graph_ptr =
79 latest_feature_ptr->mutable_lane()->mutable_lane_graph();
80 CHECK_NOTNULL(lane_graph_ptr);
81 if (lane_graph_ptr->lane_sequence().empty()) {
82 AERROR << "Obstacle [" << id << "] has no lane sequences.";
83 return false;
84 }
85
86 std::vector<double> obstacle_feature_values;
87 SetObstacleFeatureValues(obstacle_ptr, &obstacle_feature_values);
88 if (obstacle_feature_values.size() != OBSTACLE_FEATURE_SIZE) {
89 ADEBUG << "Obstacle [" << id << "] has fewer than "
90 << "expected obstacle feature_values "
91 << obstacle_feature_values.size() << ".";
92 return false;
93 }
94
95 for (int i = 0; i < lane_graph_ptr->lane_sequence_size(); ++i) {
96 LaneSequence* lane_sequence_ptr = lane_graph_ptr->mutable_lane_sequence(i);
97 ACHECK(lane_sequence_ptr != nullptr);
98 std::vector<double> lane_feature_values;
99 SetLaneFeatureValues(obstacle_ptr, lane_sequence_ptr, &lane_feature_values);
100 if (lane_feature_values.size() != LANE_FEATURE_SIZE) {
101 ADEBUG << "Obstacle [" << id << "] has fewer than "
102 << "expected lane feature_values" << lane_feature_values.size()
103 << ".";
104 continue;
105 }
106
107 std::vector<double> feature_values;
108 feature_values.insert(feature_values.end(), obstacle_feature_values.begin(),
109 obstacle_feature_values.end());
110 feature_values.insert(feature_values.end(), lane_feature_values.begin(),
111 lane_feature_values.end());
112
113 // Insert features to DataForLearning
114 if (FLAGS_prediction_offline_mode ==
116 !obstacle_ptr->IsNearJunction()) {
117 FeatureOutput::InsertDataForLearning(*latest_feature_ptr, feature_values,
118 "mlp", lane_sequence_ptr);
119 ADEBUG << "Save extracted features for learning locally.";
120 return true; // Skip Compute probability for offline mode
121 }
122 double probability = ComputeProbability(feature_values);
123
124 double centripetal_acc_probability =
126 *lane_sequence_ptr, speed);
127 probability *= centripetal_acc_probability;
128 lane_sequence_ptr->set_probability(probability);
129 }
130 return true;
131}
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 Clear()
Clear obstacle feature map
static double ProbabilityByCentripetalAcceleration(const LaneSequence &lane_sequence, const double speed)
Compute the probability by centripetal acceleration
#define ACHECK(cond)
Definition log.h:80
#define ADEBUG
Definition log.h:41
#define AERROR
Definition log.h:44

◆ ExtractFeatureValues()

void apollo::prediction::MLPEvaluator::ExtractFeatureValues ( Obstacle obstacle_ptr,
LaneSequence lane_sequence_ptr,
std::vector< double > *  feature_values 
)

Extract feature vector

参数
Obstaclepointer Lane Sequence pointer

在文件 mlp_evaluator.cc133 行定义.

135 {
136 int id = obstacle_ptr->id();
137 std::vector<double> obstacle_feature_values;
138
139 SetObstacleFeatureValues(obstacle_ptr, &obstacle_feature_values);
140
141 if (obstacle_feature_values.size() != OBSTACLE_FEATURE_SIZE) {
142 ADEBUG << "Obstacle [" << id << "] has fewer than "
143 << "expected obstacle feature_values "
144 << obstacle_feature_values.size() << ".";
145 return;
146 }
147
148 std::vector<double> lane_feature_values;
149 SetLaneFeatureValues(obstacle_ptr, lane_sequence_ptr, &lane_feature_values);
150 if (lane_feature_values.size() != LANE_FEATURE_SIZE) {
151 ADEBUG << "Obstacle [" << id << "] has fewer than "
152 << "expected lane feature_values" << lane_feature_values.size()
153 << ".";
154 return;
155 }
156
157 feature_values->insert(feature_values->end(), obstacle_feature_values.begin(),
158 obstacle_feature_values.end());
159 feature_values->insert(feature_values->end(), lane_feature_values.begin(),
160 lane_feature_values.end());
161}

◆ GetName()

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

Get the name of evaluator.

实现了 apollo::prediction::Evaluator.

在文件 mlp_evaluator.h62 行定义.

62{ return "MLP_EVALUATOR"; }

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