24 #ifndef LIVOX_ROS_DRIVER_LDDC_H_ 25 #define LIVOX_ROS_DRIVER_LDDC_H_ 28 #include "livox_sdk.h" 33 #include <livox_ros_driver/CustomMsg.h> 34 #include <livox_ros_driver/CustomPoint.h> 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);
const uint32_t kMaxSourceLidar
uint32_t PublishPointcloudData(LidarDataQueue *queue, uint32_t packet_num, uint8_t handle)
uint8_t GetTransferFormat(void)
ros::Publisher * global_imu_pub_
ros::Publisher * GetCurrentPublisher(uint8_t handle)
uint32_t PublishPointcloud2(LidarDataQueue *queue, uint32_t packet_num, uint8_t handle)
void InitPointcloud2MsgHeader(sensor_msgs::PointCloud2 &cloud)
void CreateBagFile(const std::string &file_name)
void PollingLidarPointCloudData(uint8_t handle, LidarDevice *lidar)
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)
ros::Publisher * private_pub_[kMaxSourceLidar]
uint8_t IsMultiTopic(void)
void SetPublishFrq(uint32_t frq)
pcl::PointCloud< pcl::PointXYZI > PointCloud
unsigned __int64 uint64_t
ros::Publisher * global_pub_
void SetRosNode(ros::NodeHandle *node)
void PollingLidarImuData(uint8_t handle, LidarDevice *lidar)
ros::NodeHandle * cur_node_
uint32_t PublishImuData(LidarDataQueue *queue, uint32_t packet_num, uint8_t handle)
int RegisterLds(Lds *lds)
uint32_t publish_period_ns_
void SetRosPub(ros::Publisher *pub)
ros::Publisher * GetCurrentImuPublisher(uint8_t handle)
uint32_t PublishCustomPointcloud(LidarDataQueue *queue, uint32_t packet_num, uint8_t handle)
ros::Publisher * private_imu_pub_[kMaxSourceLidar]
void DistributeLidarData(void)
int32_t GetPublishStartTime(LidarDevice *lidar, LidarDataQueue *queue, uint64_t *start_time, StoragePacket *storage_packet)
Lddc(int format, int multi_topic, int data_src, int output_type, double frq, std::string &frame_id, bool lidar_bag, bool imu_bag)
void FillPointsToPclMsg(PointCloud::Ptr &pcl_msg, LivoxPointXyzrtl *src_point, uint32_t num)