main.cpp 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440
  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. #include <stdio.h>
  25. #include <stdlib.h>
  26. #include <unistd.h>
  27. #include <string.h>
  28. #include <stdint.h>
  29. #include <math.h>
  30. #include <vector>
  31. #include <list>
  32. #include "livox_sdk.h"
  33. #include <ros/ros.h>
  34. #include <pcl_ros/point_cloud.h>
  35. #include <pcl/common/transforms.h>
  36. #include <pcl_conversions/pcl_conversions.h>
  37. #include <tf/transform_broadcaster.h>
  38. #define BUFFER_POINTS (32*1024) // must be 2^n
  39. #define POINTS_PER_FRAME 60000 // must < BUFFER_POINTS
  40. #define PACKET_GAP_MISS_TIME (1500000) // 1.5ms
  41. #define BD_ARGC_NUM (4)
  42. #define BD_ARGV_POS (1)
  43. #define COMMANDLINE_BD_SIZE (15)
  44. typedef pcl::PointCloud<pcl::PointXYZI> PointCloud;
  45. struct PointCloudQueue {
  46. LivoxPoint buffer[BUFFER_POINTS];
  47. volatile uint32_t rd_idx;
  48. volatile uint32_t wr_idx;
  49. uint32_t mask;
  50. uint32_t size; // must be 2^n
  51. };
  52. typedef struct {
  53. uint32_t receive_packet_count;
  54. uint32_t loss_packet_count;
  55. uint64_t last_timestamp;
  56. } LidarPacketStatistic;
  57. PointCloudQueue point_cloud_queue_pool[kMaxLidarCount];
  58. /* for global publisher use */
  59. ros::Publisher cloud_pub;
  60. /* for device connect use ----------------------------------------------------------------------- */
  61. typedef enum {
  62. kDeviceStateDisconnect = 0,
  63. kDeviceStateConnect = 1,
  64. kDeviceStateSampling = 2,
  65. } DeviceState;
  66. typedef struct {
  67. uint8_t handle;
  68. DeviceState device_state;
  69. DeviceInfo info;
  70. LidarPacketStatistic statistic_info;
  71. } DeviceItem;
  72. DeviceItem lidars[kMaxLidarCount];
  73. /* user add broadcast code here */
  74. const char* broadcast_code_list[] = {
  75. "0TFDFG700601881",
  76. };
  77. #define BROADCAST_CODE_LIST_SIZE (sizeof(broadcast_code_list) / sizeof(intptr_t))
  78. /* total broadcast code, include broadcast_code_list and commandline input */
  79. std::vector<std::string > total_broadcast_code;
  80. /* for pointcloud queue process */
  81. void PointCloudPoolInit(void) {
  82. for (int i=0; i<kMaxLidarCount; i++) {
  83. point_cloud_queue_pool[i].rd_idx = 0;
  84. point_cloud_queue_pool[i].wr_idx = 0;
  85. point_cloud_queue_pool[i].size = BUFFER_POINTS;
  86. point_cloud_queue_pool[i].mask = BUFFER_POINTS - 1;
  87. }
  88. }
  89. uint32_t QueuePop(PointCloudQueue* queue, LivoxPoint* out_point) {
  90. uint32_t mask = queue->mask;
  91. uint32_t rd_idx = queue->rd_idx & mask;
  92. out_point->x = queue->buffer[rd_idx].x;
  93. out_point->y = queue->buffer[rd_idx].y;
  94. out_point->z = queue->buffer[rd_idx].z;
  95. out_point->reflectivity = queue->buffer[rd_idx].reflectivity;
  96. queue->rd_idx++;
  97. }
  98. uint32_t QueuePush(PointCloudQueue *queue, LivoxPoint * in_point) {
  99. uint32_t mask = queue->mask;
  100. uint32_t wr_idx = queue->wr_idx & mask;
  101. queue->buffer[wr_idx].x = in_point->x;
  102. queue->buffer[wr_idx].y = in_point->y;
  103. queue->buffer[wr_idx].z = in_point->z;
  104. queue->buffer[wr_idx].reflectivity = in_point->reflectivity;
  105. queue->wr_idx++;
  106. }
  107. uint32_t QueueUsedSize(PointCloudQueue *queue) {
  108. return (queue->wr_idx - queue->rd_idx) & queue->mask;
  109. }
  110. uint32_t QueueIsFull(PointCloudQueue *queue) {
  111. return ((queue->wr_idx + 1) == queue->rd_idx);
  112. }
  113. uint32_t QueueIsEmpty(PointCloudQueue *queue) {
  114. return (queue->rd_idx == queue->wr_idx);
  115. }
  116. /* for pointcloud convert process */
  117. static uint32_t PublishPointcloudData(PointCloudQueue *queue, uint32_t num, sensor_msgs::PointCloud2 cloud) {
  118. /* init point cloud data struct */
  119. pcl::PointCloud<pcl::PointXYZI> curr;
  120. LivoxPoint points;
  121. for (unsigned int i = 0; i < num; i++) {
  122. QueuePop(queue, &points);
  123. pcl::PointXYZI point;
  124. point.x = points.x;
  125. point.y = points.y;
  126. point.z = points.z;
  127. point.intensity = (float) points.reflectivity;
  128. curr.points.push_back(point);
  129. }
  130. pcl::toROSMsg(curr,cloud);
  131. // if (cloud->points.size() > BUFFER_POINTS)
  132. // {
  133. // PointCloud::Ptr cloud2(new PointCloud);
  134. // cloud2->header.frame_id = "livox_frame";
  135. // cloud2->height = 1;
  136. // cloud2->width = num;
  137. // while (cloud2->points.size() < BUFFER_POINTS)
  138. // {
  139. // pcl::PointXYZI point = cloud->points[cloud->points.size() - 1];
  140. // cloud->points.pop_back();
  141. // cloud2->points.push_back(point);
  142. // }
  143. // cloud_pub.publish(cloud2);
  144. // std::cout<<cloud2->points.size()<<std::endl;
  145. // }
  146. // else
  147. // {
  148. tf::TransformBroadcaster tf_broadcaster_;
  149. tf::Transform transform;
  150. transform.setOrigin( tf::Vector3(0.0, 0.0, 0.0));
  151. transform.setRotation( tf::Quaternion(0, 0, 0, 1));
  152. tf::StampedTransform transform_msg (transform, ros::Time::now(), "map", "livox_frame");
  153. tf_broadcaster_.sendTransform(transform_msg);
  154. cloud.header.frame_id = "livox_frame";
  155. cloud.height = 1;
  156. cloud.width = num;
  157. cloud.header.stamp = ros::Time::now();
  158. cloud_pub.publish(cloud);
  159. // std::cout<<cloud->points.size()<<std::endl;
  160. // }
  161. }
  162. static void PointCloudConvert(LivoxPoint *p_dpoint, LivoxRawPoint *p_raw_point) {
  163. p_dpoint->x = p_raw_point->x/1000.0f;
  164. p_dpoint->y = p_raw_point->y/1000.0f;
  165. p_dpoint->z = p_raw_point->z/1000.0f;
  166. p_dpoint->reflectivity = p_raw_point->reflectivity;
  167. }
  168. void GetLidarData(uint8_t handle, LivoxEthPacket *data, uint32_t data_num, void *client_data) {
  169. LivoxEthPacket *lidar_pack = data;
  170. if (!data || !data_num) {
  171. return;
  172. }
  173. if (handle >= kMaxLidarCount) {
  174. return;
  175. }
  176. if ((lidar_pack->timestamp_type == kTimestampTypeNoSync) || \
  177. (lidar_pack->timestamp_type == kTimestampTypePtp) ||\
  178. (lidar_pack->timestamp_type == kTimestampTypePps)) {
  179. LidarPacketStatistic *packet_statistic = &lidars[handle].statistic_info;
  180. uint64_t cur_timestamp = *((uint64_t *)(lidar_pack->timestamp));
  181. int64_t packet_gap = cur_timestamp - packet_statistic->last_timestamp;
  182. packet_statistic->receive_packet_count++;
  183. if (packet_statistic->last_timestamp) {
  184. if (packet_gap > PACKET_GAP_MISS_TIME) {
  185. packet_statistic->loss_packet_count++;
  186. ROS_INFO("%d miss count : %ld %lu %lu %d", \
  187. handle, packet_gap,\
  188. cur_timestamp, packet_statistic->last_timestamp,\
  189. packet_statistic->loss_packet_count);
  190. }
  191. }
  192. packet_statistic->last_timestamp = cur_timestamp;
  193. }
  194. LivoxRawPoint *p_point_data = (LivoxRawPoint *)lidar_pack->data;
  195. PointCloudQueue *p_queue = &point_cloud_queue_pool[handle];
  196. LivoxPoint tmp_point;
  197. while (data_num) {
  198. PointCloudConvert(&tmp_point, p_point_data);
  199. if (QueueIsFull(p_queue)) {
  200. break;
  201. }
  202. QueuePush(p_queue, &tmp_point);
  203. --data_num;
  204. p_point_data++;
  205. }
  206. return;
  207. }
  208. void PollPointcloudData(sensor_msgs::PointCloud2 cloud) {
  209. for (int i = 0; i < kMaxLidarCount; i++) {
  210. PointCloudQueue *p_queue = &point_cloud_queue_pool[i];
  211. if (QueueUsedSize(p_queue) > POINTS_PER_FRAME) {
  212. //ROS_DEBUG("%d %d %d %d\r\n", i, p_queue->rd_idx, p_queue->wr_idx, QueueUsedSize(p_queue));
  213. PublishPointcloudData(p_queue, POINTS_PER_FRAME, cloud);
  214. }
  215. }
  216. }
  217. /** add bd to total_broadcast_code */
  218. void add_broadcast_code(const char* bd_str) {
  219. total_broadcast_code.push_back(bd_str);
  220. }
  221. /** add bd in broadcast_code_list to total_broadcast_code */
  222. void add_local_broadcast_code(void) {
  223. for (int i = 0; i < BROADCAST_CODE_LIST_SIZE; ++i) {
  224. add_broadcast_code(broadcast_code_list[i]);
  225. }
  226. }
  227. /** add commandline bd to total_broadcast_code */
  228. void add_commandline_broadcast_code(const char* cammandline_str) {
  229. char* strs = new char[strlen(cammandline_str) + 1];
  230. strcpy(strs, cammandline_str);
  231. std::string pattern = "&";
  232. char* bd_str = strtok(strs, pattern.c_str());
  233. while (bd_str != NULL) {
  234. ROS_INFO("commandline input bd:%s", bd_str);
  235. if (COMMANDLINE_BD_SIZE == strlen(bd_str)) {
  236. add_broadcast_code(bd_str);
  237. } else {
  238. ROS_INFO("Invalid bd:%s", bd_str);
  239. }
  240. bd_str = strtok(NULL, pattern.c_str());
  241. }
  242. delete [] strs;
  243. }
  244. /** Callback function of starting sampling. */
  245. void OnSampleCallback(uint8_t status, uint8_t handle, uint8_t response, void *data) {
  246. ROS_INFO("OnSampleCallback statue %d handle %d response %d", status, handle, response);
  247. if (status == kStatusSuccess) {
  248. if (response != 0) {
  249. lidars[handle].device_state = kDeviceStateConnect;
  250. }
  251. } else if (status == kStatusTimeout) {
  252. lidars[handle].device_state = kDeviceStateConnect;
  253. }
  254. }
  255. /** Callback function of stopping sampling. */
  256. void OnStopSampleCallback(uint8_t status, uint8_t handle, uint8_t response, void *data) {
  257. }
  258. /** Query the firmware version of Livox LiDAR. */
  259. void OnDeviceInformation(uint8_t status, uint8_t handle, DeviceInformationResponse *ack, void *data) {
  260. if (status != kStatusSuccess) {
  261. ROS_INFO("Device Query Informations Failed %d", status);
  262. }
  263. if (ack) {
  264. ROS_INFO("firm ver: %d.%d.%d.%d",
  265. ack->firmware_version[0],
  266. ack->firmware_version[1],
  267. ack->firmware_version[2],
  268. ack->firmware_version[3]);
  269. }
  270. }
  271. /** Callback function of changing of device state. */
  272. void OnDeviceChange(const DeviceInfo *info, DeviceEvent type) {
  273. if (info == NULL) {
  274. return;
  275. }
  276. ROS_INFO("OnDeviceChange broadcast code %s update type %d", info->broadcast_code, type);
  277. uint8_t handle = info->handle;
  278. if (handle >= kMaxLidarCount) {
  279. return;
  280. }
  281. if (type == kEventConnect) {
  282. QueryDeviceInformation(handle, OnDeviceInformation, NULL);
  283. if (lidars[handle].device_state == kDeviceStateDisconnect) {
  284. lidars[handle].device_state = kDeviceStateConnect;
  285. lidars[handle].info = *info;
  286. }
  287. } else if (type == kEventDisconnect) {
  288. lidars[handle].device_state = kDeviceStateDisconnect;
  289. } else if (type == kEventStateChange) {
  290. lidars[handle].info = *info;
  291. }
  292. if (lidars[handle].device_state == kDeviceStateConnect) {
  293. ROS_INFO("Device State error_code %d", lidars[handle].info.status.status_code);
  294. ROS_INFO("Device State working state %d", lidars[handle].info.state);
  295. ROS_INFO("Device feature %d", lidars[handle].info.feature);
  296. if (lidars[handle].info.state == kLidarStateNormal) {
  297. if (lidars[handle].info.type == kDeviceTypeHub) {
  298. HubStartSampling(OnSampleCallback, NULL);
  299. } else {
  300. LidarStartSampling(handle, OnSampleCallback, NULL);
  301. }
  302. lidars[handle].device_state = kDeviceStateSampling;
  303. }
  304. }
  305. }
  306. void OnDeviceBroadcast(const BroadcastDeviceInfo *info) {
  307. if (info == NULL) {
  308. return;
  309. }
  310. ROS_INFO("Receive Broadcast Code %s", info->broadcast_code);
  311. bool found = false;
  312. for (int i = 0; i < total_broadcast_code.size(); ++i) {
  313. if (strncmp(info->broadcast_code, total_broadcast_code[i].c_str(), kBroadcastCodeSize) == 0) {
  314. found = true;
  315. break;
  316. }
  317. }
  318. if (!found) {
  319. ROS_INFO("Not in the broacast_code_list, please add it to if want to connect!");
  320. return;
  321. }
  322. bool result = false;
  323. uint8_t handle = 0;
  324. result = AddLidarToConnect(info->broadcast_code, &handle);
  325. if (result == kStatusSuccess && handle < kMaxLidarCount) {
  326. SetDataCallback(handle, GetLidarData, NULL);
  327. lidars[handle].handle = handle;
  328. lidars[handle].device_state = kDeviceStateDisconnect;
  329. }
  330. }
  331. int main(int argc, char **argv) {
  332. if( ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Debug) ) {
  333. ros::console::notifyLoggerLevelsChanged();
  334. }
  335. ROS_INFO("Livox-SDK ros demo");
  336. PointCloudPoolInit();
  337. if (!Init()) {
  338. ROS_FATAL("Livox-SDK init fail!");
  339. return -1;
  340. }
  341. add_local_broadcast_code();
  342. if (argc >= BD_ARGC_NUM) {
  343. ROS_INFO("Commandline input %s", argv[BD_ARGV_POS]);
  344. add_commandline_broadcast_code(argv[BD_ARGV_POS]);
  345. }
  346. memset(lidars, 0, sizeof(lidars));
  347. SetBroadcastCallback(OnDeviceBroadcast);
  348. SetDeviceStateUpdateCallback(OnDeviceChange);
  349. if (!Start()) {
  350. Uninit();
  351. return -1;
  352. }
  353. sensor_msgs::PointCloud2 cloud;
  354. /* ros related */
  355. ros::init(argc, argv, "livox_lidar_publisher");
  356. ros::NodeHandle livox_node;
  357. cloud_pub = livox_node.advertise<PointCloud>("livox/lidar", POINTS_PER_FRAME);
  358. ros::Time::init();
  359. ros::Rate r(25); // 500 hz
  360. while (ros::ok()) {
  361. PollPointcloudData(cloud);
  362. ros::spinOnce();
  363. r.sleep();
  364. }
  365. Uninit();
  366. }