lds.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 
25 // livox lidar data source
26 
27 #ifndef LIVOX_ROS_DRIVER_LDS_H_
28 #define LIVOX_ROS_DRIVER_LDS_H_
29 
30 #include <math.h>
31 #include <stdint.h>
32 #include <stdio.h>
33 #include <stdlib.h>
34 #include <string>
35 #include <vector>
36 #include <mutex>
37 #include <condition_variable>
38 
39 #include "ldq.h"
40 
41 #include "livox_def.h"
42 
43 namespace livox_ros {
44 
47 
53 
55 // const uint32_t KEthPacketMaxLength = 1500;
58 
59 const uint64_t kRosTimeMax = 4294967296000000000;
60 const int64_t kPacketTimeGap = 1000000;
62 const int64_t kMaxPacketTimeGap = 1700000;
65 const int64_t kNsPerSecond = 1000000000;
67 const int kPathStrMinSize = 4;
68 const int kPathStrMaxSize = 256;
69 const int kBdCodeSize = 15;
70 
73 
74 const double PI = 3.14159265358979323846;
75 
77 typedef enum {
83 
85 typedef enum {
91 
93 typedef enum {
97 
99 
100 typedef enum {
101  kConfigFan = 1 << 0,
104  kConfigImuRate = 1 << 3,
109 
110 typedef enum {
115 
116 typedef struct {
125 
127 typedef union {
128  struct {
131  } stamp_word;
132 
133  uint8_t stamp_bytes[8];
135 } LdsStamp;
136 
138 typedef struct {
139  char broadcast_code[16];
147 } UserRawConfig;
148 
149 typedef struct {
156  volatile uint32_t set_bits;
157  volatile uint32_t get_bits;
158 } UserConfig;
159 
160 typedef float EulerAngle[3];
161 typedef float TranslationVector[3];
162 typedef float RotationMatrix[3][3];
163 
164 typedef struct {
165  EulerAngle euler;
166  TranslationVector trans;
167  RotationMatrix rotation;
168  bool enable;
170 
172 typedef struct {
185  DeviceInfo info;
192 } LidarDevice;
193 
194 typedef struct {
200 
201 typedef struct {
206 
207 #pragma pack(1)
208 
209 typedef struct {
210  float x;
211  float y;
212  float z;
213 } PointXyz;
214 
215 typedef struct {
216  float x;
217  float y;
218  float z;
219  float reflectivity;
221 
222 typedef struct {
223  float x;
224  float y;
225  float z;
226  float reflectivity;
230 
231 #pragma pack()
232 
233 typedef uint8_t *(*PointConvertHandler)(uint8_t *point_buf, \
234  LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, \
235  uint32_t line_num);
236 
238  {100, 1318, sizeof(LivoxRawPoint), 1},
239  {100, 918, 9, 1},
240  {96, 1362, 14, 1},
241  {96, 978, 9, 1},
242  {48, 1362, sizeof(LivoxDualExtendRawPoint), 2},
243  {48, 786, sizeof(LivoxDualExtendSpherPoint), 2},
244  {1, 42, sizeof(LivoxImuPoint), 1},
245  {30, 1278, sizeof(LivoxTripleExtendRawPoint), 3},
246  {30, 678, sizeof(LivoxTripleExtendSpherPoint), 3}};
247 
251  {100000, 10000, 1},
252  {100000, 10000, 1},
253  {240000, 4167 , 6},
254  {240000, 4167 , 6},
255  {100000, 10000, 1},
256  {100000, 10000, 1},
257  {100000, 10000, 1},
258  {240000, 4167, 6},
259  {240000, 4167, 6},
260 };
261 
265 bool IsFilePathValid(const char *path_str);
266 uint64_t RawLdsStampToNs(LdsStamp &timestamp, uint8_t timestamp_type);
268 uint32_t CalculatePacketQueueSize(uint32_t interval_ms, uint8_t product_type,
269  uint8_t data_type);
270 void ParseCommandlineInputBdCode(const char *cammandline_str,
271  std::vector<std::string> &bd_code_list);
273 uint8_t *LivoxPointToPxyzrtl(uint8_t *point_buf, LivoxEthPacket *eth_packet,
274  ExtrinsicParameter &extrinsic, uint32_t line_num);
275 void ZeroPointDataOfStoragePacket(StoragePacket* storage_packet);
276 uint8_t *LivoxImuDataProcess(uint8_t *point_buf, LivoxEthPacket *eth_packet);
277 void EulerAnglesToRotationMatrix(EulerAngle euler, RotationMatrix matrix);
278 void PointExtrisincCompensation(PointXyz *dst_point,
279  ExtrinsicParameter &extrinsic);
280 
281 inline uint32_t GetPointInterval(uint32_t product_type) {
282  return product_type_info_pair_table[product_type].point_interval;
283 }
284 
285 // inline uint32_t GetPacketNumPerSec(uint32_t data_type) {
286 // return packet_info_pair_table[data_type].points_per_second /
287 // packet_info_pair_table[data_type].points_per_packet;
288 //}
289 
290 inline uint32_t GetPacketNumPerSec(uint32_t product_type, uint32_t data_type) {
291  return product_type_info_pair_table[product_type].points_per_second /
292  data_type_info_pair_table[data_type].points_per_packet;
293 }
294 
295 inline uint32_t GetPacketInterval(uint32_t product_type, uint32_t data_type) {
296  return product_type_info_pair_table[product_type].point_interval *
297  data_type_info_pair_table[data_type].points_per_packet;
298 }
299 
300 inline uint32_t GetLaserLineNumber(uint32_t product_type) {
301  return product_type_info_pair_table[product_type].line_num;
302 }
303 
305  return data_type_info_pair_table[data_type].points_per_packet;
306 }
307 
308 inline uint32_t GetEthPacketLen(uint32_t data_type) {
309  return data_type_info_pair_table[data_type].packet_length;
310 }
311 
312 inline uint32_t GetPointLen(uint32_t data_type) {
313  return data_type_info_pair_table[data_type].raw_point_length;
314 }
315 
317  return data_type_info_pair_table[data_type].echo_num;
318 }
319 
320 inline void RawPointConvert(LivoxPointXyzr *dst_point, LivoxPoint *raw_point) {
321  dst_point->x = raw_point->x;
322  dst_point->y = raw_point->y;
323  dst_point->z = raw_point->z;
324  dst_point->reflectivity = (float)raw_point->reflectivity;
325 }
326 
327 inline void RawPointConvert(LivoxPointXyzr *dst_point,
328  LivoxRawPoint *raw_point) {
329  dst_point->x = raw_point->x / 1000.0f;
330  dst_point->y = raw_point->y / 1000.0f;
331  dst_point->z = raw_point->z / 1000.0f;
332  dst_point->reflectivity = (float)raw_point->reflectivity;
333 }
334 
335 inline void RawPointConvert(LivoxPointXyzr *dst_point,
336  LivoxSpherPoint *raw_point) {
337  double radius = raw_point->depth / 1000.0;
338  double theta = raw_point->theta / 100.0 / 180 * PI;
339  double phi = raw_point->phi / 100.0 / 180 * PI;
340  dst_point->x = radius * sin(theta) * cos(phi);
341  dst_point->y = radius * sin(theta) * sin(phi);
342  dst_point->z = radius * cos(theta);
343  dst_point->reflectivity = (float)raw_point->reflectivity;
344 }
345 
346 inline void RawPointConvert(LivoxPointXyzr *dst_point1,
347  LivoxPointXyzr *dst_point2,
348  LivoxDualExtendSpherPoint *raw_point) {
349  double radius1 = raw_point->depth1 / 1000.0;
350  double radius2 = raw_point->depth2 / 1000.0;
351  double theta = raw_point->theta / 100.0 / 180 * PI;
352  double phi = raw_point->phi / 100.0 / 180 * PI;
353  dst_point1->x = radius1 * sin(theta) * cos(phi);
354  dst_point1->y = radius1 * sin(theta) * sin(phi);
355  dst_point1->z = radius1 * cos(theta);
356  dst_point1->reflectivity = (float)raw_point->reflectivity1;
357 
358  dst_point2->x = radius2 * sin(theta) * cos(phi);
359  dst_point2->y = radius2 * sin(theta) * sin(phi);
360  dst_point2->z = radius2 * cos(theta);
361  dst_point2->reflectivity = (float)raw_point->reflectivity2;
362 }
363 
364 inline void RawPointConvert(LivoxPointXyzr *dst_point1,
365  LivoxPointXyzr *dst_point2,
366  LivoxPointXyzr *dst_point3,
367  LivoxTripleExtendSpherPoint *raw_point) {
368  double radius1 = raw_point->depth1 / 1000.0;
369  double radius2 = raw_point->depth2 / 1000.0;
370  double radius3 = raw_point->depth3 / 1000.0;
371  double theta = raw_point->theta / 100.0 / 180 * PI;
372  double phi = raw_point->phi / 100.0 / 180 * PI;
373  dst_point1->x = radius1 * sin(theta) * cos(phi);
374  dst_point1->y = radius1 * sin(theta) * sin(phi);
375  dst_point1->z = radius1 * cos(theta);
376  dst_point1->reflectivity = (float)raw_point->reflectivity1;
377 
378  dst_point2->x = radius2 * sin(theta) * cos(phi);
379  dst_point2->y = radius2 * sin(theta) * sin(phi);
380  dst_point2->z = radius2 * cos(theta);
381  dst_point2->reflectivity = (float)raw_point->reflectivity2;
382 
383  dst_point3->x = radius3 * sin(theta) * cos(phi);
384  dst_point3->y = radius3 * sin(theta) * sin(phi);
385  dst_point3->z = radius3 * cos(theta);
386  dst_point3->reflectivity = (float)raw_point->reflectivity3;
387 }
388 
390  return (x | y | z);
391 }
392 
393 inline bool IsTripleFloatNoneZero(float x, float y, float z) {
394  return ((x != 0.0f) || (y != 0.0f) || (z != 0.0f));
395 }
396 
397 class Semaphore {
398  public:
399  explicit Semaphore(int count = 0) : count_(count) {
400  }
401 
402  void Signal() {
403  std::unique_lock<std::mutex> lock(mutex_);
404  ++count_;
405  cv_.notify_one();
406  }
407 
408  void Wait() {
409  std::unique_lock<std::mutex> lock(mutex_);
410  cv_.wait(lock, [=] { return count_ > 0; });
411  --count_;
412  }
413 
414  int GetCount() {
415  return count_;
416  }
417 
418  private:
419  std::mutex mutex_;
420  std::condition_variable cv_;
421  volatile int count_;
422 };
423 
427 class Lds {
428  public:
429  Lds(uint32_t buffer_time_ms, uint8_t data_src);
430  virtual ~Lds();
431 
432  void StorageRawPacket(uint8_t handle, LivoxEthPacket* eth_packet);
433  uint8_t GetDeviceType(uint8_t handle);
434  static void ResetLidar(LidarDevice *lidar, uint8_t data_src);
435  static void SetLidarDataSrc(LidarDevice *lidar, uint8_t data_src);
436  void ResetLds(uint8_t data_src);
437  void RequestExit();
438  bool IsAllQueueEmpty();
439  bool IsAllQueueReadStop();
440  void CleanRequestExit() { request_exit_ = false; }
441  bool IsRequestExit() { return request_exit_; }
442  virtual void PrepareExit(void);
443  void UpdateLidarInfoByEthPacket(LidarDevice *p_lidar, \
444  LivoxEthPacket* eth_packet);
448 
449  protected:
452 
453  private:
454  volatile bool request_exit_;
455 };
456 
457 } // namespace livox_ros
458 #endif
TranslationVector trans
Definition: lds.h:166
DeviceInfo info
Definition: lds.h:185
uint32_t GetPointInterval(uint32_t product_type)
Definition: lds.h:281
bool IsFilePathValid(const char *path_str)
Definition: lds.cpp:36
float TranslationVector[3]
Definition: lds.h:161
const double PI
Definition: lds.h:74
bool enable_high_sensitivity
Definition: lds.h:155
LidarConfigCodeBit
Definition: lds.h:100
const uint32_t kMaxEthPacketQueueSize
Definition: lds.h:51
const int kBdCodeSize
Definition: lds.h:69
const int64_t kDeviceDisconnectThreshold
Definition: lds.h:64
uint32_t imu_rate
Definition: lds.h:144
const uint32_t kMaxSourceLidar
Definition: lds.h:46
uint8_t lidar_count_
Definition: lds.h:445
const uint32_t kDeviceTypeLidarMid70
Definition: lds.h:249
float EulerAngle[3]
Definition: lds.h:160
uint32_t coordinate
Definition: lds.h:152
f
const uint32_t KEthPacketHeaderLength
Definition: lds.h:54
LidarDataQueue data
Definition: lds.h:187
const int64_t kMaxPacketTimeGap
Definition: lds.h:62
bool IsTripleFloatNoneZero(float x, float y, float z)
Definition: lds.h:393
int64_t stamp
Definition: lds.h:134
uint32_t buffer_time_ms_
Definition: lds.h:450
UserConfig config
Definition: lds.h:190
ExtrinsicParameter extrinsic_parameter
Definition: lds.h:191
uint32_t GetEchoNumPerPoint(uint32_t data_type)
Definition: lds.h:316
uint32_t GetLaserLineNumber(uint32_t product_type)
Definition: lds.h:300
Semaphore semaphore_
Definition: lds.h:447
const ProductTypePointInfoPair product_type_info_pair_table[kMaxProductType]
Definition: lds.h:250
void ParseCommandlineInputBdCode(const char *cammandline_str, std::vector< std::string > &bd_code_list)
Definition: lds.cpp:128
ExtrinsicParameterType
Definition: lds.h:110
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
uint32_t imu_rate
Definition: lds.h:153
unsigned char uint8_t
Definition: stdint.h:125
void CleanRequestExit()
Definition: lds.h:440
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
uint32_t return_mode
Definition: lds.h:142
volatile uint32_t get_bits
Definition: lds.h:157
const uint32_t kPointXYZRTRSize
Definition: lds.h:72
uint32_t firmware_ver
Definition: lds.h:189
bool enable_high_sensitivity
Definition: lds.h:146
LidarDataQueue imu_data
Definition: lds.h:188
uint32_t return_mode
Definition: lds.h:151
uint32_t extrinsic_parameter_source
Definition: lds.h:154
uint32_t extrinsic_parameter_source
Definition: lds.h:145
uint32_t high
Definition: lds.h:130
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 low
Definition: lds.h:129
const uint32_t kMaxPointPerEthPacket
Definition: lds.h:49
uint8_t data_src_
Definition: lds.h:451
void PointExtrisincCompensation(PointXyz *dst_point, const PointXyz &src_point, ExtrinsicParameter &extrinsic)
Definition: lds.cpp:193
volatile bool request_exit_
Definition: lds.h:454
uint64_t GetStoragePacketTimestamp(StoragePacket *packet, uint8_t data_src)
Definition: lds.cpp:75
const uint32_t kMaxProductType
Definition: lds.h:248
std::mutex mutex_
Definition: lds.h:419
unsigned __int64 uint64_t
Definition: stdint.h:137
volatile uint32_t set_bits
Definition: lds.h:156
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
uint8_t raw_data_type
Definition: lds.h:175
uint8_t data_src
Definition: lds.h:174
LidarPacketStatistic statistic_info
Definition: lds.h:186
bool data_is_pubulished
Definition: lds.h:176
LidarDataOutputType
Definition: lds.h:93
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
CoordinateType
Definition: lds.h:98
const DataTypePointInfoPair data_type_info_pair_table[kMaxPointDataType]
Definition: lds.h:237
uint64_t RawLdsStampToNs(LdsStamp &timestamp, uint8_t timestamp_type)
Definition: lds.cpp:46
const int kPathStrMaxSize
Definition: lds.h:68
LidarConnectState
Definition: lds.h:77
const uint32_t kPointXYZRSize
Definition: lds.h:71
LidarDataSourceType
Definition: lds.h:85
uint32_t coordinate
Definition: lds.h:143
signed __int64 int64_t
Definition: stdint.h:136
const int kPathStrMinSize
Definition: lds.h:67
void EulerAnglesToRotationMatrix(EulerAngle euler, RotationMatrix matrix)
Definition: lds.cpp:150
const uint32_t KCartesianPointSize
Definition: lds.h:56
signed int int32_t
Definition: stdint.h:124
bool IsTripleIntNoneZero(int32_t x, int32_t y, int32_t z)
Definition: lds.h:389
const uint32_t kMinEthPacketQueueSize
Definition: lds.h:50
const uint32_t KSphericalPointSzie
Definition: lds.h:57
const uint32_t kImuEthPacketQueueSize
Definition: lds.h:52
uint8_t * LivoxPointToPxyzrtl(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
Definition: lds.cpp:208
int GetCount()
Definition: lds.h:414
bool IsRequestExit()
Definition: lds.h:441
volatile int count_
Definition: lds.h:421
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
uint32_t CalculatePacketQueueSize(uint32_t interval_ms, uint8_t product_type, uint8_t data_type)
Definition: lds.cpp:113
Semaphore(int count=0)
Definition: lds.h:399
volatile LidarConnectState connect_state
Definition: lds.h:184
volatile uint32_t packet_interval_max
Definition: lds.h:180
std::condition_variable cv_
Definition: lds.h:420
const int64_t kNsPerSecond
Definition: lds.h:65
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