lddc.h
Go to the documentation of this file.
1 //
2 // The MIT License (MIT)
3 //
4 // Copyright (c) 2019 Livox. All rights reserved.
5 //
6 // Permission is hereby granted, free of charge, to any person obtaining a copy
7 // of this software and associated documentation files (the "Software"), to deal
8 // in the Software without restriction, including without limitation the rights
9 // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
10 // copies of the Software, and to permit persons to whom the Software is
11 // furnished to do so, subject to the following conditions:
12 //
13 // The above copyright notice and this permission notice shall be included in
14 // all copies or substantial portions of the Software.
15 //
16 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
17 // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
18 // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
19 // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
20 // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
21 // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
22 // SOFTWARE.
23 //
24 #ifndef LIVOX_ROS_DRIVER_LDDC_H_
25 #define LIVOX_ROS_DRIVER_LDDC_H_
26 
27 #include "lds.h"
28 #include "livox_sdk.h"
29 
30 #include <ros/ros.h>
31 #include <rosbag/bag.h>
32 #include <pcl_ros/point_cloud.h>
33 #include <livox_ros_driver/CustomMsg.h>
34 #include <livox_ros_driver/CustomPoint.h>
35 
36 namespace livox_ros {
37 
38 typedef pcl::PointCloud<pcl::PointXYZI> PointCloud;
39 
41 typedef enum {
45 } TransferType;
46 
47 class Lddc {
48  public:
49  Lddc(int format, int multi_topic, int data_src, int output_type, double frq,
50  std::string &frame_id, bool lidar_bag, bool imu_bag);
51  ~Lddc();
52 
53  int RegisterLds(Lds *lds);
54  void DistributeLidarData(void);
55  void CreateBagFile(const std::string &file_name);
56  void PrepareExit(void);
57 
60  void SetRosNode(ros::NodeHandle *node) { cur_node_ = node; }
61 
62  void SetRosPub(ros::Publisher *pub) { global_pub_ = pub; };
63  void SetPublishFrq(uint32_t frq) { publish_frq_ = frq; }
64 
66 
67  private:
69  uint64_t *start_time,
70  StoragePacket *storage_packet);
72  uint8_t handle);
74  uint8_t handle);
76  uint8_t handle);
78  uint8_t handle);
79 
82  void PollingLidarPointCloudData(uint8_t handle, LidarDevice *lidar);
83  void PollingLidarImuData(uint8_t handle, LidarDevice *lidar);
84  void InitPointcloud2MsgHeader(sensor_msgs::PointCloud2& cloud);
85  void FillPointsToPclMsg(PointCloud::Ptr& pcl_msg, \
86  LivoxPointXyzrtl* src_point, uint32_t num);
87  void FillPointsToCustomMsg(livox_ros_driver::CustomMsg& livox_msg, \
88  LivoxPointXyzrtl* src_point, uint32_t num, uint32_t offset_time, \
89  uint32_t point_interval, uint32_t echo_num);
94  double publish_frq_;
96  std::string frame_id_;
103 
106 };
107 
108 } // namespace livox_ros
109 #endif
const uint32_t kMaxSourceLidar
Definition: lds.h:46
uint32_t PublishPointcloudData(LidarDataQueue *queue, uint32_t packet_num, uint8_t handle)
Definition: lddc.cpp:270
uint8_t GetTransferFormat(void)
Definition: lddc.h:58
ros::Publisher * global_imu_pub_
Definition: lddc.h:102
ros::Publisher * GetCurrentPublisher(uint8_t handle)
Definition: lddc.cpp:591
uint8_t data_src_
Definition: lddc.h:92
TransferType
Definition: lddc.h:41
uint32_t PublishPointcloud2(LidarDataQueue *queue, uint32_t packet_num, uint8_t handle)
Definition: lddc.cpp:164
void InitPointcloud2MsgHeader(sensor_msgs::PointCloud2 &cloud)
Definition: lddc.cpp:132
unsigned char uint8_t
Definition: stdint.h:125
void CreateBagFile(const std::string &file_name)
Definition: lddc.cpp:673
void PollingLidarPointCloudData(uint8_t handle, LidarDevice *lidar)
Definition: lddc.cpp:535
void FillPointsToCustomMsg(livox_ros_driver::CustomMsg &livox_msg, LivoxPointXyzrtl *src_point, uint32_t num, uint32_t offset_time, uint32_t point_interval, uint32_t echo_num)
Definition: lddc.cpp:356
ros::Publisher * private_pub_[kMaxSourceLidar]
Definition: lddc.h:99
uint8_t output_type_
Definition: lddc.h:93
uint8_t IsMultiTopic(void)
Definition: lddc.h:59
void SetPublishFrq(uint32_t frq)
Definition: lddc.h:63
Lds * lds_
Definition: lddc.h:65
uint8_t transfer_format_
Definition: lddc.h:90
bool enable_lidar_bag_
Definition: lddc.h:97
pcl::PointCloud< pcl::PointXYZI > PointCloud
Definition: lddc.h:38
unsigned int uint32_t
Definition: stdint.h:127
rosbag::Bag * bag_
Definition: lddc.h:105
unsigned __int64 uint64_t
Definition: stdint.h:137
bool enable_imu_bag_
Definition: lddc.h:98
ros::Publisher * global_pub_
Definition: lddc.h:100
void SetRosNode(ros::NodeHandle *node)
Definition: lddc.h:60
void PollingLidarImuData(uint8_t handle, LidarDevice *lidar)
Definition: lddc.cpp:558
ros::NodeHandle * cur_node_
Definition: lddc.h:104
uint32_t PublishImuData(LidarDataQueue *queue, uint32_t packet_num, uint8_t handle)
Definition: lddc.cpp:481
int RegisterLds(Lds *lds)
Definition: lddc.cpp:526
std::string frame_id_
Definition: lddc.h:96
uint32_t publish_period_ns_
Definition: lddc.h:95
double publish_frq_
Definition: lddc.h:94
void PrepareExit(void)
Definition: lddc.cpp:681
void SetRosPub(ros::Publisher *pub)
Definition: lddc.h:62
signed int int32_t
Definition: stdint.h:124
ros::Publisher * GetCurrentImuPublisher(uint8_t handle)
Definition: lddc.cpp:640
uint32_t PublishCustomPointcloud(LidarDataQueue *queue, uint32_t packet_num, uint8_t handle)
Definition: lddc.cpp:378
ros::Publisher * private_imu_pub_[kMaxSourceLidar]
Definition: lddc.h:101
void DistributeLidarData(void)
Definition: lddc.cpp:569
uint8_t use_multi_topic_
Definition: lddc.h:91
int32_t GetPublishStartTime(LidarDevice *lidar, LidarDataQueue *queue, uint64_t *start_time, StoragePacket *storage_packet)
Definition: lddc.cpp:91
Lddc(int format, int multi_topic, int data_src, int output_type, double frq, std::string &frame_id, bool lidar_bag, bool imu_bag)
Definition: lddc.cpp:45
void FillPointsToPclMsg(PointCloud::Ptr &pcl_msg, LivoxPointXyzrtl *src_point, uint32_t num)
Definition: lddc.cpp:255


livox_ros_driver
Author(s): Livox Dev Team
autogenerated on Mon Mar 15 2021 02:40:46