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

#include <lidar_component_base_impl.h>

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

Public 成员函数

virtual ~LidarComponentBaseImpl ()=default
 
bool Init () override=0
 
virtual bool InitBase (const LidarConfigBase &lidar_config_base)=0
 
virtual void ReadScanCallback (const std::shared_ptr< ScanType > &scan_message)=0
 
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 成员函数

bool InitConverter (const LidarConfigBase &lidar_config_base)
 
bool InitPacket (const LidarConfigBase &lidar_config_base)
 
virtual bool WriteScan (const std::shared_ptr< ScanType > &scan_message)
 
virtual std::shared_ptr< PointCloudAllocatePointCloud ()
 
virtual bool WritePointCloud (const std::shared_ptr< PointCloud > &point_cloud)
 
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 成员函数

static void PcdDefaultCleaner (std::shared_ptr< PointCloud > &unused_pcd_frame)
 

Protected 属性

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_
 

额外继承的成员函数

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

详细描述

template<typename ScanType, typename ComponentType = apollo::cyber::NullType>
class apollo::drivers::lidar::LidarComponentBaseImpl< ScanType, ComponentType >

在文件 lidar_component_base_impl.h35 行定义.

构造及析构函数说明

◆ ~LidarComponentBaseImpl()

template<typename ScanType , typename ComponentType = apollo::cyber::NullType>
virtual apollo::drivers::lidar::LidarComponentBaseImpl< ScanType, ComponentType >::~LidarComponentBaseImpl ( )
virtualdefault

成员函数说明

◆ AcquireScanMessage()

template<typename ScanType , typename ComponentType >
std::shared_ptr< ScanType > apollo::drivers::lidar::LidarComponentBaseImpl< ScanType, ComponentType >::AcquireScanMessage ( )

在文件 lidar_component_base_impl.h118 行定义.

118 {
119 if (scan_writer_ == nullptr) {
120 return std::make_shared<ScanType>();
121 }
122 return scan_writer_->AcquireMessage();
123}

◆ AllocatePointCloud()

◆ GetPointQueue()

template<typename ScanType , typename ComponentType >
std::shared_ptr< apollo::cyber::base::ArenaQueue< PointXYZIT > > apollo::drivers::lidar::LidarComponentBaseImpl< ScanType, ComponentType >::GetPointQueue ( )
protectedvirtual

在文件 lidar_component_base_impl.h133 行定义.

133 {
134 std::shared_ptr<apollo::cyber::base::ArenaQueue<PointXYZIT>> ret;
135 auto channel_id = pcd_writer_->GetChannelId();
136
137 auto arena_manager =
138 apollo::cyber::transport::ProtobufArenaManager::Instance();
139 if (!arena_manager->Enable()) {
140 ADEBUG << "arena manager enable failed.";
141 } else {
143 arena_manager->RegisterQueue<apollo::drivers::PointXYZIT>(channel_id,
144 170000);
145 ret = std::shared_ptr<apollo::cyber::base::ArenaQueue<PointXYZIT>>(
146 reinterpret_cast<
148 arena_manager->GetAvailableBuffer(channel_id)),
150 }
151 return ret;
152}
#define ADEBUG
Definition log.h:41

◆ Init()

◆ InitBase()

◆ InitConverter()

template<typename ScanType , typename ComponentType >
bool apollo::drivers::lidar::LidarComponentBaseImpl< ScanType, ComponentType >::InitConverter ( const LidarConfigBase lidar_config_base)
protected

在文件 lidar_component_base_impl.h76 行定义.

