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

#include <lane_scanning_evaluator.h>

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

Public 成员函数

 LaneScanningEvaluator ()
 Constructor
 
virtual ~LaneScanningEvaluator ()=default
 Destructor
 
bool Evaluate (Obstacle *obstacle_ptr, ObstaclesContainer *obstacles_container) override
 Override Evaluate
 
bool Evaluate (Obstacle *obstacle_ptr, ObstaclesContainer *obstacles_container, std::vector< Obstacle * > dynamic_env) override
 Override Evaluate
 
bool ExtractFeatures (const Obstacle *obstacle_ptr, const LaneGraph *lane_graph_ptr, std::vector< double > *feature_values)
 Extract features for learning model's input
 
bool ExtractStringFeatures (const LaneGraph &lane_graph, std::vector< std::string > *const string_feature_values)
 
std::string GetName () override
 Get the name of evaluator.
 
- Public 成员函数 继承自 apollo::prediction::Evaluator
 Evaluator ()=default
 Constructor
 
virtual ~Evaluator ()=default
 Destructor
 
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_scanning_evaluator.h31 行定义.

构造及析构函数说明

◆ LaneScanningEvaluator()

apollo::prediction::LaneScanningEvaluator::LaneScanningEvaluator ( )

Constructor

在文件 lane_scanning_evaluator.cc39 行定义.

39 : device_(torch::kCPU) {
41 LoadModel();
42}
ObstacleConf::EvaluatorType evaluator_type_
Definition evaluator.h:156

◆ ~LaneScanningEvaluator()

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

Destructor

成员函数说明

◆ Evaluate() [1/2]

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

Override Evaluate

参数
Obstaclepointer
Obstaclescontainer

实现了 apollo::prediction::Evaluator.

在文件 lane_scanning_evaluator.cc44 行定义.

45 {
46 std::vector<Obstacle*> dummy_dynamic_env;
47 Evaluate(obstacle_ptr, obstacles_container, dummy_dynamic_env);
48 return true;
49}
bool Evaluate(Obstacle *obstacle_ptr, ObstaclesContainer *obstacles_container) override
Override Evaluate

◆ Evaluate() [2/2]

bool apollo::prediction::LaneScanningEvaluator::Evaluate ( Obstacle obstacle_ptr,
ObstaclesContainer obstacles_container,
std::vector< Obstacle * >  dynamic_env 
)
overridevirtual

Override Evaluate

参数
Obstaclepointer
Obstaclescontainer
vectorof all Obstacles

重载 apollo::prediction::Evaluator .

在文件 lane_scanning_evaluator.cc51 行定义.

53 {
54 // Sanity checks.
55 omp_set_num_threads(1);
56 CHECK_NOTNULL(obstacle_ptr);
57
58 obstacle_ptr->SetEvaluatorType(evaluator_type_);
59
60 int id = obstacle_ptr->id();
61 if (!obstacle_ptr->latest_feature().IsInitialized()) {
62 AERROR << "Obstacle [" << id << "] has no latest feature.";
63 return false;
64 }
65 Feature* latest_feature_ptr = obstacle_ptr->mutable_latest_feature();
66 CHECK_NOTNULL(latest_feature_ptr);
67 if (!latest_feature_ptr->has_lane() ||
68 !latest_feature_ptr->lane().has_lane_graph_ordered()) {
69 AERROR << "Obstacle [" << id << "] has no lane graph.";
70 return false;
71 }
72 LaneGraph* lane_graph_ptr =
73 latest_feature_ptr->mutable_lane()->mutable_lane_graph_ordered();
74 CHECK_NOTNULL(lane_graph_ptr);
75 if (lane_graph_ptr->lane_sequence().empty()) {
76 AERROR << "Obstacle [" << id << "] has no lane sequences.";
77 return false;
78 }
79 ADEBUG << "There are " << lane_graph_ptr->lane_sequence_size()
80 << " lane sequences to scan.";
81
82 // Extract features, and:
83 // - if in offline mode, save it locally for training.
84 // - if in online mode, pass it through trained model to evaluate.
85 std::vector<double> feature_values;
86 ExtractFeatures(obstacle_ptr, lane_graph_ptr, &feature_values);
87 std::vector<std::string> string_feature_values;
88 ExtractStringFeatures(*lane_graph_ptr, &string_feature_values);
89
90 std::vector<double> labels = {0.0};
91 if (FLAGS_prediction_offline_mode ==
93 std::string learning_data_tag = "vehicle_cruise";
94 if (latest_feature_ptr->has_junction_feature()) {
95 learning_data_tag = "vehicle_junction";
96 }
97 FeatureOutput::InsertDataForLearning(*latest_feature_ptr, feature_values,
98 string_feature_values,
99 learning_data_tag, nullptr);
100 ADEBUG << "Save extracted features for learning locally.";
101 return true;
102 }
103
104 feature_values.push_back(static_cast<double>(MAX_NUM_LANE));
105
106 std::vector<torch::jit::IValue> torch_inputs;
107 torch::Tensor torch_input =
108 torch::zeros({1, static_cast<int>(feature_values.size())});
109 for (size_t i = 0; i < feature_values.size(); ++i) {
110 torch_input[0][i] = static_cast<float>(feature_values[i]);
111 }
112 torch_inputs.push_back(std::move(torch_input));
113 ModelInference(torch_inputs, torch_lane_scanning_model_, latest_feature_ptr);
114 return true;
115}
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
bool ExtractFeatures(const Obstacle *obstacle_ptr, const LaneGraph *lane_graph_ptr, std::vector< double > *feature_values)
Extract features for learning model's input
bool ExtractStringFeatures(const LaneGraph &lane_graph, std::vector< std::string > *const string_feature_values)
#define ADEBUG
Definition log.h:41
#define AERROR
Definition log.h:44

