Apollo 10.0
自动驾驶开放平台
lidar_component_base_impl.h
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2024 The Apollo Authors. All Rights Reserved.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *****************************************************************************/
16#ifndef APOLLO_LIDAR_COMPONENT_BASE_IMPL_H
17#define APOLLO_LIDAR_COMPONENT_BASE_IMPL_H
18
19#include <memory>
20#include <string>
21
22#include "modules/common_msgs/sensor_msgs/pointcloud.pb.h"
23#include "modules/drivers/lidar/common/proto/lidar_config_base.pb.h"
24
26#include "cyber/cyber.h"
29
30namespace apollo {
31namespace drivers {
32namespace lidar {
33
34template <typename ScanType, typename ComponentType = apollo::cyber::NullType>
35class LidarComponentBaseImpl : public apollo::cyber::Component<ComponentType> {
36 public:
37 virtual ~LidarComponentBaseImpl() = default;
38
39 bool Init() override = 0;
40 virtual bool InitBase(const LidarConfigBase& lidar_config_base) = 0;
41 virtual void ReadScanCallback(
42 const std::shared_ptr<ScanType>& scan_message) = 0;
43
44 std::shared_ptr<ScanType> AcquireScanMessage();
45
46 protected:
47 bool InitConverter(const LidarConfigBase& lidar_config_base);
48
49 bool InitPacket(const LidarConfigBase& lidar_config_base);
50
51 virtual bool WriteScan(const std::shared_ptr<ScanType>& scan_message);
52
53 virtual std::shared_ptr<PointCloud> AllocatePointCloud();
54
55 virtual bool WritePointCloud(const std::shared_ptr<PointCloud>& point_cloud);
56
57 virtual std::shared_ptr<apollo::cyber::base::ArenaQueue<PointXYZIT>>
59 // static std::shared_ptr<PointCloud> PcdDefaultAllocator(
60 // std::shared_ptr<cyber::Writer<PointCloud>>& pcd_writer);
61
62 static void PcdDefaultCleaner(std::shared_ptr<PointCloud>& unused_pcd_frame);
63
64 std::string frame_id_;
65
66 private:
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;
70 // std::shared_ptr<SyncBuffering<PointCloud>> pcd_buffer_ = nullptr;
71
72 std::atomic<int> pcd_sequence_num_{0};
73};
74
75template <typename ScanType, typename ComponentType>
77 const LidarConfigBase& lidar_config_base) {
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}
103
104template <typename ScanType, typename ComponentType>
106 const LidarConfigBase& lidar_config_base) {
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}
115
116template <typename ScanType, typename ComponentType>
117std::shared_ptr<ScanType>
119 if (scan_writer_ == nullptr) {
120 return std::make_shared<ScanType>();
121 }
122 return scan_writer_->AcquireMessage();
123}
124
125template <typename ScanType, typename ComponentType>
127 const std::shared_ptr<ScanType>& scan_message) {
128 return scan_writer_->Write(scan_message);
129}
130
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();
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}
153
154template <typename ScanType, typename ComponentType>
155std::shared_ptr<PointCloud>
157 return pcd_writer_->AcquireMessage();
158}
159
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(
167 cyber::Time().Now().ToSecond());
168 RETURN_VAL_IF(!pcd_writer_->Write(point_cloud), false);
169 return true;
170}
171
172// template <typename ScanType, typename ComponentType>
173// std::shared_ptr<PointCloud>
174// LidarComponentBaseImpl<ScanType, ComponentType>::PcdDefaultAllocator(
175// std::shared_ptr<cyber::Writer<PointCloud>>& pcd_writer) {
176// constexpr int default_point_cloud_reserve = 170000;
177// std::shared_ptr<PointCloud> new_pcd_object =
178// pcd_writer->AcquireMessage();
179// new_pcd_object->mutable_point()->Reserve(default_point_cloud_reserve);
180// AINFO << "new pcd frame memory allocated, reserve point size = "
181// << default_point_cloud_reserve;
182// return new_pcd_object;
183// }
184
185template <typename ScanType, typename ComponentType>
187 std::shared_ptr<PointCloud>& unused_pcd_frame) {
188 unused_pcd_frame->clear_point();
189}
190} // namespace lidar
191} // namespace drivers
192} // namespace apollo
193#endif // APOLLO_LIDAR_COMPONENT_BASE_IMPL_H
Cyber has builtin time type Time.
Definition time.h:31
virtual bool WritePointCloud(const std::shared_ptr< PointCloud > &point_cloud)
bool InitConverter(const LidarConfigBase &lidar_config_base)
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)
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)
Definition log.h:114
#define ADEBUG
Definition log.h:41
class register implement
Definition arena_queue.h:37