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

#include <predictor_manager.h>

apollo::prediction::PredictorManager 的协作图:

Public 成员函数

 PredictorManager ()
 Constructor
 
virtual ~PredictorManager ()=default
 Destructor
 
void Init (const PredictionConf &config)
 Initializer
 
PredictorGetPredictor (const ObstacleConf::PredictorType &type)
 Get predictor
 
void Run (const apollo::perception::PerceptionObstacles &perception_obstacles, const ADCTrajectoryContainer *adc_trajectory_container, ObstaclesContainer *obstacles_container)
 Execute the predictor generation
 
void PredictObstacle (const ADCTrajectoryContainer *adc_trajectory_container, Obstacle *obstacle, ObstaclesContainer *obstacles_container, PredictionObstacle *const prediction_obstacle)
 Predict a single obstacle
 
const PredictionObstaclesprediction_obstacles ()
 Get prediction obstacles
 

详细描述

在文件 predictor_manager.h38 行定义.

构造及析构函数说明

◆ PredictorManager()

apollo::prediction::PredictorManager::PredictorManager ( )

Constructor

在文件 predictor_manager.cc60 行定义.

60{ RegisterPredictors(); }

◆ ~PredictorManager()

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

Destructor

成员函数说明

◆ GetPredictor()

Predictor * apollo::prediction::PredictorManager::GetPredictor ( const ObstacleConf::PredictorType type)

Get predictor

返回
Pointer to the predictor

在文件 predictor_manager.cc124 行定义.

125 {
126 auto it = predictors_.find(type);
127 return it != predictors_.end() ? it->second.get() : nullptr;
128}

◆ Init()

void apollo::prediction::PredictorManager::Init ( const PredictionConf config)

Initializer

参数
Predictionconfig

在文件 predictor_manager.cc73 行定义.

73 {
74 for (const auto& conf : config.obstacle_conf()) {
75 if (!conf.has_obstacle_type()) {
76 AERROR << "Obstacle config [" << conf.ShortDebugString()
77 << "] has not defined obstacle type.";
78 continue;
79 }
80
81 if (!conf.has_predictor_type()) {
82 AERROR << "Obstacle config [" << conf.ShortDebugString()
83 << "] has not defined predictor type.";
84 continue;
85 }
86
87 switch (conf.obstacle_type()) {
89 InitVehiclePredictors(conf);
90 break;
91 }
93 InitCyclistPredictors(conf);
94 break;
95 }
97 pedestrian_predictor_ = conf.predictor_type();
98 break;
99 }
101 InitDefaultPredictors(conf);
102 break;
103 }
104 default: { break; }
105 }
106 }
107
108 AINFO << "Defined vehicle on lane obstacle predictor ["
109 << vehicle_on_lane_predictor_ << "].";
110 AINFO << "Defined vehicle off lane obstacle predictor ["
111 << vehicle_off_lane_predictor_ << "].";
112 AINFO << "Defined bicycle on lane obstacle predictor ["
113 << cyclist_on_lane_predictor_ << "].";
114 AINFO << "Defined bicycle off lane obstacle predictor ["
115 << cyclist_off_lane_predictor_ << "].";
116 AINFO << "Defined pedestrian obstacle predictor [" << pedestrian_predictor_
117 << "].";
118 AINFO << "Defined default on lane obstacle predictor ["
119 << default_on_lane_predictor_ << "].";
120 AINFO << "Defined default off lane obstacle predictor ["
121 << default_off_lane_predictor_ << "].";
122}
#define AERROR
Definition log.h:44
#define AINFO
Definition log.h:42

◆ prediction_obstacles()

const PredictionObstacles & apollo::prediction::PredictorManager::prediction_obstacles ( )

Get prediction obstacles

返回
Prediction obstacles

在文件 predictor_manager.cc347 行定义.

347 {
348 return prediction_obstacles_;
349}

◆ PredictObstacle()