◆ ExtractFeatures()

bool apollo::prediction::LaneScanningEvaluator::ExtractFeatures ( const Obstacle obstacle_ptr,
const LaneGraph lane_graph_ptr,
std::vector< double > *  feature_values 
)

Extract features for learning model's input

参数
Obstaclepointer
LaneGraph pointer
Tobe filled up with extracted features

在文件 lane_scanning_evaluator.cc130 行定义.

132 {
133 // Sanity checks.
134 CHECK_NOTNULL(obstacle_ptr);
135 int id = obstacle_ptr->id();
136 CHECK_NOTNULL(lane_graph_ptr);
137
138 // Extract obstacle related features.
139 std::vector<double> obstacle_feature_values;
140 if (!ExtractObstacleFeatures(obstacle_ptr, &obstacle_feature_values)) {
141 ADEBUG << "Failed to extract obstacle features for obs_id = " << id;
142 }
143 if (obstacle_feature_values.size() != OBSTACLE_FEATURE_SIZE) {
144 ADEBUG << "Obstacle [" << id << "] has fewer than "
145 << "expected obstacle feature_values "
146 << obstacle_feature_values.size() << ".";
147 return false;
148 }
149 ADEBUG << "Obstacle feature size = " << obstacle_feature_values.size();
150 feature_values->insert(feature_values->end(), obstacle_feature_values.begin(),
151 obstacle_feature_values.end());
152
153 // Extract static environmental (lane-related) features.
154 std::vector<double> static_feature_values;
155 std::vector<int> lane_sequence_idx_to_remove;
156 if (!ExtractStaticEnvFeatures(obstacle_ptr, lane_graph_ptr,
157 &static_feature_values,
158 &lane_sequence_idx_to_remove)) {
159 AERROR << "Failed to extract static environmental features around obs_id = "
160 << id;
161 }
162 if (static_feature_values.size() %
163 (SINGLE_LANE_FEATURE_SIZE *
164 (LANE_POINTS_SIZE + BACKWARD_LANE_POINTS_SIZE)) !=
165 0) {
166 AERROR << "Obstacle [" << id << "] has incorrect static env feature size: "
167 << static_feature_values.size() << ".";
168 return false;
169 }
170 feature_values->insert(feature_values->end(), static_feature_values.begin(),
171 static_feature_values.end());
172
173 return true;
174}

◆ ExtractStringFeatures()

bool apollo::prediction::LaneScanningEvaluator::ExtractStringFeatures ( const LaneGraph lane_graph,
std::vector< std::string > *const  string_feature_values 
)

在文件 lane_scanning_evaluator.cc117 行定义.

119 {
120 for (const LaneSequence& lane_sequence : lane_graph.lane_sequence()) {
121 string_feature_values->push_back("|");
122 for (int i = lane_sequence.adc_lane_segment_idx();
123 i < static_cast<int>(lane_sequence.lane_segment_size()); ++i) {
124 string_feature_values->push_back(lane_sequence.lane_segment(i).lane_id());
125 }
126 }
127 return true;
128}

◆ GetName()

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

Get the name of evaluator.

实现了 apollo::prediction::Evaluator.

在文件 lane_scanning_evaluator.h77 行定义.

77{ return "LANE_SCANNING_EVALUATOR"; }

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