lds.cpp
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 
25 #include "lds.h"
26 
27 #include <math.h>
28 #include <stdio.h>
29 #include <string.h>
30 #include <time.h>
31 #include <chrono>
32 
33 namespace livox_ros {
34 
36 bool IsFilePathValid(const char *path_str) {
37  int str_len = strlen(path_str);
38 
39  if ((str_len > kPathStrMinSize) && (str_len < kPathStrMaxSize)) {
40  return true;
41  } else {
42  return false;
43  }
44 }
45 
46 uint64_t RawLdsStampToNs(LdsStamp &timestamp, uint8_t timestamp_type) {
47  if (timestamp_type == kTimestampTypePps) {
48  return timestamp.stamp;
49  } else if (timestamp_type == kTimestampTypeNoSync) {
50  return timestamp.stamp;
51  } else if (timestamp_type == kTimestampTypePtp) {
52  return timestamp.stamp;
53  } else if (timestamp_type == kTimestampTypePpsGps) {
54  struct tm time_utc;
55  time_utc.tm_isdst = 0;
56  time_utc.tm_year = timestamp.stamp_bytes[0] + 100; // map 2000 to 1990
57  time_utc.tm_mon = timestamp.stamp_bytes[1] - 1; // map 1~12 to 0~11
58  time_utc.tm_mday = timestamp.stamp_bytes[2];
59  time_utc.tm_hour = timestamp.stamp_bytes[3];
60  time_utc.tm_min = 0;
61  time_utc.tm_sec = 0;
62 
63  // uint64_t time_epoch = mktime(&time_utc);
64  uint64_t time_epoch = timegm(&time_utc); // no timezone
65  time_epoch = time_epoch * 1000000 + timestamp.stamp_word.high; // to us
66  time_epoch = time_epoch * 1000; // to ns
67 
68  return time_epoch;
69  } else {
70  printf("Timestamp type[%d] invalid.\n", timestamp_type);
71  return 0;
72  }
73 }
74 
76  LivoxEthPacket *raw_packet =
77  reinterpret_cast<LivoxEthPacket *>(packet->raw_data);
78  LdsStamp timestamp;
79  memcpy(timestamp.stamp_bytes, raw_packet->timestamp, sizeof(timestamp));
80 
81  if (raw_packet->timestamp_type == kTimestampTypePps) {
82  if (data_src != kSourceLvxFile) {
83  return (timestamp.stamp + packet->time_rcv);
84  } else {
85  return timestamp.stamp;
86  }
87  } else if (raw_packet->timestamp_type == kTimestampTypeNoSync) {
88  return timestamp.stamp;
89  } else if (raw_packet->timestamp_type == kTimestampTypePtp) {
90  return timestamp.stamp;
91  } else if (raw_packet->timestamp_type == kTimestampTypePpsGps) {
92  struct tm time_utc;
93  time_utc.tm_isdst = 0;
94  time_utc.tm_year = raw_packet->timestamp[0] + 100; // map 2000 to 1990
95  time_utc.tm_mon = raw_packet->timestamp[1] - 1; // map 1~12 to 0~11
96  time_utc.tm_mday = raw_packet->timestamp[2];
97  time_utc.tm_hour = raw_packet->timestamp[3];
98  time_utc.tm_min = 0;
99  time_utc.tm_sec = 0;
100 
101  // uint64_t time_epoch = mktime(&time_utc);
102  uint64_t time_epoch = timegm(&time_utc); // no timezone
103  time_epoch = time_epoch * 1000000 + timestamp.stamp_word.high; // to us
104  time_epoch = time_epoch * 1000; // to ns
105 
106  return time_epoch;
107  } else {
108  printf("Timestamp type[%d] invalid.\n", raw_packet->timestamp_type);
109  return 0;
110  }
111 }
112 
114  uint8_t data_type) {
115  uint32_t queue_size =
116  (interval_ms * GetPacketNumPerSec(product_type, data_type)) / 1000;
117 
118  queue_size = queue_size * 2;
119  if (queue_size < kMinEthPacketQueueSize) {
120  queue_size = kMinEthPacketQueueSize;
121  } else if (queue_size > kMaxEthPacketQueueSize) {
122  queue_size = kMaxEthPacketQueueSize;
123  }
124 
125  return queue_size;
126 }
127 
128 void ParseCommandlineInputBdCode(const char *cammandline_str,
129  std::vector<std::string> &bd_code_list) {
130  char *strs = new char[strlen(cammandline_str) + 1];
131  strcpy(strs, cammandline_str);
132 
133  std::string pattern = "&";
134  char *bd_str = strtok(strs, pattern.c_str());
135  std::string invalid_bd = "000000000";
136  while (bd_str != NULL) {
137  printf("Commandline input bd:%s\n", bd_str);
138  if ((kBdCodeSize == strlen(bd_str)) &&
139  (NULL == strstr(bd_str, invalid_bd.c_str()))) {
140  bd_code_list.push_back(bd_str);
141  } else {
142  printf("Invalid bd:%s!\n", bd_str);
143  }
144  bd_str = strtok(NULL, pattern.c_str());
145  }
146 
147  delete[] strs;
148 }
149 
151  double cos_roll = cos(static_cast<double>(euler[0]));
152  double cos_pitch = cos(static_cast<double>(euler[1]));
153  double cos_yaw = cos(static_cast<double>(euler[2]));
154  double sin_roll = sin(static_cast<double>(euler[0]));
155  double sin_pitch = sin(static_cast<double>(euler[1]));
156  double sin_yaw = sin(static_cast<double>(euler[2]));
157 
158  matrix[0][0] = cos_pitch * cos_yaw;
159  matrix[0][1] = sin_roll * sin_pitch * cos_yaw - cos_roll * sin_yaw;
160  matrix[0][2] = cos_roll * sin_pitch * cos_yaw + sin_roll * sin_yaw;
161 
162  matrix[1][0] = cos_pitch * sin_yaw;
163  matrix[1][1] = sin_roll * sin_pitch * sin_yaw + cos_roll * cos_yaw;
164  matrix[1][2] = cos_roll * sin_pitch * sin_yaw - sin_roll * cos_yaw;
165 
166  matrix[2][0] = -sin_pitch;
167  matrix[2][1] = sin_roll * cos_pitch;
168  matrix[2][2] = cos_roll * cos_pitch;
169 
170  /*
171  float rotate[3][3] = {
172  {
173  std::cos(info.pitch) * std::cos(info.yaw),
174  std::sin(info.roll) * std::sin(info.pitch) * std::cos(info.yaw) -
175  std::cos(info.roll) * std::sin(info.yaw), std::cos(info.roll) *
176  std::sin(info.pitch) * std::cos(info.yaw) + std::sin(info.roll) *
177  std::sin(info.yaw) },
178  {
179  std::cos(info.pitch) * std::sin(info.yaw),
180  std::sin(info.roll) * std::sin(info.pitch) * std::sin(info.yaw) +
181  std::cos(info.roll) * std::cos(info.yaw), std::cos(info.roll) *
182  std::sin(info.pitch) * std::sin(info.yaw) - std::sin(info.roll) *
183  std::cos(info.yaw) },
184  {
185  -std::sin(info.pitch),
186  std::sin(info.roll) * std::cos(info.pitch),
187  std::cos(info.roll) * std::cos(info.pitch)
188  }
189  };
190  */
191 }
192 
193 void PointExtrisincCompensation(PointXyz *dst_point, const PointXyz &src_point,
194  ExtrinsicParameter &extrinsic) {
195  dst_point->x = src_point.x * extrinsic.rotation[0][0] +
196  src_point.y * extrinsic.rotation[0][1] +
197  src_point.z * extrinsic.rotation[0][2] + extrinsic.trans[0];
198  dst_point->y = src_point.x * extrinsic.rotation[1][0] +
199  src_point.y * extrinsic.rotation[1][1] +
200  src_point.z * extrinsic.rotation[1][2] + extrinsic.trans[1];
201  dst_point->z = src_point.x * extrinsic.rotation[2][0] +
202  src_point.y * extrinsic.rotation[2][1] +
203  src_point.z * extrinsic.rotation[2][2] + extrinsic.trans[2];
204 }
205 
208 uint8_t *LivoxPointToPxyzrtl(uint8_t *point_buf, LivoxEthPacket *eth_packet,
209  ExtrinsicParameter &extrinsic, uint32_t line_num) {
210  LivoxPointXyzrtl *dst_point = (LivoxPointXyzrtl *)point_buf;
211  uint32_t points_per_packet = GetPointsPerPacket(eth_packet->data_type);
212  LivoxPoint *raw_point = reinterpret_cast<LivoxPoint *>(eth_packet->data);
213 
214  while (points_per_packet) {
215  RawPointConvert((LivoxPointXyzr *)dst_point, raw_point);
216  if (extrinsic.enable && IsTripleFloatNoneZero(raw_point->x,
217  raw_point->y, raw_point->z)) {
218  PointXyz src_point = *((PointXyz *)dst_point);
219  PointExtrisincCompensation((PointXyz *)dst_point, src_point, extrinsic);
220  }
221  dst_point->tag = 0;
222  dst_point->line = 0;
223  ++raw_point;
224  ++dst_point;
225  --points_per_packet;
226  }
227 
228  return (uint8_t *)dst_point;
229 }
230 
231 static uint8_t *LivoxRawPointToPxyzrtl(uint8_t *point_buf, LivoxEthPacket *eth_packet,
232  ExtrinsicParameter &extrinsic, uint32_t line_num) {
233  LivoxPointXyzrtl *dst_point = (LivoxPointXyzrtl *)point_buf;
234  uint32_t points_per_packet = GetPointsPerPacket(eth_packet->data_type);
235  LivoxRawPoint *raw_point =
236  reinterpret_cast<LivoxRawPoint *>(eth_packet->data);
237 
238  while (points_per_packet) {
239  RawPointConvert((LivoxPointXyzr *)dst_point, raw_point);
240  if (extrinsic.enable && IsTripleIntNoneZero(raw_point->x,
241  raw_point->y, raw_point->z)) {
242  PointXyz src_point = *((PointXyz *)dst_point);
243  PointExtrisincCompensation((PointXyz *)dst_point, src_point, extrinsic);
244  }
245  dst_point->tag = 0;
246  dst_point->line = 0;
247  ++raw_point;
248  ++dst_point;
249  --points_per_packet;
250  }
251 
252  return (uint8_t *)dst_point;
253 }
254 
256  LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, \
257  uint32_t line_num) {
258  LivoxPointXyzrtl *dst_point = (LivoxPointXyzrtl *)point_buf;
259  uint32_t points_per_packet = GetPointsPerPacket(eth_packet->data_type);
260  LivoxSpherPoint *raw_point =
261  reinterpret_cast<LivoxSpherPoint *>(eth_packet->data);
262 
263  while (points_per_packet) {
264  RawPointConvert((LivoxPointXyzr *)dst_point, raw_point);
265  if (extrinsic.enable && raw_point->depth) {
266  PointXyz src_point = *((PointXyz *)dst_point);
267  PointExtrisincCompensation((PointXyz *)dst_point, src_point, extrinsic);
268  }
269  dst_point->tag = 0;
270  dst_point->line = 0;
271  ++raw_point;
272  ++dst_point;
273  --points_per_packet;
274  }
275 
276  return (uint8_t *)dst_point;
277 }
278 
280  LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, \
281  uint32_t line_num) {
282  LivoxPointXyzrtl *dst_point = (LivoxPointXyzrtl *)point_buf;
283  uint32_t points_per_packet = GetPointsPerPacket(eth_packet->data_type);
284  LivoxExtendRawPoint *raw_point =
285  reinterpret_cast<LivoxExtendRawPoint *>(eth_packet->data);
286 
287  uint8_t line_id = 0;
288  while (points_per_packet) {
289  RawPointConvert((LivoxPointXyzr *)dst_point, (LivoxRawPoint *)raw_point);
290  if (extrinsic.enable && IsTripleIntNoneZero(raw_point->x,
291  raw_point->y, raw_point->z)) {
292  PointXyz src_point = *((PointXyz *)dst_point);
293  PointExtrisincCompensation((PointXyz *)dst_point, src_point, extrinsic);
294  }
295  dst_point->tag = raw_point->tag;
296  if (line_num > 1) {
297  dst_point->line = line_id % line_num;
298  } else {
299  dst_point->line = 0;
300  }
301  ++raw_point;
302  ++dst_point;
303  ++line_id;
304  --points_per_packet;
305  }
306 
307  return (uint8_t *)dst_point;
308 }
309 
311  LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, \
312  uint32_t line_num) {
313  LivoxPointXyzrtl *dst_point = (LivoxPointXyzrtl *)point_buf;
314  uint32_t points_per_packet = GetPointsPerPacket(eth_packet->data_type);
315  LivoxExtendSpherPoint *raw_point =
316  reinterpret_cast<LivoxExtendSpherPoint *>(eth_packet->data);
317 
318  uint8_t line_id = 0;
319  while (points_per_packet) {
320  RawPointConvert((LivoxPointXyzr *)dst_point, (LivoxSpherPoint *)raw_point);
321  if (extrinsic.enable && raw_point->depth) {
322  PointXyz src_point = *((PointXyz *)dst_point);
323  PointExtrisincCompensation((PointXyz *)dst_point, src_point, extrinsic);
324  }
325  dst_point->tag = raw_point->tag;
326  if (line_num > 1) {
327  dst_point->line = line_id % line_num;
328  } else {
329  dst_point->line = 0;
330  }
331  ++raw_point;
332  ++dst_point;
333  ++line_id;
334  --points_per_packet;
335  }
336 
337  return (uint8_t *)dst_point;
338 }
339 
341  LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, \
342  uint32_t line_num) {
343  LivoxPointXyzrtl *dst_point = (LivoxPointXyzrtl *)point_buf;
344  uint32_t points_per_packet = GetPointsPerPacket(eth_packet->data_type);
345  LivoxExtendRawPoint *raw_point =
346  reinterpret_cast<LivoxExtendRawPoint *>(eth_packet->data);
347 
348  /* LivoxDualExtendRawPoint = 2*LivoxExtendRawPoint */
349  points_per_packet = points_per_packet * 2;
350  uint8_t line_id = 0;
351  while (points_per_packet) {
352  RawPointConvert((LivoxPointXyzr *)dst_point, (LivoxRawPoint *)raw_point);
353  if (extrinsic.enable && IsTripleIntNoneZero(raw_point->x,
354  raw_point->y, raw_point->z)) {
355  PointXyz src_point = *((PointXyz *)dst_point);
356  PointExtrisincCompensation((PointXyz *)dst_point, src_point, extrinsic);
357  }
358  dst_point->tag = raw_point->tag;
359  if (line_num > 1) {
360  dst_point->line = (line_id / 2) % line_num;
361  } else {
362  dst_point->line = 0;
363  }
364  ++raw_point;
365  ++dst_point;
366  ++line_id;
367  --points_per_packet;
368  }
369 
370  return (uint8_t *)dst_point;
371 }
372 
374  LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, \
375  uint32_t line_num) {
376  LivoxPointXyzrtl *dst_point = (LivoxPointXyzrtl *)point_buf;
377  uint32_t points_per_packet = GetPointsPerPacket(eth_packet->data_type);
378  LivoxDualExtendSpherPoint *raw_point =
379  reinterpret_cast<LivoxDualExtendSpherPoint *>(eth_packet->data);
380 
381  uint8_t line_id = 0;
382  while (points_per_packet) {
383  RawPointConvert((LivoxPointXyzr *)dst_point,
384  (LivoxPointXyzr *)(dst_point + 1),
385  (LivoxDualExtendSpherPoint *)raw_point);
386  if (extrinsic.enable && raw_point->depth1) {
387  PointXyz src_point = *((PointXyz *)dst_point);
388  PointExtrisincCompensation((PointXyz *)dst_point, src_point, extrinsic);
389  }
390  dst_point->tag = raw_point->tag1;
391  if (line_num > 1) {
392  dst_point->line = line_id % line_num;
393  } else {
394  dst_point->line = 0;
395  }
396  ++dst_point;
397 
398  if (extrinsic.enable && raw_point->depth2) {
399  PointXyz src_point = *((PointXyz *)dst_point);
400  PointExtrisincCompensation((PointXyz *)dst_point, src_point, extrinsic);
401  }
402  dst_point->tag = raw_point->tag2;
403  if (line_num > 1) {
404  dst_point->line = line_id % line_num;
405  } else {
406  dst_point->line = 0;
407  }
408  ++dst_point;
409 
410  ++raw_point; /* only increase one */
411  ++line_id;
412  --points_per_packet;
413  }
414 
415  return (uint8_t *)dst_point;
416 }
417 
419  LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, \
420  uint32_t line_num) {
421  LivoxPointXyzrtl *dst_point = (LivoxPointXyzrtl *)point_buf;
422  uint32_t points_per_packet = GetPointsPerPacket(eth_packet->data_type);
423  LivoxExtendRawPoint *raw_point =
424  reinterpret_cast<LivoxExtendRawPoint *>(eth_packet->data);
425 
426  /* LivoxTripleExtendRawPoint = 3*LivoxExtendRawPoint, echo_num */
427  points_per_packet = points_per_packet * 3;
428  uint8_t line_id = 0;
429  while (points_per_packet) {
430  RawPointConvert((LivoxPointXyzr *)dst_point, (LivoxRawPoint *)raw_point);
431  if (extrinsic.enable && IsTripleIntNoneZero(raw_point->x,
432  raw_point->y, raw_point->z)) {
433  PointXyz src_point = *((PointXyz *)dst_point);
434  PointExtrisincCompensation((PointXyz *)dst_point, src_point, extrinsic);
435  }
436  dst_point->tag = raw_point->tag;
437  if (line_num > 1) {
438  dst_point->line = (line_id / 3) % line_num;
439  } else {
440  dst_point->line = 0;
441  }
442  ++raw_point;
443  ++dst_point;
444  ++line_id;
445  --points_per_packet;
446  }
447 
448  return (uint8_t *)dst_point;
449 }
450 
452  LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, \
453  uint32_t line_num) {
454  LivoxPointXyzrtl *dst_point = (LivoxPointXyzrtl *)point_buf;
455  uint32_t points_per_packet = GetPointsPerPacket(eth_packet->data_type);
456  LivoxTripleExtendSpherPoint *raw_point =
457  reinterpret_cast<LivoxTripleExtendSpherPoint *>(eth_packet->data);
458 
459  uint8_t line_id = 0;
460  while (points_per_packet) {
461  RawPointConvert((LivoxPointXyzr *)dst_point,
462  (LivoxPointXyzr *)(dst_point + 1),
463  (LivoxPointXyzr *)(dst_point + 2),
464  (LivoxTripleExtendSpherPoint *)raw_point);
465  if (extrinsic.enable && raw_point->depth1) {
466  PointXyz src_point = *((PointXyz *)dst_point);
467  PointExtrisincCompensation((PointXyz *)dst_point, src_point, extrinsic);
468  }
469  dst_point->tag = raw_point->tag1;
470  if (line_num > 1) {
471  dst_point->line = line_id % line_num;
472  } else {
473  dst_point->line = 0;
474  }
475  ++dst_point;
476 
477  if (extrinsic.enable && raw_point->depth2) {
478  PointXyz src_point = *((PointXyz *)dst_point);
479  PointExtrisincCompensation((PointXyz *)dst_point, src_point, extrinsic);
480  }
481  dst_point->tag = raw_point->tag2;
482  if (line_num > 1) {
483  dst_point->line = line_id % line_num;
484  } else {
485  dst_point->line = 0;
486  }
487  ++dst_point;
488 
489  if (extrinsic.enable && raw_point->depth3) {
490  PointXyz src_point = *((PointXyz *)dst_point);
491  PointExtrisincCompensation((PointXyz *)dst_point, src_point, extrinsic);
492  }
493  dst_point->tag = raw_point->tag3;
494  if (line_num > 1) {
495  dst_point->line = line_id % line_num;
496  } else {
497  dst_point->line = 0;
498  }
499  ++dst_point;
500 
501  ++raw_point; /* only increase one */
502  ++line_id;
503  --points_per_packet;
504  }
505 
506  return (uint8_t *)dst_point;
507 }
508 
509 uint8_t *LivoxImuDataProcess(uint8_t *point_buf, LivoxEthPacket *eth_packet) {
510  memcpy(point_buf, eth_packet->data, sizeof(LivoxImuPoint));
511  return point_buf;
512 }
513 
514 const PointConvertHandler to_pxyzi_handler_table[kMaxPointDataType] = {
521  nullptr,
524  };
525 
527  if (data_type < kMaxPointDataType)
528  return to_pxyzi_handler_table[data_type];
529  else
530  return nullptr;
531 }
532 
534  LivoxEthPacket *raw_packet =
535  reinterpret_cast<LivoxEthPacket *>(storage_packet->raw_data);
536  uint32_t point_length = GetPointLen(raw_packet->data_type);
537  memset(raw_packet->data, 0, point_length * storage_packet->point_num);
538 }
539 
540 #if 0
541 
542 static void PointCloudConvert(LivoxPoint *p_dpoint, LivoxRawPoint *p_raw_point) {
543  p_dpoint->x = p_raw_point->x/1000.0f;
544  p_dpoint->y = p_raw_point->y/1000.0f;
545  p_dpoint->z = p_raw_point->z/1000.0f;
546  p_dpoint->reflectivity = p_raw_point->reflectivity;
547 }
548 
549 #endif
550 
551 /* Member function --------------------------------------------------------- */
552 Lds::Lds(uint32_t buffer_time_ms, uint8_t data_src) : \
553  lidar_count_(kMaxSourceLidar), semaphore_(0), \
554  buffer_time_ms_(buffer_time_ms), data_src_(data_src), request_exit_(false) {
556 };
557 
559  lidar_count_ = 0;
560  ResetLds(0);
561 };
562 
563 void Lds::ResetLidar(LidarDevice *lidar, uint8_t data_src) {
564  DeInitQueue(&lidar->data);
565  DeInitQueue(&lidar->imu_data);
566 
567  memset(lidar, 0, sizeof(LidarDevice));
568 
570  lidar->handle = kMaxSourceLidar;
571  lidar->data_src = data_src;
572  lidar->data_is_pubulished = false;
574  lidar->raw_data_type = 0xFF;
575 }
576 
577 void Lds::SetLidarDataSrc(LidarDevice *lidar, uint8_t data_src) {
578  lidar->data_src = data_src;
579 }
580 
581 void Lds::ResetLds(uint8_t data_src) {
583  for (uint32_t i = 0; i < kMaxSourceLidar; i++) {
584  ResetLidar(&lidars_[i], data_src);
585  }
586 }
587 
589  request_exit_ = true;
590 }
591 
593  for (int i = 0; i < lidar_count_; i++) {
594  if (!QueueIsEmpty(&lidars_[i].data)) {
595  return false;
596  }
597  }
598 
599  return true;
600 }
601 
603  for (int i = 0; i < lidar_count_; i++) {
604  uint32_t data_size = QueueUsedSize(&lidars_[i].data);
605  if (data_size && (data_size > lidars_[i].onetime_publish_packets)) {
606  return false;
607  }
608  }
609 
610  return true;
611 }
612 
614  if (handle < kMaxSourceLidar) {
615  return lidars_[handle].info.type;
616  } else {
617  return kDeviceTypeHub;
618  }
619 }
620 
622  LivoxEthPacket* eth_packet) {
623  if (p_lidar->raw_data_type != eth_packet->data_type) {
624  p_lidar->raw_data_type = eth_packet->data_type;
625  p_lidar->packet_interval = GetPacketInterval(p_lidar->info.type, \
626  eth_packet->data_type);
627  p_lidar->packet_interval_max = p_lidar->packet_interval * 1.8f;
628  p_lidar->onetime_publish_packets = \
629  GetPacketNumPerSec(p_lidar->info.type, \
630  p_lidar->raw_data_type) * buffer_time_ms_ / 1000;
631  printf("Lidar[%d][%s] DataType[%d] PacketInterval[%d] PublishPackets[%d]\n",
632  p_lidar->handle, p_lidar->info.broadcast_code, p_lidar->raw_data_type,
633  p_lidar->packet_interval, p_lidar->onetime_publish_packets);
634  }
635 }
636 
637 void Lds::StorageRawPacket(uint8_t handle, LivoxEthPacket* eth_packet) {
638  LidarDevice *p_lidar = &lidars_[handle];
639  LidarPacketStatistic *packet_statistic = &p_lidar->statistic_info;
640  LdsStamp cur_timestamp;
641  uint64_t timestamp;
642 
643  memcpy(cur_timestamp.stamp_bytes, eth_packet->timestamp,
644  sizeof(cur_timestamp));
645  timestamp = RawLdsStampToNs(cur_timestamp, eth_packet->timestamp_type);
646  if (timestamp >= kRosTimeMax) {
647  printf("Raw EthPacket time out of range Lidar[%d]\n", handle);
648  return;
649  }
650 
651  if (kImu != eth_packet->data_type) {
652  UpdateLidarInfoByEthPacket(p_lidar, eth_packet);
653  if (eth_packet->timestamp_type == kTimestampTypePps) {
655  if ((cur_timestamp.stamp < packet_statistic->last_timestamp) &&
656  (cur_timestamp.stamp < kPacketTimeGap)) {
657  auto cur_time = std::chrono::high_resolution_clock::now();
658  int64_t sync_time = cur_time.time_since_epoch().count();
660  packet_statistic->timebase = sync_time;
661  }
662  }
663  packet_statistic->last_timestamp = cur_timestamp.stamp;
664 
665  LidarDataQueue *p_queue = &p_lidar->data;
666  if (nullptr == p_queue->storage_packet) {
667  uint32_t queue_size = CalculatePacketQueueSize(
668  buffer_time_ms_, p_lidar->info.type, eth_packet->data_type);
669  InitQueue(p_queue, queue_size);
670  printf("Lidar[%d][%s] storage queue size : %d %d\n", p_lidar->handle,
671  p_lidar->info.broadcast_code, queue_size, p_queue->size);
672  }
673  if (!QueueIsFull(p_queue)) {
674  QueuePushAny(p_queue, (uint8_t *)eth_packet,
675  GetEthPacketLen(eth_packet->data_type),
676  packet_statistic->timebase,
677  GetPointsPerPacket(eth_packet->data_type));
678  if (QueueUsedSize(p_queue) > p_lidar->onetime_publish_packets) {
679  if (semaphore_.GetCount() <= 0) {
680  semaphore_.Signal();
681  }
682  }
683  }
684  } else {
685  if (eth_packet->timestamp_type == kTimestampTypePps) {
687  if ((cur_timestamp.stamp < packet_statistic->last_imu_timestamp) &&
688  (cur_timestamp.stamp < kPacketTimeGap)) {
689  auto cur_time = std::chrono::high_resolution_clock::now();
690  int64_t sync_time = cur_time.time_since_epoch().count();
692  packet_statistic->imu_timebase = sync_time;
693  }
694  }
695  packet_statistic->last_imu_timestamp = cur_timestamp.stamp;
696 
697  LidarDataQueue *p_queue = &p_lidar->imu_data;
698  if (nullptr == p_queue->storage_packet) {
699  uint32_t queue_size = 256; /* fixed imu data queue size */
700  InitQueue(p_queue, queue_size);
701  printf("Lidar[%d][%s] imu storage queue size : %d %d\n", p_lidar->handle,
702  p_lidar->info.broadcast_code, queue_size, p_queue->size);
703  }
704  if (!QueueIsFull(p_queue)) {
705  QueuePushAny(p_queue, (uint8_t *)eth_packet,
706  GetEthPacketLen(eth_packet->data_type),
707  packet_statistic->imu_timebase,
708  GetPointsPerPacket(eth_packet->data_type));
709  }
710  }
711 }
712 
713 void Lds::PrepareExit(void) {}
714 
715 } // namespace livox_ros
TranslationVector trans
Definition: lds.h:166
DeviceInfo info
Definition: lds.h:185
bool IsFilePathValid(const char *path_str)
Definition: lds.cpp:36
const uint32_t kMaxEthPacketQueueSize
Definition: lds.h:51
const int kBdCodeSize
Definition: lds.h:69
const uint32_t kMaxSourceLidar
Definition: lds.h:46
uint8_t lidar_count_
Definition: lds.h:445
float EulerAngle[3]
Definition: lds.h:160
LidarDataQueue data
Definition: lds.h:187
bool IsTripleFloatNoneZero(float x, float y, float z)
Definition: lds.h:393
int64_t stamp
Definition: lds.h:134
uint8_t raw_data[KEthPacketMaxLength]
Definition: ldq.h:41
uint32_t buffer_time_ms_
Definition: lds.h:450
Semaphore semaphore_
Definition: lds.h:447
void ParseCommandlineInputBdCode(const char *cammandline_str, std::vector< std::string > &bd_code_list)
Definition: lds.cpp:128
Lds(uint32_t buffer_time_ms, uint8_t data_src)
Definition: lds.cpp:552
uint32_t QueueIsFull(LidarDataQueue *queue)
Definition: ldq.cpp:101
float RotationMatrix[3][3]
Definition: lds.h:162
uint32_t GetPointsPerPacket(uint32_t data_type)
Definition: lds.h:304
uint8_t * LivoxImuDataProcess(uint8_t *point_buf, LivoxEthPacket *eth_packet)
Definition: lds.cpp:509
unsigned char uint8_t
Definition: stdint.h:125
struct livox_ros::LdsStamp::@14 stamp_word
uint8_t stamp_bytes[8]
Definition: lds.h:133
uint8_t *(* PointConvertHandler)(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
Definition: lds.h:233
void ZeroPointDataOfStoragePacket(StoragePacket *storage_packet)
Definition: lds.cpp:533
static uint8_t * LivoxRawPointToPxyzrtl(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
Definition: lds.cpp:231
bool IsAllQueueEmpty()
Definition: lds.cpp:592
static uint8_t * LivoxTripleExtendSpherPointToPxyzrtl(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
Definition: lds.cpp:451
LidarDataQueue imu_data
Definition: lds.h:188
static void ResetLidar(LidarDevice *lidar, uint8_t data_src)
Definition: lds.cpp:563
uint32_t high
Definition: lds.h:130
static uint8_t * LivoxExtendSpherPointToPxyzrtl(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
Definition: lds.cpp:310
unsigned int uint32_t
Definition: stdint.h:127
uint32_t GetPacketNumPerSec(uint32_t product_type, uint32_t data_type)
Definition: lds.h:290
uint32_t QueuePushAny(LidarDataQueue *queue, uint8_t *data, uint32_t length, uint64_t time_rcv, uint32_t point_num)
Definition: ldq.cpp:120
uint8_t data_src_
Definition: lds.h:451
uint8_t GetDeviceType(uint8_t handle)
Definition: lds.cpp:613
void PointExtrisincCompensation(PointXyz *dst_point, const PointXyz &src_point, ExtrinsicParameter &extrinsic)
Definition: lds.cpp:193
volatile bool request_exit_
Definition: lds.h:454
bool IsAllQueueReadStop()
Definition: lds.cpp:602
uint64_t GetStoragePacketTimestamp(StoragePacket *packet, uint8_t data_src)
Definition: lds.cpp:75
static uint8_t * LivoxDualExtendSpherPointToPxyzrtl(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
Definition: lds.cpp:373
unsigned __int64 uint64_t
Definition: stdint.h:137
virtual void PrepareExit(void)
Definition: lds.cpp:713
const int64_t kPacketTimeGap
Definition: lds.h:60
const uint64_t kRosTimeMax
Definition: lds.h:59
void RawPointConvert(LivoxPointXyzr *dst_point, LivoxPoint *raw_point)
Definition: lds.h:320
uint32_t point_num
Definition: ldq.h:40
uint32_t QueueUsedSize(LidarDataQueue *queue)
Definition: ldq.cpp:93
uint64_t time_rcv
Definition: ldq.h:39
uint8_t raw_data_type
Definition: lds.h:175
uint8_t data_src
Definition: lds.h:174
LidarPacketStatistic statistic_info
Definition: lds.h:186
int InitQueue(LidarDataQueue *queue, uint32_t queue_size)
Definition: ldq.cpp:33
bool data_is_pubulished
Definition: lds.h:176
volatile uint32_t packet_interval
Definition: lds.h:178
uint32_t GetPacketInterval(uint32_t product_type, uint32_t data_type)
Definition: lds.h:295
RotationMatrix rotation
Definition: lds.h:167
StoragePacket * storage_packet
Definition: ldq.h:47
virtual ~Lds()
Definition: lds.cpp:558
uint32_t QueueIsEmpty(LidarDataQueue *queue)
Definition: ldq.cpp:105
void StorageRawPacket(uint8_t handle, LivoxEthPacket *eth_packet)
Definition: lds.cpp:637
uint64_t RawLdsStampToNs(LdsStamp &timestamp, uint8_t timestamp_type)
Definition: lds.cpp:46
const int kPathStrMaxSize
Definition: lds.h:68
static uint8_t * LivoxDualExtendRawPointToPxyzrtl(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
Definition: lds.cpp:340
static uint8_t * LivoxSpherPointToPxyzrtl(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
Definition: lds.cpp:255
signed __int64 int64_t
Definition: stdint.h:136
void UpdateLidarInfoByEthPacket(LidarDevice *p_lidar, LivoxEthPacket *eth_packet)
Definition: lds.cpp:621
const int kPathStrMinSize
Definition: lds.h:67
void RequestExit()
Definition: lds.cpp:588
void EulerAnglesToRotationMatrix(EulerAngle euler, RotationMatrix matrix)
Definition: lds.cpp:150
static uint8_t * LivoxTripleExtendRawPointToPxyzrtl(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
Definition: lds.cpp:418
static uint8_t * LivoxExtendRawPointToPxyzrtl(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
Definition: lds.cpp:279
int DeInitQueue(LidarDataQueue *queue)
Definition: ldq.cpp:55
void ResetLds(uint8_t data_src)
Definition: lds.cpp:581
bool IsTripleIntNoneZero(int32_t x, int32_t y, int32_t z)
Definition: lds.h:389
const uint32_t kMinEthPacketQueueSize
Definition: lds.h:50
const PointConvertHandler to_pxyzi_handler_table[kMaxPointDataType]
Definition: lds.cpp:514
uint8_t * LivoxPointToPxyzrtl(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
Definition: lds.cpp:208
LidarDevice lidars_[kMaxSourceLidar]
Definition: lds.h:446
int GetCount()
Definition: lds.h:414
volatile uint32_t onetime_publish_packets
Definition: lds.h:183
uint32_t GetEthPacketLen(uint32_t data_type)
Definition: lds.h:308
PointConvertHandler GetConvertHandler(uint8_t data_type)
Definition: lds.cpp:526
void Signal()
Definition: lds.h:402
static void SetLidarDataSrc(LidarDevice *lidar, uint8_t data_src)
Definition: lds.cpp:577
uint32_t CalculatePacketQueueSize(uint32_t interval_ms, uint8_t product_type, uint8_t data_type)
Definition: lds.cpp:113
volatile LidarConnectState connect_state
Definition: lds.h:184
volatile uint32_t packet_interval_max
Definition: lds.h:180
uint32_t GetPointLen(uint32_t data_type)
Definition: lds.h:312
uint8_t handle
Definition: lds.h:173


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