void apollo::prediction::PredictorManager::PredictObstacle ( const ADCTrajectoryContainer adc_trajectory_container,
Obstacle obstacle,
ObstaclesContainer obstacles_container,
PredictionObstacle *const  prediction_obstacle 
)

Predict a single obstacle

参数
Apointer to adc_trajectory_container
Apointer to the specific obstacle
Apointer to the obstacles container
Apointer to prediction_obstacle

在文件 predictor_manager.cc232 行定义.

235 {
236 CHECK_NOTNULL(obstacle);
237 prediction_obstacle->set_timestamp(obstacle->timestamp());
238
239 if (obstacle->ToIgnore()) {
240 ADEBUG << "Ignore obstacle [" << obstacle->id() << "]";
241 RunEmptyPredictor(adc_trajectory_container, obstacle, obstacles_container);
242 prediction_obstacle->mutable_priority()->set_priority(
244 } else if (obstacle->IsStill()) {
245 ADEBUG << "Still obstacle [" << obstacle->id() << "]";
246 RunEmptyPredictor(adc_trajectory_container, obstacle, obstacles_container);
247 } else {
248 switch (obstacle->type()) {
250 if (FLAGS_enable_multi_agent_vehicle_evaluator) {
251 RunEmptyPredictor(adc_trajectory_container, obstacle,
252 obstacles_container);
253 } else {
254 RunVehiclePredictor(adc_trajectory_container, obstacle,
255 obstacles_container);
256 }
257 break;
258 }
260 if (FLAGS_enable_multi_agent_pedestrian_evaluator) {
261 RunEmptyPredictor(adc_trajectory_container, obstacle,
262 obstacles_container);
263 } else {
264 RunPedestrianPredictor(adc_trajectory_container, obstacle,
265 obstacles_container);
266 }
267 break;
268 }
270 RunCyclistPredictor(adc_trajectory_container, obstacle,
271 obstacles_container);
272 break;
273 }
274 default: {
275 RunDefaultPredictor(adc_trajectory_container, obstacle,
276 obstacles_container);
277 break;
278 }
279 }
280 }
281
282 for (const auto& trajectory :
283 obstacle->latest_feature().predicted_trajectory()) {
284 prediction_obstacle->add_trajectory()->CopyFrom(trajectory);
285 }
286 prediction_obstacle->set_timestamp(obstacle->timestamp());
287 prediction_obstacle->mutable_priority()->CopyFrom(
288 obstacle->latest_feature().priority());
289 prediction_obstacle->mutable_interactive_tag()->CopyFrom(
290 obstacle->latest_feature().interactive_tag());
291 prediction_obstacle->set_is_static(obstacle->IsStill());
292 if (FLAGS_prediction_offline_mode ==
294 const Scenario& scenario = obstacles_container->curr_scenario();
295 FeatureOutput::InsertPredictionResult(obstacle, *prediction_obstacle,
296 obstacle->obstacle_conf(), scenario);
297 }
298}
static void InsertPredictionResult(const Obstacle *obstacle, const PredictionObstacle &prediction_obstacle, const ObstacleConf &obstacle_conf, const Scenario &scenario)
Insert a prediction result with predicted trajectories
#define ADEBUG
Definition log.h:41

◆ Run()

void apollo::prediction::PredictorManager::Run ( const apollo::perception::PerceptionObstacles perception_obstacles,
const ADCTrajectoryContainer adc_trajectory_container,
ObstaclesContainer obstacles_container 
)

Execute the predictor generation

参数
Adctrajectory container
Obstaclescontainer

在文件 predictor_manager.cc130 行定义.

133 {
134 prediction_obstacles_.Clear();
135
136 if (FLAGS_enable_multi_thread) {
137 PredictObstaclesInParallel(perception_obstacles, adc_trajectory_container,
138 obstacles_container);
139 } else {
140 PredictObstacles(perception_obstacles, adc_trajectory_container,
141 obstacles_container);
142 }
143}

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