123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440 |
- //
- // The MIT License (MIT)
- //
- // Copyright (c) 2019 Livox. All rights reserved.
- //
- // Permission is hereby granted, free of charge, to any person obtaining a copy
- // of this software and associated documentation files (the "Software"), to deal
- // in the Software without restriction, including without limitation the rights
- // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- // copies of the Software, and to permit persons to whom the Software is
- // furnished to do so, subject to the following conditions:
- //
- // The above copyright notice and this permission notice shall be included in
- // all copies or substantial portions of the Software.
- //
- // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
- // SOFTWARE.
- //
- #include <stdio.h>
- #include <stdlib.h>
- #include <unistd.h>
- #include <string.h>
- #include <stdint.h>
- #include <math.h>
- #include <vector>
- #include <list>
- #include "livox_sdk.h"
- #include <ros/ros.h>
- #include <pcl_ros/point_cloud.h>
- #include <pcl/common/transforms.h>
- #include <pcl_conversions/pcl_conversions.h>
- #include <tf/transform_broadcaster.h>
- #define BUFFER_POINTS (32*1024) // must be 2^n
- #define POINTS_PER_FRAME 60000 // must < BUFFER_POINTS
- #define PACKET_GAP_MISS_TIME (1500000) // 1.5ms
- #define BD_ARGC_NUM (4)
- #define BD_ARGV_POS (1)
- #define COMMANDLINE_BD_SIZE (15)
- typedef pcl::PointCloud<pcl::PointXYZI> PointCloud;
- struct PointCloudQueue {
- LivoxPoint buffer[BUFFER_POINTS];
- volatile uint32_t rd_idx;
- volatile uint32_t wr_idx;
- uint32_t mask;
- uint32_t size; // must be 2^n
- };
- typedef struct {
- uint32_t receive_packet_count;
- uint32_t loss_packet_count;
- uint64_t last_timestamp;
- } LidarPacketStatistic;
- PointCloudQueue point_cloud_queue_pool[kMaxLidarCount];
- /* for global publisher use */
- ros::Publisher cloud_pub;
- /* for device connect use ----------------------------------------------------------------------- */
- typedef enum {
- kDeviceStateDisconnect = 0,
- kDeviceStateConnect = 1,
- kDeviceStateSampling = 2,
- } DeviceState;
- typedef struct {
- uint8_t handle;
- DeviceState device_state;
- DeviceInfo info;
- LidarPacketStatistic statistic_info;
- } DeviceItem;
- DeviceItem lidars[kMaxLidarCount];
- /* user add broadcast code here */
- const char* broadcast_code_list[] = {
- "0TFDFG700601881",
- };
- #define BROADCAST_CODE_LIST_SIZE (sizeof(broadcast_code_list) / sizeof(intptr_t))
- /* total broadcast code, include broadcast_code_list and commandline input */
- std::vector<std::string > total_broadcast_code;
- /* for pointcloud queue process */
- void PointCloudPoolInit(void) {
- for (int i=0; i<kMaxLidarCount; i++) {
- point_cloud_queue_pool[i].rd_idx = 0;
- point_cloud_queue_pool[i].wr_idx = 0;
- point_cloud_queue_pool[i].size = BUFFER_POINTS;
- point_cloud_queue_pool[i].mask = BUFFER_POINTS - 1;
- }
- }
- uint32_t QueuePop(PointCloudQueue* queue, LivoxPoint* out_point) {
- uint32_t mask = queue->mask;
- uint32_t rd_idx = queue->rd_idx & mask;
- out_point->x = queue->buffer[rd_idx].x;
- out_point->y = queue->buffer[rd_idx].y;
- out_point->z = queue->buffer[rd_idx].z;
- out_point->reflectivity = queue->buffer[rd_idx].reflectivity;
- queue->rd_idx++;
- }
- uint32_t QueuePush(PointCloudQueue *queue, LivoxPoint * in_point) {
- uint32_t mask = queue->mask;
- uint32_t wr_idx = queue->wr_idx & mask;
- queue->buffer[wr_idx].x = in_point->x;
- queue->buffer[wr_idx].y = in_point->y;
- queue->buffer[wr_idx].z = in_point->z;
- queue->buffer[wr_idx].reflectivity = in_point->reflectivity;
- queue->wr_idx++;
- }
- uint32_t QueueUsedSize(PointCloudQueue *queue) {
- return (queue->wr_idx - queue->rd_idx) & queue->mask;
- }
- uint32_t QueueIsFull(PointCloudQueue *queue) {
- return ((queue->wr_idx + 1) == queue->rd_idx);
- }
- uint32_t QueueIsEmpty(PointCloudQueue *queue) {
- return (queue->rd_idx == queue->wr_idx);
- }
- /* for pointcloud convert process */
- static uint32_t PublishPointcloudData(PointCloudQueue *queue, uint32_t num, sensor_msgs::PointCloud2 cloud) {
- /* init point cloud data struct */
- pcl::PointCloud<pcl::PointXYZI> curr;
- LivoxPoint points;
- for (unsigned int i = 0; i < num; i++) {
- QueuePop(queue, &points);
- pcl::PointXYZI point;
- point.x = points.x;
- point.y = points.y;
- point.z = points.z;
- point.intensity = (float) points.reflectivity;
- curr.points.push_back(point);
- }
- pcl::toROSMsg(curr,cloud);
- // if (cloud->points.size() > BUFFER_POINTS)
- // {
- // PointCloud::Ptr cloud2(new PointCloud);
- // cloud2->header.frame_id = "livox_frame";
- // cloud2->height = 1;
- // cloud2->width = num;
- // while (cloud2->points.size() < BUFFER_POINTS)
- // {
- // pcl::PointXYZI point = cloud->points[cloud->points.size() - 1];
- // cloud->points.pop_back();
- // cloud2->points.push_back(point);
- // }
- // cloud_pub.publish(cloud2);
- // std::cout<<cloud2->points.size()<<std::endl;
- // }
- // else
- // {
-
- tf::TransformBroadcaster tf_broadcaster_;
- tf::Transform transform;
- transform.setOrigin( tf::Vector3(0.0, 0.0, 0.0));
- transform.setRotation( tf::Quaternion(0, 0, 0, 1));
- tf::StampedTransform transform_msg (transform, ros::Time::now(), "map", "livox_frame");
- tf_broadcaster_.sendTransform(transform_msg);
- cloud.header.frame_id = "livox_frame";
- cloud.height = 1;
- cloud.width = num;
- cloud.header.stamp = ros::Time::now();
- cloud_pub.publish(cloud);
- // std::cout<<cloud->points.size()<<std::endl;
- // }
- }
- static void PointCloudConvert(LivoxPoint *p_dpoint, LivoxRawPoint *p_raw_point) {
- p_dpoint->x = p_raw_point->x/1000.0f;
- p_dpoint->y = p_raw_point->y/1000.0f;
- p_dpoint->z = p_raw_point->z/1000.0f;
- p_dpoint->reflectivity = p_raw_point->reflectivity;
- }
- void GetLidarData(uint8_t handle, LivoxEthPacket *data, uint32_t data_num, void *client_data) {
- LivoxEthPacket *lidar_pack = data;
- if (!data || !data_num) {
- return;
- }
- if (handle >= kMaxLidarCount) {
- return;
- }
- if ((lidar_pack->timestamp_type == kTimestampTypeNoSync) || \
- (lidar_pack->timestamp_type == kTimestampTypePtp) ||\
- (lidar_pack->timestamp_type == kTimestampTypePps)) {
- LidarPacketStatistic *packet_statistic = &lidars[handle].statistic_info;
- uint64_t cur_timestamp = *((uint64_t *)(lidar_pack->timestamp));
- int64_t packet_gap = cur_timestamp - packet_statistic->last_timestamp;
- packet_statistic->receive_packet_count++;
- if (packet_statistic->last_timestamp) {
- if (packet_gap > PACKET_GAP_MISS_TIME) {
- packet_statistic->loss_packet_count++;
- ROS_INFO("%d miss count : %ld %lu %lu %d", \
- handle, packet_gap,\
- cur_timestamp, packet_statistic->last_timestamp,\
- packet_statistic->loss_packet_count);
- }
- }
- packet_statistic->last_timestamp = cur_timestamp;
- }
- LivoxRawPoint *p_point_data = (LivoxRawPoint *)lidar_pack->data;
- PointCloudQueue *p_queue = &point_cloud_queue_pool[handle];
- LivoxPoint tmp_point;
- while (data_num) {
- PointCloudConvert(&tmp_point, p_point_data);
- if (QueueIsFull(p_queue)) {
- break;
- }
- QueuePush(p_queue, &tmp_point);
- --data_num;
- p_point_data++;
- }
- return;
- }
- void PollPointcloudData(sensor_msgs::PointCloud2 cloud) {
- for (int i = 0; i < kMaxLidarCount; i++) {
- PointCloudQueue *p_queue = &point_cloud_queue_pool[i];
- if (QueueUsedSize(p_queue) > POINTS_PER_FRAME) {
- //ROS_DEBUG("%d %d %d %d\r\n", i, p_queue->rd_idx, p_queue->wr_idx, QueueUsedSize(p_queue));
- PublishPointcloudData(p_queue, POINTS_PER_FRAME, cloud);
- }
- }
- }
- /** add bd to total_broadcast_code */
- void add_broadcast_code(const char* bd_str) {
- total_broadcast_code.push_back(bd_str);
- }
- /** add bd in broadcast_code_list to total_broadcast_code */
- void add_local_broadcast_code(void) {
- for (int i = 0; i < BROADCAST_CODE_LIST_SIZE; ++i) {
- add_broadcast_code(broadcast_code_list[i]);
- }
- }
- /** add commandline bd to total_broadcast_code */
- void add_commandline_broadcast_code(const char* cammandline_str) {
- char* strs = new char[strlen(cammandline_str) + 1];
- strcpy(strs, cammandline_str);
- std::string pattern = "&";
- char* bd_str = strtok(strs, pattern.c_str());
- while (bd_str != NULL) {
- ROS_INFO("commandline input bd:%s", bd_str);
- if (COMMANDLINE_BD_SIZE == strlen(bd_str)) {
- add_broadcast_code(bd_str);
- } else {
- ROS_INFO("Invalid bd:%s", bd_str);
- }
- bd_str = strtok(NULL, pattern.c_str());
- }
- delete [] strs;
- }
- /** Callback function of starting sampling. */
- void OnSampleCallback(uint8_t status, uint8_t handle, uint8_t response, void *data) {
- ROS_INFO("OnSampleCallback statue %d handle %d response %d", status, handle, response);
- if (status == kStatusSuccess) {
- if (response != 0) {
- lidars[handle].device_state = kDeviceStateConnect;
- }
- } else if (status == kStatusTimeout) {
- lidars[handle].device_state = kDeviceStateConnect;
- }
- }
- /** Callback function of stopping sampling. */
- void OnStopSampleCallback(uint8_t status, uint8_t handle, uint8_t response, void *data) {
- }
- /** Query the firmware version of Livox LiDAR. */
- void OnDeviceInformation(uint8_t status, uint8_t handle, DeviceInformationResponse *ack, void *data) {
- if (status != kStatusSuccess) {
- ROS_INFO("Device Query Informations Failed %d", status);
- }
- if (ack) {
- ROS_INFO("firm ver: %d.%d.%d.%d",
- ack->firmware_version[0],
- ack->firmware_version[1],
- ack->firmware_version[2],
- ack->firmware_version[3]);
- }
- }
- /** Callback function of changing of device state. */
- void OnDeviceChange(const DeviceInfo *info, DeviceEvent type) {
- if (info == NULL) {
- return;
- }
- ROS_INFO("OnDeviceChange broadcast code %s update type %d", info->broadcast_code, type);
- uint8_t handle = info->handle;
- if (handle >= kMaxLidarCount) {
- return;
- }
- if (type == kEventConnect) {
- QueryDeviceInformation(handle, OnDeviceInformation, NULL);
- if (lidars[handle].device_state == kDeviceStateDisconnect) {
- lidars[handle].device_state = kDeviceStateConnect;
- lidars[handle].info = *info;
- }
- } else if (type == kEventDisconnect) {
- lidars[handle].device_state = kDeviceStateDisconnect;
- } else if (type == kEventStateChange) {
- lidars[handle].info = *info;
- }
- if (lidars[handle].device_state == kDeviceStateConnect) {
- ROS_INFO("Device State error_code %d", lidars[handle].info.status.status_code);
- ROS_INFO("Device State working state %d", lidars[handle].info.state);
- ROS_INFO("Device feature %d", lidars[handle].info.feature);
- if (lidars[handle].info.state == kLidarStateNormal) {
- if (lidars[handle].info.type == kDeviceTypeHub) {
- HubStartSampling(OnSampleCallback, NULL);
- } else {
- LidarStartSampling(handle, OnSampleCallback, NULL);
- }
- lidars[handle].device_state = kDeviceStateSampling;
- }
- }
- }
- void OnDeviceBroadcast(const BroadcastDeviceInfo *info) {
- if (info == NULL) {
- return;
- }
- ROS_INFO("Receive Broadcast Code %s", info->broadcast_code);
- bool found = false;
- for (int i = 0; i < total_broadcast_code.size(); ++i) {
- if (strncmp(info->broadcast_code, total_broadcast_code[i].c_str(), kBroadcastCodeSize) == 0) {
- found = true;
- break;
- }
- }
- if (!found) {
- ROS_INFO("Not in the broacast_code_list, please add it to if want to connect!");
- return;
- }
- bool result = false;
- uint8_t handle = 0;
- result = AddLidarToConnect(info->broadcast_code, &handle);
- if (result == kStatusSuccess && handle < kMaxLidarCount) {
- SetDataCallback(handle, GetLidarData, NULL);
- lidars[handle].handle = handle;
- lidars[handle].device_state = kDeviceStateDisconnect;
- }
- }
- int main(int argc, char **argv) {
- if( ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Debug) ) {
- ros::console::notifyLoggerLevelsChanged();
- }
- ROS_INFO("Livox-SDK ros demo");
- PointCloudPoolInit();
- if (!Init()) {
- ROS_FATAL("Livox-SDK init fail!");
- return -1;
- }
- add_local_broadcast_code();
- if (argc >= BD_ARGC_NUM) {
- ROS_INFO("Commandline input %s", argv[BD_ARGV_POS]);
- add_commandline_broadcast_code(argv[BD_ARGV_POS]);
- }
- memset(lidars, 0, sizeof(lidars));
- SetBroadcastCallback(OnDeviceBroadcast);
- SetDeviceStateUpdateCallback(OnDeviceChange);
- if (!Start()) {
- Uninit();
- return -1;
- }
- sensor_msgs::PointCloud2 cloud;
- /* ros related */
- ros::init(argc, argv, "livox_lidar_publisher");
- ros::NodeHandle livox_node;
- cloud_pub = livox_node.advertise<PointCloud>("livox/lidar", POINTS_PER_FRAME);
- ros::Time::init();
- ros::Rate r(25); // 500 hz
- while (ros::ok()) {
- PollPointcloudData(cloud);
- ros::spinOnce();
- r.sleep();
- }
- Uninit();
- }
|