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

#include <predictor_submodule.h>

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

Public 成员函数

 ~PredictorSubmodule ()=default
 Destructor
 
std::string Name () const
 Get name of the node
 
bool Init () override
 Initialize the node
 
bool Proc (const std::shared_ptr< apollo::perception::PerceptionObstacles > &, const std::shared_ptr< ADCTrajectoryContainer > &, const std::shared_ptr< SubmoduleOutput > &) override
 Data callback upon receiving a prediction evaluator output.
 
- Public 成员函数 继承自 apollo::cyber::Component< apollo::perception::PerceptionObstacles, ADCTrajectoryContainer, SubmoduleOutput >
 Component ()
 
 ~Component () override
 
bool Initialize (const ComponentConfig &config) override
 init the component by protobuf object.
 
bool Process (const std::shared_ptr< apollo::perception::PerceptionObstacles > &msg0, const std::shared_ptr< ADCTrajectoryContainer > &msg1, const std::shared_ptr< SubmoduleOutput > &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_
 

详细描述

在文件 predictor_submodule.h36 行定义.

构造及析构函数说明

◆ ~PredictorSubmodule()

apollo::prediction::PredictorSubmodule::~PredictorSubmodule ( )
default

Destructor

成员函数说明

◆ Init()

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

Initialize the node

返回
If initialized

实现了 apollo::cyber::ComponentBase.

在文件 predictor_submodule.cc37 行定义.

37 {
38 predictor_manager_.reset(new PredictorManager());
39
40 PredictionConf prediction_conf;
41 if (!ComponentBase::GetProtoConfig(&prediction_conf)) {
42 AERROR << "Unable to load prediction conf file: "
43 << ComponentBase::ConfigFilePath();
44 return false;
45 }
46 ADEBUG << "Prediction config file is loaded into: "
47 << prediction_conf.ShortDebugString();
48 if (!MessageProcess::InitPredictors(predictor_manager_.get(),
49 prediction_conf)) {
50 return false;
51 }
52 predictor_writer_ = node_->CreateWriter<PredictionObstacles>(
53 prediction_conf.topic_conf().prediction_topic());
54 return true;
55}
std::shared_ptr< Node > node_
static bool InitPredictors(PredictorManager *predictor_manager, const PredictionConf &prediction_conf)
#define ADEBUG
Definition log.h:41
#define AERROR
Definition log.h:44

◆ Name()

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

Get name of the node

返回
Name of the node

在文件 predictor_submodule.cc33 行定义.

33 {
34 return FLAGS_evaluator_submodule_name;
35}

◆ Proc()

bool apollo::prediction::PredictorSubmodule::Proc ( const std::shared_ptr< apollo::perception::PerceptionObstacles > &  ,
const std::shared_ptr< ADCTrajectoryContainer > &  ,
const std::shared_ptr< SubmoduleOutput > &   
)
override

Data callback upon receiving a prediction evaluator output.

参数
Predictionadc trajectory container.
Predictionevaluator output.

在文件 predictor_submodule.cc57 行定义.

60 {
61 const apollo::common::Header& perception_header =
62 perception_obstacles->header();
63 const apollo::common::ErrorCode& perception_error_code =
64 perception_obstacles->error_code();
65 const apollo::cyber::Time& frame_start_time =
66 submodule_output->frame_start_time();
67 ObstaclesContainer obstacles_container(*submodule_output);
68 predictor_manager_->Run(*perception_obstacles, adc_trajectory_container.get(),
69 &obstacles_container);
70 PredictionObstacles prediction_obstacles =
71 predictor_manager_->prediction_obstacles();
72
73 prediction_obstacles.set_end_timestamp(Clock::NowInSeconds());
74 prediction_obstacles.mutable_header()->set_lidar_timestamp(
75 perception_header.lidar_timestamp());
76 prediction_obstacles.mutable_header()->set_camera_timestamp(
77 perception_header.camera_timestamp());
78 prediction_obstacles.mutable_header()->set_radar_timestamp(
79 perception_header.radar_timestamp());
80 prediction_obstacles.set_perception_error_code(perception_error_code);
81
82 common::util::FillHeader(node_->Name(), &prediction_obstacles);
83 predictor_writer_->Write(prediction_obstacles);
84
85 const apollo::cyber::Time& end_time = Clock::Now();
86 ADEBUG << "End to end time = "
87 << (end_time - frame_start_time).ToSecond() * 1000 << " ms";
88
89 return true;
90}
static double NowInSeconds()
gets the current time in second.
Definition clock.cc:56
static Time Now()
PRECISION >= 1000000 means the precision is at least 1us.
Definition clock.cc:40
Cyber has builtin time type Time.
Definition time.h:31
optional uint64 camera_timestamp
Definition header.proto:22
optional uint64 lidar_timestamp
Definition header.proto:19
optional uint64 radar_timestamp
Definition header.proto:25

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