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

#include <junction_map_evaluator.h>

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

Public 成员函数

 JunctionMapEvaluator ()=delete
 Constructor
 
 JunctionMapEvaluator (SemanticMap *semantic_map)
 
virtual ~JunctionMapEvaluator ()=default
 Destructor
 
void Clear ()
 Clear obstacle feature map
 
bool Evaluate (Obstacle *obstacle_ptr, ObstaclesContainer *obstacles_container) override
 Override Evaluate
 
bool ExtractFeatureValues (Obstacle *obstacle_ptr, 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_map_evaluator.h32 行定义.

构造及析构函数说明

◆ JunctionMapEvaluator() [1/2]

apollo::prediction::JunctionMapEvaluator::JunctionMapEvaluator ( )
delete

Constructor

◆ JunctionMapEvaluator() [2/2]

apollo::prediction::JunctionMapEvaluator::JunctionMapEvaluator ( SemanticMap semantic_map)
explicit

在文件 junction_map_evaluator.cc33 行定义.

34 : device_(torch::kCPU), semantic_map_(semantic_map) {
36 LoadModel();
37}
ObstacleConf::EvaluatorType evaluator_type_
Definition evaluator.h:156

◆ ~JunctionMapEvaluator()

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

Destructor

成员函数说明

◆ Clear()

void apollo::prediction::JunctionMapEvaluator::Clear ( )

Clear obstacle feature map

在文件 junction_map_evaluator.cc39 行定义.

39{}

◆ Evaluate()

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

Override Evaluate

参数
Obstaclepointer
Obstaclescontainer

实现了 apollo::prediction::Evaluator.

在文件 junction_map_evaluator.cc41 行定义.

42 {
43 // Sanity checks.
44 omp_set_num_threads(1);
45
46 obstacle_ptr->SetEvaluatorType(evaluator_type_);
47
48 Clear();
49 CHECK_NOTNULL(obstacle_ptr);
50 int id = obstacle_ptr->id();
51 if (!obstacle_ptr->latest_feature().IsInitialized()) {
52 AERROR << "Obstacle [" << id << "] has no latest feature.";
53 return false;
54 }
55 Feature* latest_feature_ptr = obstacle_ptr->mutable_latest_feature();
56 CHECK_NOTNULL(latest_feature_ptr);
57
58 // Assume obstacle is NOT closed to any junction exit
59 if (!latest_feature_ptr->has_junction_feature() ||
60 latest_feature_ptr->junction_feature().junction_exit_size() < 2) {
61 ADEBUG << "Obstacle [" << id << "] has less than two junction_exits.";
62 return false;
63 }
64 // Extract features of junction_exit_mask
65 std::vector<double> feature_values;
66 if (!ExtractFeatureValues(obstacle_ptr, &feature_values)) {
67 ADEBUG << "Obstacle [" << id << "] failed to extract junction exit mask";
68 return false;
69 }
70
71 if (!FLAGS_enable_semantic_map) {
72 ADEBUG << "Not enable semantic map, exit junction_map_evaluator.";
73 return false;
74 }
75 cv::Mat feature_map;
76 if (!semantic_map_->GetMapById(id, &feature_map)) {
77 return false;
78 }
79
80 // Build input features for torch
81 std::vector<torch::jit::IValue> torch_inputs;
82 // Process the feature_map
83 cv::cvtColor(feature_map, feature_map, cv::COLOR_BGR2RGB);
84 cv::Mat img_float;
85 feature_map.convertTo(img_float, CV_32F, 1.0 / 255);
86 torch::Tensor img_tensor = torch::from_blob(img_float.data, {1, 224, 224, 3});
87 img_tensor = img_tensor.permute({0, 3, 1, 2});
88 img_tensor[0][0] = img_tensor[0][0].sub(0.485).div(0.229);
89 img_tensor[0][1] = img_tensor[0][1].sub(0.456).div(0.224);
90 img_tensor[0][2] = img_tensor[0][2].sub(0.406).div(0.225);
91 // Process junction_exit_mask
92 torch::Tensor junction_exit_mask =
93 torch::zeros({1, static_cast<int>(feature_values.size())});
94 for (size_t i = 0; i < feature_values.size(); ++i) {
95 junction_exit_mask[0][i] = static_cast<float>(feature_values[i]);
96 }
97
98 torch_inputs.push_back(
99 c10::ivalue::Tuple::create({std::move(img_tensor.to(device_)),
100 std::move(junction_exit_mask.to(device_))}));
101
102 // Compute probability
103 std::vector<double> probability;
104 at::Tensor torch_output_tensor =
105 torch_model_.forward(torch_inputs).toTensor().to(torch::kCPU);
106 auto torch_output = torch_output_tensor.accessor<float, 2>();
107 for (int i = 0; i < torch_output.size(1); ++i) {
108 probability.push_back(static_cast<double>(torch_output[0][i]));
109 }
110
111 std::unordered_map<std::string, double> junction_exit_prob;
112 for (const JunctionExit& junction_exit :
113 latest_feature_ptr->junction_feature().junction_exit()) {
114 double x =
115 junction_exit.exit_position().x() - latest_feature_ptr->position().x();
116 double y =
117 junction_exit.exit_position().y() - latest_feature_ptr->position().y();
118 double angle =
119 std::atan2(y, x) - std::atan2(latest_feature_ptr->raw_velocity().y(),
120 latest_feature_ptr->raw_velocity().x());
121 double d_idx = (angle / (2.0 * M_PI) + 1.0 / 24.0) * 12.0;
122 int idx = static_cast<int>(floor(d_idx >= 0 ? d_idx : d_idx + 12));
123 junction_exit_prob[junction_exit.exit_lane_id()] = probability[idx];
124 }
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 for (int i = 0; i < lane_graph_ptr->lane_sequence_size(); ++i) {
135 LaneSequence* lane_sequence_ptr = lane_graph_ptr->mutable_lane_sequence(i);
136 CHECK_NOTNULL(lane_sequence_ptr);
137 for (const LaneSegment& lane_segment : lane_sequence_ptr->lane_segment()) {
138 if (junction_exit_prob.find(lane_segment.lane_id()) !=
139 junction_exit_prob.end()) {
140 lane_sequence_ptr->set_probability(
141 junction_exit_prob[lane_segment.lane_id()]);
142 }
143 }
144 }
145 return true;
146}
bool ExtractFeatureValues(Obstacle *obstacle_ptr, std::vector< double > *feature_values)
Extract feature vector
bool GetMapById(const int obstacle_id, cv::Mat *feature_map)
#define ADEBUG
Definition log.h:41
#define AERROR
Definition log.h:44

◆ ExtractFeatureValues()

bool apollo::prediction::JunctionMapEvaluator::ExtractFeatureValues ( Obstacle obstacle_ptr,
std::vector< double > *  feature_values 
)

Extract feature vector

参数
Obstaclepointer Feature container in a vector for receiving the feature values

在文件 junction_map_evaluator.cc148 行定义.

149 {
150 feature_values->clear();
151 feature_values->resize(JUNCTION_FEATURE_SIZE, 0.0);
152 Feature* feature_ptr = obstacle_ptr->mutable_latest_feature();
153 if (!feature_ptr->has_position()) {
154 ADEBUG << "Obstacle [" << obstacle_ptr->id() << "] has no position.";
155 return false;
156 }
157 double heading = std::atan2(feature_ptr->raw_velocity().y(),
158 feature_ptr->raw_velocity().x());
159 if (!feature_ptr->has_junction_feature()) {
160 AERROR << "Obstacle [" << obstacle_ptr->id()
161 << "] has no junction_feature.";
162 return false;
163 }
164
165 int num_junction_exit = feature_ptr->junction_feature().junction_exit_size();
166 for (int i = 0; i < num_junction_exit; ++i) {
167 const JunctionExit& junction_exit =
168 feature_ptr->junction_feature().junction_exit(i);
169 double x = junction_exit.exit_position().x() - feature_ptr->position().x();
170 double y = junction_exit.exit_position().y() - feature_ptr->position().y();
171 double diff_x = std::cos(-heading) * x - std::sin(-heading) * y;
172 double diff_y = std::sin(-heading) * x + std::cos(-heading) * y;
173 double angle = std::atan2(diff_y, diff_x);
174 double d_idx = (angle / (2.0 * M_PI) + 1.0 / 24.0) * 12.0;
175 int idx = static_cast<int>(floor(d_idx >= 0 ? d_idx : d_idx + 12));
176 feature_values->at(idx) = 1.0;
177 }
178 return true;
179}

◆ GetName()

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

Get the name of evaluator.

实现了 apollo::prediction::Evaluator.

在文件 junction_map_evaluator.h69 行定义.

69{ return "JUNCTION_MAP_EVALUATOR"; }

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