16#ifndef APOLLO_LIDAR_COMPONENT_BASE_IMPL_H
17#define APOLLO_LIDAR_COMPONENT_BASE_IMPL_H
22#include "modules/common_msgs/sensor_msgs/pointcloud.pb.h"
23#include "modules/drivers/lidar/common/proto/lidar_config_base.pb.h"
34template <
typename ScanType,
typename ComponentType = apollo::cyber::NullType>
42 const std::shared_ptr<ScanType>& scan_message) = 0;
51 virtual bool WriteScan(
const std::shared_ptr<ScanType>& scan_message);
57 virtual std::shared_ptr<apollo::cyber::base::ArenaQueue<PointXYZIT>>
67 std::shared_ptr<cyber::Writer<ScanType>> scan_writer_ =
nullptr;
68 std::shared_ptr<cyber::Reader<ScanType>> scan_reader_ =
nullptr;
69 std::shared_ptr<cyber::Writer<PointCloud>> pcd_writer_ =
nullptr;
72 std::atomic<int> pcd_sequence_num_{0};
75template <
typename ScanType,
typename ComponentType>
78 pcd_writer_ = this->node_->template CreateWriter<PointCloud>(
83 LidarConfigBase_SourceType_RAW_PACKET) {
84 scan_reader_ = this->node_->template CreateReader<ScanType>(
87 std::placeholders::_1));
91 frame_id_ = lidar_config_base.
frame_id();
104template <
typename ScanType,
typename ComponentType>
108 LidarConfigBase_SourceType_ONLINE_LIDAR) {
109 scan_writer_ = this->node_->template CreateWriter<ScanType>(
116template <
typename ScanType,
typename ComponentType>
117std::shared_ptr<ScanType>
119 if (scan_writer_ ==
nullptr) {
120 return std::make_shared<ScanType>();
122 return scan_writer_->AcquireMessage();
125template <
typename ScanType,
typename ComponentType>
127 const std::shared_ptr<ScanType>& scan_message) {
128 return scan_writer_->Write(scan_message);
131template <
typename ScanType,
typename ComponentType>
132std::shared_ptr<apollo::cyber::base::ArenaQueue<PointXYZIT>>
134 std::shared_ptr<apollo::cyber::base::ArenaQueue<PointXYZIT>> ret;
135 auto channel_id = pcd_writer_->GetChannelId();
138 apollo::cyber::transport::ProtobufArenaManager::Instance();
139 if (!arena_manager->Enable()) {
140 ADEBUG <<
"arena manager enable failed.";
145 ret = std::shared_ptr<apollo::cyber::base::ArenaQueue<PointXYZIT>>(
148 arena_manager->GetAvailableBuffer(channel_id)),
154template <
typename ScanType,
typename ComponentType>
155std::shared_ptr<PointCloud>
157 return pcd_writer_->AcquireMessage();
160template <
typename ScanType,
typename ComponentType>
162 const std::shared_ptr<PointCloud>& point_cloud) {
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(
185template <
typename ScanType,
typename ComponentType>
187 std::shared_ptr<PointCloud>& unused_pcd_frame) {
188 unused_pcd_frame->clear_point();
Cyber has builtin time type Time.
virtual bool WritePointCloud(const std::shared_ptr< PointCloud > &point_cloud)
bool InitConverter(const LidarConfigBase &lidar_config_base)
virtual ~LidarComponentBaseImpl()=default
bool InitPacket(const LidarConfigBase &lidar_config_base)
virtual std::shared_ptr< apollo::cyber::base::ArenaQueue< PointXYZIT > > GetPointQueue()
virtual bool WriteScan(const std::shared_ptr< ScanType > &scan_message)
std::shared_ptr< ScanType > AcquireScanMessage()
static void PcdDefaultCleaner(std::shared_ptr< PointCloud > &unused_pcd_frame)
virtual std::shared_ptr< PointCloud > AllocatePointCloud()
virtual bool InitBase(const LidarConfigBase &lidar_config_base)=0
virtual void ReadScanCallback(const std::shared_ptr< ScanType > &scan_message)=0
#define RETURN_VAL_IF(condition, val)
required string scan_channel
required string point_cloud_channel
required SourceType source_type