Apollo 10.0
自动驾驶开放平台
rslidar_component.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#pragma once
17
18#include <memory>
19
20#include "rs_driver/api/lidar_driver.hpp"
21#include "rs_driver/driver/driver_param.hpp"
22#include "rs_driver/msg/packet.hpp"
23#include "rs_driver/msg/point_cloud_msg.hpp"
24
25#include "modules/drivers/lidar/rslidar/proto/rslidar.pb.h"
26#include "modules/drivers/lidar/rslidar/proto/rslidar_config.pb.h"
27
31
32namespace apollo {
33namespace drivers {
34namespace lidar {
35
36typedef PointXYZIRT PointT;
37typedef PointCloudT<PointT> PointCloudMsg;
38
39using ::robosense::lidar::InputType;
40
42 : public LidarComponentBase<robosense::RobosenseScanPacket> {
43 public:
44 bool Init() override;
45
46 void ReadScanCallback(const std::shared_ptr<robosense::RobosenseScanPacket>&
47 scan_message) override;
48
49 void RsPacketCallback(const ::robosense::lidar::Packet& lidar_packet);
50
51 std::shared_ptr<PointCloudMsg> RsCloudAllocateCallback();
52
53 void RsCloudPutCallback(std::shared_ptr<PointCloudMsg> rs_cloud);
54
56
58
59 private:
60 std::shared_ptr<::robosense::lidar::LidarDriver<PointCloudMsg>> driver_ptr_;
62
63 ::robosense::lidar::SyncQueue<std::shared_ptr<PointCloudMsg>> cloud_queue_;
64 std::shared_ptr<SyncBuffering<PointCloudMsg>> cloud_buffer_;
65 std::thread cloud_handle_thread_;
66
67 int seq_ = 0;
68};
70
71} // namespace lidar
72} // namespace drivers
73} // namespace apollo
void RsCloudPutCallback(std::shared_ptr< PointCloudMsg > rs_cloud)
std::shared_ptr< PointCloudMsg > RsCloudAllocateCallback()
void RsPacketCallback(const ::robosense::lidar::Packet &lidar_packet)
void ReadScanCallback(const std::shared_ptr< robosense::RobosenseScanPacket > &scan_message) override
#define CYBER_REGISTER_COMPONENT(name)
Definition component.h:656
PointCloudT< PointT > PointCloudMsg
class register implement
Definition arena_queue.h:37