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

#include <lane_aggregating_evaluator.h>

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

Public 成员函数

 LaneAggregatingEvaluator ()
 Constructor
 
virtual ~LaneAggregatingEvaluator ()=default
 Destructor
 
bool Evaluate (Obstacle *obstacle_ptr, ObstaclesContainer *obstacles_container) override
 Override Evaluate
 
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_
 

详细描述

在文件 lane_aggregating_evaluator.h40 行定义.

构造及析构函数说明

◆ LaneAggregatingEvaluator()

apollo::prediction::LaneAggregatingEvaluator::LaneAggregatingEvaluator ( )

Constructor

在文件 lane_aggregating_evaluator.cc32 行定义.

32 : device_(torch::kCPU) {
34 LoadModel();
35}
ObstacleConf::EvaluatorType evaluator_type_
Definition evaluator.h:156

◆ ~LaneAggregatingEvaluator()

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

Destructor

成员函数说明

◆ Evaluate()

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

Override Evaluate

参数
Obstaclepointer
Obstaclescontainer

实现了 apollo::prediction::Evaluator.

在文件 lane_aggregating_evaluator.cc47 行定义.

48 {
49 // Sanity checks.
50 CHECK_NOTNULL(obstacle_ptr);
51
52 obstacle_ptr->SetEvaluatorType(evaluator_type_);
53
54 int id = obstacle_ptr->id();
55 if (!obstacle_ptr->latest_feature().IsInitialized()) {
56 AERROR << "Obstacle [" << id << "] has no latest feature.";
57 return false;
58 }
59 Feature* latest_feature_ptr = obstacle_ptr->mutable_latest_feature();
60 CHECK_NOTNULL(latest_feature_ptr);
61 if (!latest_feature_ptr->has_lane() ||
62 !latest_feature_ptr->lane().has_lane_graph_ordered()) {
63 AERROR << "Obstacle [" << id << "] has no lane graph.";
64 return false;
65 }
66 LaneGraph* lane_graph_ptr =
67 latest_feature_ptr->mutable_lane()->mutable_lane_graph_ordered();
68 CHECK_NOTNULL(lane_graph_ptr);
69 if (lane_graph_ptr->lane_sequence().empty()) {
70 AERROR << "Obstacle [" << id << "] has no lane sequences.";
71 return false;
72 }
73 ADEBUG << "There are " << lane_graph_ptr->lane_sequence_size()
74 << " lane sequences to scan.";
75
76 // Extract features, and do model inferencing.
77 // 1. Encode the obstacle features.
78 std::vector<double> obstacle_feature_values;
79 if (!ExtractObstacleFeatures(obstacle_ptr, &obstacle_feature_values)) {
80 ADEBUG << "Failed to extract obstacle features for obs_id = " << id;
81 }
82 if (obstacle_feature_values.size() != OBSTACLE_FEATURE_SIZE) {
83 ADEBUG << "Obstacle [" << id << "] has fewer than "
84 << "expected obstacle feature_values "
85 << obstacle_feature_values.size() << ".";
86 return false;
87 }
88 ADEBUG << "Obstacle feature size = " << obstacle_feature_values.size();
89 std::vector<torch::jit::IValue> obstacle_encoding_inputs;
90 torch::Tensor obstacle_encoding_inputs_tensor =
91 torch::zeros({1, static_cast<int>(obstacle_feature_values.size())});
92 for (size_t i = 0; i < obstacle_feature_values.size(); ++i) {
93 obstacle_encoding_inputs_tensor[0][i] =
94 static_cast<float>(obstacle_feature_values[i]);
95 }
96 obstacle_encoding_inputs.push_back(
97 std::move(obstacle_encoding_inputs_tensor));
98 torch::Tensor obstalce_encoding =
99 torch_obstacle_encoding_.forward(obstacle_encoding_inputs)
100 .toTensor()
101 .to(torch::kCPU);
102 // 2. Encode the lane features.
103 std::vector<std::vector<double>> lane_feature_values;
104 std::vector<int> lane_sequence_idx_to_remove;
105 if (!ExtractStaticEnvFeatures(obstacle_ptr, lane_graph_ptr,
106 &lane_feature_values,
107 &lane_sequence_idx_to_remove)) {
108 AERROR << "Failed to extract static environmental features around obs_id = "
109 << id;
110 }
111 std::vector<torch::Tensor> lane_encoding_list;
112 for (const auto& single_lane_feature_values : lane_feature_values) {
113 if (single_lane_feature_values.size() !=
114 SINGLE_LANE_FEATURE_SIZE *
115 (LANE_POINTS_SIZE + BACKWARD_LANE_POINTS_SIZE)) {
116 AERROR << "Obstacle [" << id << "] has incorrect lane feature size.";
117 return false;
118 }
119 std::vector<torch::jit::IValue> single_lane_encoding_inputs;
120 torch::Tensor single_lane_encoding_inputs_tensor =
121 torch::zeros({1, SINGLE_LANE_FEATURE_SIZE * LANE_POINTS_SIZE});
122 for (size_t i = 0; i < SINGLE_LANE_FEATURE_SIZE * LANE_POINTS_SIZE; ++i) {
123 single_lane_encoding_inputs_tensor[0][i] = static_cast<float>(
124 single_lane_feature_values[i + SINGLE_LANE_FEATURE_SIZE *
125 BACKWARD_LANE_POINTS_SIZE]);
126 }
127 single_lane_encoding_inputs.push_back(
128 std::move(single_lane_encoding_inputs_tensor));
129 torch::Tensor single_lane_encoding =
130 torch_lane_encoding_.forward(single_lane_encoding_inputs)
131 .toTensor()
132 .to(torch::kCPU);
133 lane_encoding_list.push_back(std::move(single_lane_encoding));
134 }
135 // 3. Aggregate the lane features.
136 // torch::Tensor aggregated_lane_encoding =
137 // AggregateLaneEncodings(lane_encoding_list);
138 // 4. Make prediction.
139 std::vector<double> prediction_scores;
140 for (size_t i = 0; i < lane_encoding_list.size(); ++i) {
141 std::vector<torch::jit::IValue> prediction_layer_inputs;
142 torch::Tensor prediction_layer_inputs_tensor = torch::zeros(
143 {1, OBSTACLE_ENCODING_SIZE + SINGLE_LANE_ENCODING_SIZE + 1});
144 for (size_t j = 0; j < OBSTACLE_ENCODING_SIZE; ++j) {
145 prediction_layer_inputs_tensor[0][j] = obstalce_encoding[0][j];
146 }
147 for (size_t j = 0; j + 1 < SINGLE_LANE_ENCODING_SIZE; ++j) {
148 prediction_layer_inputs_tensor[0][OBSTACLE_ENCODING_SIZE + j] =
149 lane_encoding_list[i][0][j];
150 }
151 prediction_layer_inputs_tensor[0][OBSTACLE_ENCODING_SIZE +
152 SINGLE_LANE_ENCODING_SIZE - 1] =
153 static_cast<float>(lane_feature_values[i][SINGLE_LANE_FEATURE_SIZE *
154 BACKWARD_LANE_POINTS_SIZE]);
155 prediction_layer_inputs_tensor[0][OBSTACLE_ENCODING_SIZE +
156 SINGLE_LANE_ENCODING_SIZE] = 0.0;
157 // for (size_t j = 0; j < AGGREGATED_ENCODING_SIZE; ++j) {
158 // prediction_layer_inputs_tensor[0][OBSTACLE_ENCODING_SIZE +
159 // SINGLE_LANE_ENCODING_SIZE + j] =
160 // aggregated_lane_encoding[0][j];
161 // }
162 prediction_layer_inputs.push_back(
163 std::move(prediction_layer_inputs_tensor));
164 torch::Tensor prediction_layer_output =
165 torch_prediction_layer_.forward(prediction_layer_inputs)
166 .toTensor()
167 .to(torch::kCPU);
168 auto prediction_score = prediction_layer_output.accessor<float, 2>();
169 prediction_scores.push_back(static_cast<double>(prediction_score[0][0]));
170 }
171
172 // Pass the predicted result to the predictor to plot trajectory.
173 std::vector<double> output_probabilities = StableSoftmax(prediction_scores);
174 for (int i = 0; i < lane_graph_ptr->lane_sequence_size(); ++i) {
175 lane_graph_ptr->mutable_lane_sequence(i)->set_probability(
176 output_probabilities[i]);
177 ADEBUG << output_probabilities[i];
178 }
179
180 *(latest_feature_ptr->mutable_lane()->mutable_lane_graph()) = *lane_graph_ptr;
181 return true;
182}
#define ADEBUG
Definition log.h:41
#define AERROR
Definition log.h:44

◆ GetName()

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

Get the name of evaluator.

实现了 apollo::prediction::Evaluator.

在文件 lane_aggregating_evaluator.h63 行定义.

63{ return "LANE_AGGREGATING_EVALUATOR"; }

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