Apollo 10.0
自动驾驶开放平台
apollo::drivers::lidar::LidarDriverComponent类 参考

#include <lidar_driver_component.h>

类 apollo::drivers::lidar::LidarDriverComponent 继承关系图:
apollo::drivers::lidar::LidarDriverComponent 的协作图:

Public 成员函数

 LidarDriverComponent ()
 
 ~LidarDriverComponent ()
 
bool Init () override
 
- Public 成员函数 继承自 apollo::cyber::Component< M0, M1, M2, M3 >
 Component ()
 
 ~Component () override
 
bool Initialize (const ComponentConfig &config) override
 init the component by protobuf object.
 
bool Process (const std::shared_ptr< M0 > &msg0, const std::shared_ptr< M1 > &msg1, const std::shared_ptr< M2 > &msg2, const std::shared_ptr< M3 > &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_
 

详细描述

在文件 lidar_driver_component.h30 行定义.

构造及析构函数说明

◆ LidarDriverComponent()

apollo::drivers::lidar::LidarDriverComponent::LidarDriverComponent ( )

在文件 lidar_driver_component.cc24 行定义.

24{}

◆ ~LidarDriverComponent()

apollo::drivers::lidar::LidarDriverComponent::~LidarDriverComponent ( )
inline

在文件 lidar_driver_component.h33 行定义.

33{}

成员函数说明

◆ Init()

bool apollo::drivers::lidar::LidarDriverComponent::Init ( )
overridevirtual

实现了 apollo::cyber::ComponentBase.

在文件 lidar_driver_component.cc25 行定义.

25 {
26 if (!GetProtoConfig(&conf_)) {
27 AERROR << "load config error, file:" << config_file_path_;
28 return false;
29 }
30 node_ = apollo::cyber::CreateNode("drivers_lidar");
31 AINFO << "conf:" << conf_.DebugString();
32 LidarDriverFactory::Instance()->RegisterLidarClients();
33 driver_ = LidarDriverFactory::Instance()->CreateLidarDriver(node_, conf_);
34 if (driver_ == nullptr || !driver_->Init()) {
35 AERROR << "driver init error";
36 return false;
37 }
38 return true;
39}
bool GetProtoConfig(T *config) const
#define AERROR
Definition log.h:44
#define AINFO
Definition log.h:42
std::unique_ptr< Node > CreateNode(const std::string &node_name, const std::string &name_space)
Definition cyber.cc:33

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