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

#include <velodyne_driver_component.h>

类 apollo::drivers::velodyne::VelodyneDriverComponent 继承关系图:
apollo::drivers::velodyne::VelodyneDriverComponent 的协作图:

Public 成员函数

 ~VelodyneDriverComponent ()
 
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_
 

详细描述

在文件 velodyne_driver_component.h37 行定义.

构造及析构函数说明

◆ ~VelodyneDriverComponent()

apollo::drivers::velodyne::VelodyneDriverComponent::~VelodyneDriverComponent ( )
inline

在文件 velodyne_driver_component.h39 行定义.

39{}

成员函数说明

◆ Init()

bool apollo::drivers::velodyne::VelodyneDriverComponent::Init ( )
overridevirtual

实现了 apollo::cyber::ComponentBase.

在文件 velodyne_driver_component.cc30 行定义.

30 {
31 AINFO << "Velodyne driver component init";
32 Config velodyne_config;
33 if (!GetProtoConfig(&velodyne_config)) {
34 return false;
35 }
36 AINFO << "Velodyne config: " << velodyne_config.DebugString();
37 // start the driver
38 std::shared_ptr<::apollo::cyber::Node> node =
39 apollo::cyber::CreateNode("lidar_drivers");
40 VelodyneDriver *driver =
41 VelodyneDriverFactory::CreateDriver(node, velodyne_config);
42 if (driver == nullptr) {
43 return false;
44 }
45 dvr_.reset(driver);
46 dvr_->Init();
47 // spawn device poll thread
48 runing_ = true;
49 return true;
50}
bool GetProtoConfig(T *config) const
static VelodyneDriver * CreateDriver(const std::shared_ptr<::apollo::cyber::Node > &node, const Config &config)
Definition driver.cc:232
#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

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