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

#include <cruise_mlp_evaluator.h>

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

Public 成员函数

 CruiseMLPEvaluator ()
 Constructor
 
virtual ~CruiseMLPEvaluator ()=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 ()
 
- 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_
 

详细描述

在文件 cruise_mlp_evaluator.h32 行定义.

构造及析构函数说明

◆ CruiseMLPEvaluator()

apollo::prediction::CruiseMLPEvaluator::CruiseMLPEvaluator ( )

Constructor

在文件 cruise_mlp_evaluator.cc47 行定义.

47 : device_(torch::kCPU) {
49 LoadModels();
50}
ObstacleConf::EvaluatorType evaluator_type_
Definition evaluator.h:156

◆ ~CruiseMLPEvaluator()

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

Destructor

成员函数说明

◆ Clear()

void apollo::prediction::CruiseMLPEvaluator::Clear ( )

在文件 cruise_mlp_evaluator.cc52 行定义.

52{}

◆ Evaluate()

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

Override Evaluate

参数
Obstaclepointer
Obstaclescontainer

实现了 apollo::prediction::Evaluator.

在文件 cruise_mlp_evaluator.cc54 行定义.

55 {
56 // Sanity checks.
57 omp_set_num_threads(1);
58 Clear();
59 CHECK_NOTNULL(obstacle_ptr);
60
61 obstacle_ptr->SetEvaluatorType(evaluator_type_);
62
63 int id = obstacle_ptr->id();
64 if (!obstacle_ptr->latest_feature().IsInitialized()) {
65 AERROR << "Obstacle [" << id << "] has no latest feature.";
66 return false;
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 LaneGraph* lane_graph_ptr =
76 latest_feature_ptr->mutable_lane()->mutable_lane_graph();
77 CHECK_NOTNULL(lane_graph_ptr);
78 if (lane_graph_ptr->lane_sequence().empty()) {
79 AERROR << "Obstacle [" << id << "] has no lane sequences.";
80 return false;
81 }
82
83 ADEBUG << "There are " << lane_graph_ptr->lane_sequence_size()
84 << " lane sequences with probabilities:";
85 // For every possible lane sequence, extract features that are needed
86 // to feed into our trained model.
87 // Then compute the likelihood of the obstacle moving onto that laneseq.
88 for (int i = 0; i < lane_graph_ptr->lane_sequence_size(); ++i) {
89 LaneSequence* lane_sequence_ptr = lane_graph_ptr->mutable_lane_sequence(i);
90 CHECK_NOTNULL(lane_sequence_ptr);
91 std::vector<double> feature_values;
92 ExtractFeatureValues(obstacle_ptr, lane_sequence_ptr, &feature_values);
93 if (feature_values.size() !=
94 OBSTACLE_FEATURE_SIZE + SINGLE_LANE_FEATURE_SIZE * LANE_POINTS_SIZE) {
95 lane_sequence_ptr->set_probability(0.0);
96 ADEBUG << "Skip lane sequence due to incorrect feature size";
97 continue;
98 }
99
100 // Insert features to DataForLearning
101 if (FLAGS_prediction_offline_mode ==
103 std::vector<double> interaction_feature_values;
104 SetInteractionFeatureValues(obstacle_ptr, obstacles_container,
105 lane_sequence_ptr,
106 &interaction_feature_values);
107 if (interaction_feature_values.size() != INTERACTION_FEATURE_SIZE) {
108 ADEBUG << "Obstacle [" << id << "] has fewer than "
109 << "expected lane feature_values"
110 << interaction_feature_values.size() << ".";
111 return false;
112 }
113 ADEBUG << "Interaction feature size = "
114 << interaction_feature_values.size();
115 feature_values.insert(feature_values.end(),
116 interaction_feature_values.begin(),
117 interaction_feature_values.end());
118 FeatureOutput::InsertDataForLearning(*latest_feature_ptr, feature_values,
119 "lane_scanning", lane_sequence_ptr);
120 ADEBUG << "Save extracted features for learning locally.";
121 return true; // Skip Compute probability for offline mode
122 }
123
124 std::vector<torch::jit::IValue> torch_inputs;
125 int input_dim = static_cast<int>(
126 OBSTACLE_FEATURE_SIZE + SINGLE_LANE_FEATURE_SIZE * LANE_POINTS_SIZE);
127 torch::Tensor torch_input = torch::zeros({1, input_dim});
128 for (size_t i = 0; i < feature_values.size(); ++i) {
129 torch_input[0][i] = static_cast<float>(feature_values[i]);
130 }
131 torch_inputs.push_back(std::move(torch_input.to(device_)));
132 if (lane_sequence_ptr->vehicle_on_lane()) {
133 ModelInference(torch_inputs, torch_go_model_, lane_sequence_ptr);
134 } else {
135 ModelInference(torch_inputs, torch_cutin_model_, lane_sequence_ptr);
136 }
137 }
138 return true;
139}
void ExtractFeatureValues(Obstacle *obstacle_ptr, LaneSequence *lane_sequence_ptr, std::vector< double > *feature_values)
Extract feature vector
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
#define ADEBUG
Definition log.h:41
#define AERROR
Definition log.h:44

◆ ExtractFeatureValues()

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

Extract feature vector

参数
Obstaclepointer Lane Sequence pointer

在文件 cruise_mlp_evaluator.cc141 行定义.

143 {
144 // Sanity checks.
145 CHECK_NOTNULL(obstacle_ptr);
146 CHECK_NOTNULL(lane_sequence_ptr);
147 int id = obstacle_ptr->id();
148
149 // Extract obstacle related features.
150 std::vector<double> obstacle_feature_values;
151 SetObstacleFeatureValues(obstacle_ptr, &obstacle_feature_values);
152 if (obstacle_feature_values.size() != OBSTACLE_FEATURE_SIZE) {
153 ADEBUG << "Obstacle [" << id << "] has fewer than "
154 << "expected obstacle feature_values "
155 << obstacle_feature_values.size() << ".";
156 return;
157 }
158 ADEBUG << "Obstacle feature size = " << obstacle_feature_values.size();
159 feature_values->insert(feature_values->end(), obstacle_feature_values.begin(),
160 obstacle_feature_values.end());
161
162 // Extract lane related features.
163 std::vector<double> lane_feature_values;
164 SetLaneFeatureValues(obstacle_ptr, lane_sequence_ptr, &lane_feature_values);
165 if (lane_feature_values.size() !=
166 SINGLE_LANE_FEATURE_SIZE * LANE_POINTS_SIZE) {
167 ADEBUG << "Obstacle [" << id << "] has fewer than "
168 << "expected lane feature_values" << lane_feature_values.size()
169 << ".";
170 return;
171 }
172 ADEBUG << "Lane feature size = " << lane_feature_values.size();
173 feature_values->insert(feature_values->end(), lane_feature_values.begin(),
174 lane_feature_values.end());
175}

◆ GetName()

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

Get the name of evaluator.

实现了 apollo::prediction::Evaluator.

在文件 cruise_mlp_evaluator.h64 行定义.

64{ return "CRUISE_MLP_EVALUATOR"; }

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