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

#include <prediction_component.h>

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

Public 成员函数

 ~PredictionComponent ()
 Destructor
 
std::string Name () const
 Get name of the node
 
bool Init () override
 Initialize the node
 
bool Proc (const std::shared_ptr< perception::PerceptionObstacles > &) override
 Data callback upon receiving a perception obstacle message.
 
void OfflineProcessFeatureProtoFile (const std::string &features_proto_file)
 Load and process feature proto file.
 
- Public 成员函数 继承自 apollo::cyber::Component< perception::PerceptionObstacles >
 Component ()
 
 ~Component () override
 
bool Initialize (const ComponentConfig &config) override
 init the component by protobuf object.
 
bool Process (const std::shared_ptr< perception::PerceptionObstacles > &msg0, const std::shared_ptr< NullType > &msg1, const std::shared_ptr< NullType > &msg2, const std::shared_ptr< NullType > &msg3)
 
- Public 成员函数 继承自 apollo::cyber::ComponentBase
virtual ~ComponentBase ()
 
virtual bool Initialize (const TimerComponentConfig &config)
 
virtual void Shutdown ()
 
template<typename T >
bool GetProtoConfig (T *config) const
 

额外继承的成员函数

- Public 类型 继承自 apollo::cyber::ComponentBase
template<typename M >
using Reader = cyber::Reader< M >
 
- Protected 成员函数 继承自 apollo::cyber::ComponentBase
virtual void Clear ()
 
const std::string & ConfigFilePath () const
 
void LoadConfigFiles (const ComponentConfig &config)
 
void LoadConfigFiles (const TimerComponentConfig &config)
 
- Protected 属性 继承自 apollo::cyber::ComponentBase
std::atomic< bool > is_shutdown_ = {false}
 
std::shared_ptr< Nodenode_ = nullptr
 
std::string config_file_path_ = ""
 
std::vector< std::shared_ptr< ReaderBase > > readers_
 

详细描述

在文件 prediction_component.h41 行定义.

构造及析构函数说明

◆ ~PredictionComponent()

apollo::prediction::PredictionComponent::~PredictionComponent ( )

Destructor

在文件 prediction_component.cc46 行定义.

46{}

成员函数说明

◆ Init()

bool apollo::prediction::PredictionComponent::Init ( )
overridevirtual

Initialize the node

返回
If initialized

实现了 apollo::cyber::ComponentBase.

在文件 prediction_component.cc71 行定义.

71 {
72 component_start_time_ = Clock::NowInSeconds();
73
74 container_manager_ = std::make_shared<ContainerManager>();
75 evaluator_manager_.reset(new EvaluatorManager());
76 predictor_manager_.reset(new PredictorManager());
77 scenario_manager_.reset(new ScenarioManager());
78
79 PredictionConf prediction_conf;
80 if (!ComponentBase::GetProtoConfig(&prediction_conf)) {
81 AERROR << "Unable to load prediction conf file: "
82 << ComponentBase::ConfigFilePath();
83 return false;
84 }
85 ADEBUG << "Prediction config file is loaded into: "
86 << prediction_conf.ShortDebugString();
87
88 if (!MessageProcess::Init(container_manager_.get(), evaluator_manager_.get(),
89 predictor_manager_.get(), prediction_conf)) {
90 return false;
91 }
92
93 planning_reader_ = node_->CreateReader<ADCTrajectory>(
94 prediction_conf.topic_conf().planning_trajectory_topic(), nullptr);
95
96 localization_reader_ =
97 node_->CreateReader<localization::LocalizationEstimate>(
98 prediction_conf.topic_conf().localization_topic(), nullptr);
99
100 storytelling_reader_ = node_->CreateReader<storytelling::Stories>(
101 prediction_conf.topic_conf().storytelling_topic(), nullptr);
102
103 prediction_writer_ = node_->CreateWriter<PredictionObstacles>(
104 prediction_conf.topic_conf().prediction_topic());
105
106 container_writer_ = node_->CreateWriter<SubmoduleOutput>(
107 prediction_conf.topic_conf().container_topic_name());
108
109 adc_container_writer_ = node_->CreateWriter<ADCTrajectoryContainer>(
110 prediction_conf.topic_conf().adccontainer_topic_name());
111
112 perception_obstacles_writer_ = node_->CreateWriter<PerceptionObstacles>(
113 prediction_conf.topic_conf().perception_obstacles_topic_name());
114
115 return true;
116}
static double NowInSeconds()
gets the current time in second.
Definition clock.cc:56
std::shared_ptr< Node > node_
static bool Init(ContainerManager *container_manager, EvaluatorManager *evaluator_manager, PredictorManager *predictor_manager, const PredictionConf &prediction_conf)
#define ADEBUG
Definition log.h:41
#define AERROR
Definition log.h:44

◆ Name()

std::string apollo::prediction::PredictionComponent::Name ( ) const

Get name of the node

返回
Name of the node

在文件 prediction_component.cc48 行定义.

48 {
49 return FLAGS_prediction_module_name;
50}

◆ OfflineProcessFeatureProtoFile()

void apollo::prediction::PredictionComponent::OfflineProcessFeatureProtoFile ( const std::string &  features_proto_file)

Load and process feature proto file.

参数
abin file including a sequence of feature proto.

在文件 prediction_component.cc52 行定义.

53 {
54 auto obstacles_container_ptr =
55 container_manager_->GetContainer<ObstaclesContainer>(
57 obstacles_container_ptr->Clear();
58 Features features;
59 apollo::cyber::common::GetProtoFromBinaryFile(features_proto_file_name,
60 &features);
61 for (const Feature& feature : features.feature()) {
62 obstacles_container_ptr->InsertFeatureProto(feature);
63 Obstacle* obstacle_ptr = obstacles_container_ptr->GetObstacle(feature.id());
64 if (!obstacle_ptr) {
65 continue;
66 }
67 evaluator_manager_->EvaluateObstacle(obstacle_ptr, obstacles_container_ptr);
68 }
69}
bool GetProtoFromBinaryFile(const std::string &file_name, google::protobuf::Message *message)
Parses the content of the file specified by the file_name as binary representation of protobufs,...
Definition file.cc:118

◆ Proc()

bool apollo::prediction::PredictionComponent::Proc ( const std::shared_ptr< perception::PerceptionObstacles > &  )
override

Data callback upon receiving a perception obstacle message.

参数
Perceptionobstacle message.

在文件 prediction_component.cc118 行定义.

119 {
120 if (FLAGS_use_lego) {
121 return ContainerSubmoduleProcess(perception_obstacles);
122 }
123 return PredictionEndToEndProc(perception_obstacles);
124}

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