77 {
78 pcd_writer_ = this->node_->template CreateWriter<PointCloud>(
79 lidar_config_base.point_cloud_channel());
80 RETURN_VAL_IF(pcd_writer_ == nullptr, false);
81
82 if (lidar_config_base.source_type() ==
83 LidarConfigBase_SourceType_RAW_PACKET) {
84 scan_reader_ = this->node_->template CreateReader<ScanType>(
85 lidar_config_base.scan_channel(),
87 std::placeholders::_1));
88 RETURN_VAL_IF(scan_reader_ == nullptr, false);
89 }
90
91 frame_id_ = lidar_config_base.frame_id();
92
93 // pcd_buffer_ = std::make_shared<SyncBuffering<PointCloud>>(
94 // [this](){
95 // return LidarComponentBaseImpl::PcdDefaultAllocator(
96 // this->pcd_writer_);
97 // },
98 // LidarComponentBaseImpl::PcdDefaultCleaner);
99 // pcd_buffer_->SetBufferSize(lidar_config_base.buffer_size());
100 // pcd_buffer_->Init();
101 return true;
102}
std::shared_ptr< Node > node_
virtual void ReadScanCallback(const std::shared_ptr< ScanType > &scan_message)=0
#define RETURN_VAL_IF(condition, val)
Definition log.h:114

◆ InitPacket()

template<typename ScanType , typename ComponentType >
bool apollo::drivers::lidar::LidarComponentBaseImpl< ScanType, ComponentType >::InitPacket ( const LidarConfigBase lidar_config_base)
protected

在文件 lidar_component_base_impl.h105 行定义.

106 {
107 if (lidar_config_base.source_type() ==
108 LidarConfigBase_SourceType_ONLINE_LIDAR) {
109 scan_writer_ = this->node_->template CreateWriter<ScanType>(
110 lidar_config_base.scan_channel());
111 RETURN_VAL_IF(scan_writer_ == nullptr, false);
112 }
113 return true;
114}

◆ PcdDefaultCleaner()

template<typename ScanType , typename ComponentType >
void apollo::drivers::lidar::LidarComponentBaseImpl< ScanType, ComponentType >::PcdDefaultCleaner ( std::shared_ptr< PointCloud > &  unused_pcd_frame)
staticprotected

在文件 lidar_component_base_impl.h186 行定义.

187 {
188 unused_pcd_frame->clear_point();
189}

◆ ReadScanCallback()

template<typename ScanType , typename ComponentType = apollo::cyber::NullType>
virtual void apollo::drivers::lidar::LidarComponentBaseImpl< ScanType, ComponentType >::ReadScanCallback ( const std::shared_ptr< ScanType > &  scan_message)
pure virtual

◆ WritePointCloud()

template<typename ScanType , typename ComponentType >
bool apollo::drivers::lidar::LidarComponentBaseImpl< ScanType, ComponentType >::WritePointCloud ( const std::shared_ptr< PointCloud > &  point_cloud)
protectedvirtual

apollo::drivers::lidar::LidarComponentBase< ScanType >, apollo::drivers::lidar::LidarComponentBase< HesaiUdpFrame >, apollo::drivers::lidar::LidarComponentBase< livox::LivoxScan >, apollo::drivers::lidar::LidarComponentBase< LslidarScan >, apollo::drivers::lidar::LidarComponentBase< robosense::RobosenseScanPacket >, apollo::drivers::lidar::LidarComponentBase< seyond::SeyondScan > , 以及 apollo::drivers::lidar::LidarComponentBase< vanjee::VanjeeScanPacket > 重载.

在文件 lidar_component_base_impl.h161 行定义.

162 {
163 point_cloud->mutable_header()->set_frame_id(frame_id_);
164 point_cloud->mutable_header()->set_sequence_num(
165 pcd_sequence_num_.fetch_add(1));
166 point_cloud->mutable_header()->set_timestamp_sec(
167 cyber::Time().Now().ToSecond());
168 RETURN_VAL_IF(!pcd_writer_->Write(point_cloud), false);
169 return true;
170}

◆ WriteScan()

template<typename ScanType , typename ComponentType >
bool apollo::drivers::lidar::LidarComponentBaseImpl< ScanType, ComponentType >::WriteScan ( const std::shared_ptr< ScanType > &  scan_message)
protectedvirtual

apollo::drivers::lidar::LidarComponentBase< ScanType > 重载.

在文件 lidar_component_base_impl.h126 行定义.

127 {
128 return scan_writer_->Write(scan_message);
129}

类成员变量说明

◆ frame_id_

template<typename ScanType , typename ComponentType = apollo::cyber::NullType>
std::string apollo::drivers::lidar::LidarComponentBaseImpl< ScanType, ComponentType >::frame_id_
protected

在文件 lidar_component_base_impl.h64 行定义.


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