Apollo 10.0
自动驾驶开放平台
apollo::drivers::lidar::LidarComponentBase< ScanType > 模板类 参考abstract

#include <lidar_component_base.h>

类 apollo::drivers::lidar::LidarComponentBase< ScanType > 继承关系图:
apollo::drivers::lidar::LidarComponentBase< ScanType > 的协作图:

Public 类型

using BaseComponent = LidarComponentBaseImpl< ScanType >
 
- Public 类型 继承自 apollo::cyber::ComponentBase
template<typename M >
using Reader = cyber::Reader< M >
 

Public 成员函数

virtual ~LidarComponentBase ()=default
 
virtual bool Init ()=0
 
virtual void ReadScanCallback (const std::shared_ptr< ScanType > &scan_message)=0
 
bool InitBase (const LidarConfigBase &lidar_config_base) override
 
bool WriteScan (const std::shared_ptr< ScanType > &scan_message)
 
std::shared_ptr< PointCloudAllocatePointCloud ()
 
bool WritePointCloud (const std::shared_ptr< PointCloud > &point_cloud)
 
- Public 成员函数 继承自 apollo::drivers::lidar::LidarComponentBaseImpl< ScanType, ComponentType >
virtual ~LidarComponentBaseImpl ()=default
 
std::shared_ptr< ScanType > AcquireScanMessage ()
 
- 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
 

额外继承的成员函数

- Protected 成员函数 继承自 apollo::drivers::lidar::LidarComponentBaseImpl< ScanType, ComponentType >
bool InitConverter (const LidarConfigBase &lidar_config_base)
 
bool InitPacket (const LidarConfigBase &lidar_config_base)
 
virtual std::shared_ptr< apollo::cyber::base::ArenaQueue< PointXYZIT > > GetPointQueue ()
 
- Protected 成员函数 继承自 apollo::cyber::ComponentBase
virtual void Clear ()
 
const std::string & ConfigFilePath () const
 
void LoadConfigFiles (const ComponentConfig &config)
 
void LoadConfigFiles (const TimerComponentConfig &config)
 
- 静态 Protected 成员函数 继承自 apollo::drivers::lidar::LidarComponentBaseImpl< ScanType, ComponentType >
static void PcdDefaultCleaner (std::shared_ptr< PointCloud > &unused_pcd_frame)
 
- Protected 属性 继承自 apollo::drivers::lidar::LidarComponentBaseImpl< ScanType, ComponentType >
std::string frame_id_
 
- 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_
 

详细描述

template<typename ScanType>
class apollo::drivers::lidar::LidarComponentBase< ScanType >

在文件 lidar_component_base.h26 行定义.

成员类型定义说明

◆ BaseComponent

template<typename ScanType >
using apollo::drivers::lidar::LidarComponentBase< ScanType >::BaseComponent = LidarComponentBaseImpl<ScanType>

在文件 lidar_component_base.h28 行定义.

构造及析构函数说明

◆ ~LidarComponentBase()

template<typename ScanType >
virtual apollo::drivers::lidar::LidarComponentBase< ScanType >::~LidarComponentBase ( )
virtualdefault

成员函数说明

◆ AllocatePointCloud()

template<typename ScanType >
std::shared_ptr< PointCloud > apollo::drivers::lidar::LidarComponentBase< ScanType >::AllocatePointCloud ( )
inlinevirtual

重载 apollo::drivers::lidar::LidarComponentBaseImpl< ScanType, ComponentType > .

在文件 lidar_component_base.h47 行定义.

47 {
48 return BaseComponent::AllocatePointCloud();
49 }

◆ Init()

◆ InitBase()

template<typename ScanType >
bool apollo::drivers::lidar::LidarComponentBase< ScanType >::InitBase ( const LidarConfigBase lidar_config_base)
inlineoverridevirtual

实现了 apollo::drivers::lidar::LidarComponentBaseImpl< ScanType, ComponentType >.

在文件 lidar_component_base.h37 行定义.

37 {
38 RETURN_VAL_IF(!this->InitPacket(lidar_config_base), false);
39 RETURN_VAL_IF(!this->InitConverter(lidar_config_base), false);
40 return true;
41 }
bool InitConverter(const LidarConfigBase &lidar_config_base)
bool InitPacket(const LidarConfigBase &lidar_config_base)
#define RETURN_VAL_IF(condition, val)
Definition log.h:114

◆ ReadScanCallback()

◆ WritePointCloud()

template<typename ScanType >
bool apollo::drivers::lidar::LidarComponentBase< ScanType >::WritePointCloud ( const std::shared_ptr< PointCloud > &  point_cloud)
inlinevirtual

重载 apollo::drivers::lidar::LidarComponentBaseImpl< ScanType, ComponentType > .

在文件 lidar_component_base.h51 行定义.

51 {
52 return BaseComponent::WritePointCloud(point_cloud);
53 }

◆ WriteScan()

template<typename ScanType >
bool apollo::drivers::lidar::LidarComponentBase< ScanType >::WriteScan ( const std::shared_ptr< ScanType > &  scan_message)
inlinevirtual

重载 apollo::drivers::lidar::LidarComponentBaseImpl< ScanType, ComponentType > .

在文件 lidar_component_base.h43 行定义.

43 {
44 return BaseComponent::WriteScan(scan_message);
45 }

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