livox2-sys 0.1.0

A Rust wrapper for the Livox SDK2
Documentation
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
//
// The MIT License (MIT)
//
// Copyright (c) 2022 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.
//

#ifndef LIVOX_LIDAR_DEF_H_
#define LIVOX_LIDAR_DEF_H_

#include <stdint.h>

#define kMaxLidarCount 32

#pragma pack(1)

#define LIVOX_LIDAR_SDK_MAJOR_VERSION       1
#define LIVOX_LIDAR_SDK_MINOR_VERSION       2
#define LIVOX_LIDAR_SDK_PATCH_VERSION       5

#define kBroadcastCodeSize 16

/** Fuction return value defination, refer to \ref LivoxStatus. */
typedef int32_t livox_status;


/** The numeric version information struct.  */
typedef struct {
  int major;      /**< major number */
  int minor;      /**< minor number */
  int patch;      /**< patch number */
} LivoxLidarSdkVer;

typedef struct {
  uint8_t dev_type;
  char sn[16];
  char lidar_ip[16];
} LivoxLidarInfo;

/** Device type. */
typedef enum {
  kLivoxLidarTypeHub = 0,
  kLivoxLidarTypeMid40 = 1,
  kLivoxLidarTypeTele = 2,
  kLivoxLidarTypeHorizon = 3,
  kLivoxLidarTypeMid70 = 6,
  kLivoxLidarTypeAvia = 7,
  kLivoxLidarTypeMid360 = 9,
  kLivoxLidarTypeIndustrialHAP = 10,
  kLivoxLidarTypeHAP = 15,
  kLivoxLidarTypePA = 16,
} LivoxLidarDeviceType;

typedef enum {
  kKeyPclDataType             = 0x0000,
  kKeyPatternMode             = 0x0001,
  kKeyDualEmitEn              = 0x0002,
  kKeyPointSendEn             = 0x0003,
  kKeyLidarIpCfg              = 0x0004,
  kKeyStateInfoHostIpCfg      = 0x0005,
  kKeyLidarPointDataHostIpCfg = 0x0006,
  kKeyLidarImuHostIpCfg       = 0x0007,
  kKeyCtlHostIpCfg            = 0x0008,
  kKeyLogHostIpCfg            = 0x0009,
  
  kKeyVehicleSpeed            = 0x0010,
  kKeyEnvironmentTemp         = 0x0011,
  kKeyInstallAttitude         = 0x0012,
  kKeyBlindSpotSet            = 0x0013,
  kKeyFrameRate               = 0x0014,
  kKeyFovCfg0                 = 0x0015,
  kKeyFovCfg1                 = 0x0016,
  kKeyFovCfgEn                = 0x0017,
  kKeyDetectMode              = 0x0018,
  kKeyFuncIoCfg               = 0x0019,
  kKeyWorkModeAfterBoot       = 0x0020,
  kKeyWorkMode                = 0x001A,
  kKeyGlassHeat               = 0x001B,
  kKeyImuDataEn               = 0x001C,
  kKeyFusaEn                  = 0x001D,
  kKeyForceHeatEn             = 0x001E,

  kKeyLogParamSet             = 0x7FFF,

  kKeySn                      = 0x8000,
  kKeyProductInfo             = 0x8001,
  kKeyVersionApp              = 0x8002,
  kKeyVersionLoader           = 0x8003,
  kKeyVersionHardware         = 0x8004,
  kKeyMac                     = 0x8005,
  kKeyCurWorkState            = 0x8006,
  kKeyCoreTemp                = 0x8007,
  kKeyPowerUpCnt              = 0x8008,
  kKeyLocalTimeNow            = 0x8009,
  kKeyLastSyncTime            = 0x800A,
  kKeyTimeOffset              = 0x800B,
  kKeyTimeSyncType            = 0x800C,  
  kKeyStatusCode              = 0x800D,
  kKeyLidarDiagStatus         = 0x800E,
  kKeyLidarFlashStatus        = 0x800F,
  kKeyFwType                  = 0x8010,
  kKeyHmsCode                 = 0x8011,
  kKeyCurGlassHeatState       = 0x8012,
  
  kKeyRoiMode                 = 0xFFFE,
  kKeyLidarDiagInfoQuery      = 0xFFFF
} ParamKeyName;

typedef struct {
  uint8_t version;
  uint16_t length;
  uint16_t time_interval;      /**< unit: 0.1 us */
  uint16_t dot_num;
  uint16_t udp_cnt;
  uint8_t frame_cnt;
  uint8_t data_type;
  uint8_t time_type;
  uint8_t rsvd[12];
  uint32_t crc32;
  uint8_t timestamp[8];
  uint8_t data[1];             /**< Point cloud data. */
} LivoxLidarEthernetPacket;

typedef struct {
  uint8_t  sof;
  uint8_t  version;
  uint16_t length;
  uint32_t seq_num;
  uint16_t cmd_id;
  uint8_t  cmd_type;
  uint8_t  sender_type;
  char     rsvd[6];
  uint16_t crc16_h;
  uint32_t crc32_d;
  uint8_t  data[1];
} LivoxLidarCmdPacket;

typedef struct {
  float gyro_x;
  float gyro_y;
  float gyro_z;
  float acc_x;
  float acc_y;
  float acc_z;
} LivoxLidarImuRawPoint;

typedef struct {
  int32_t x;            /**< X axis, Unit:mm */
  int32_t y;            /**< Y axis, Unit:mm */
  int32_t z;            /**< Z axis, Unit:mm */
  uint8_t reflectivity; /**< Reflectivity */
  uint8_t tag;          /**< Tag */
} LivoxLidarCartesianHighRawPoint;

typedef struct {
  int16_t x;            /**< X axis, Unit:cm */
  int16_t y;            /**< Y axis, Unit:cm */
  int16_t z;            /**< Z axis, Unit:cm */
  uint8_t reflectivity; /**< Reflectivity */
  uint8_t tag;          /**< Tag */
} LivoxLidarCartesianLowRawPoint;

typedef struct {
  uint32_t depth;
  uint16_t theta;
  uint16_t phi;
  uint8_t reflectivity;
  uint8_t tag;
} LivoxLidarSpherPoint;

typedef enum {
  kLivoxLidarImuData = 0,
  kLivoxLidarCartesianCoordinateHighData = 0x01,
  kLivoxLidarCartesianCoordinateLowData = 0x02,
  kLivoxLidarSphericalCoordinateData = 0x03
} LivoxLidarPointDataType;

typedef enum {
  kLivoxLidarRealTimeLog = 0,
  kLivoxLidarExceptionLog = 0x01
} LivoxLidarLogType;

typedef enum {
  kLivoxLidarStatusSendFailed = -9,           /**< Command send failed. */
  kLivoxLidarStatusHandlerImplNotExist = -8,  /**< Handler implementation not exist. */
  kLivoxLidarStatusInvalidHandle = -7,        /**< Device handle invalid. */
  kLivoxLidarStatusChannelNotExist = -6,      /**< Command channel not exist. */
  kLivoxLidarStatusNotEnoughMemory = -5,      /**< No enough memory. */
  kLivoxLidarStatusTimeout = -4,              /**< Operation timeouts. */
  kLivoxLidarStatusNotSupported = -3,         /**< Operation is not supported on this device. */
  kLivoxLidarStatusNotConnected = -2,         /**< Requested device is not connected. */
  kLivoxLidarStatusFailure = -1,              /**< Failure. */
  kLivoxLidarStatusSuccess = 0                /**< Success. */
} LivoxLidarStatus;

typedef struct {
  uint16_t key;                /*< Key, refer to \ref DeviceParamKeyName. */
  uint16_t length;             /*< Length of value. */
  uint8_t value[1];            /*< Value. */
} LivoxLidarKeyValueParam;

typedef struct {
  uint8_t ret_code;
  uint16_t error_key;
} LivoxLidarAsyncControlResponse;

typedef struct {
  uint8_t ret_code;
  const char* lidar_info;
} LivoxLidarInfoResponse;

typedef struct {
  uint8_t ret_code;
  uint16_t param_num;
  uint8_t data[1];
} LivoxLidarDiagInternalInfoResponse;

typedef enum {
  kLivoxLidarScanPatternNoneRepetive = 0x00,
  kLivoxLidarScanPatternRepetive = 0x01,
  kLivoxLidarScanPatternRepetiveLowFrameRate = 0x02
} LivoxLidarScanPattern;

typedef enum {
  kLivoxLidarFrameRate10Hz = 0x00,
  kLivoxLidarFrameRate15Hz = 0x01,
  kLivoxLidarFrameRate20Hz = 0x02,
  kLivoxLidarFrameRate25Hz = 0x03,
} LivoxLidarPointFrameRate;

typedef enum {
  kLivoxLidarNormal = 0x01,
  kLivoxLidarWakeUp = 0x02,
  kLivoxLidarSleep = 0x03,
  kLivoxLidarError = 0x04,
  kLivoxLidarPowerOnSelfTest = 0x05,
  kLivoxLidarMotorStarting = 0x06,
  kLivoxLidarMotorStoping = 0x07,
  kLivoxLidarUpgrade = 0x08
} LivoxLidarWorkMode;

typedef enum {
  kLivoxLidarWorkModeAfterBootDefault = 0x00,
  kLivoxLidarWorkModeAfterBootNormal = 0x01,
  kLivoxLidarWorkModeAfterBootWakeUp = 0x02
} LivoxLidarWorkModeAfterBoot;

typedef struct {
  float roll_deg;
  float pitch_deg;
  float yaw_deg;
  int32_t x; //mm
  int32_t y; //mm
  int32_t z; // mm
} LivoxLidarInstallAttitude;

typedef struct {
  int32_t yaw_start;
  int32_t yaw_stop;
  int32_t pitch_start;
  int32_t pitch_stop;
  uint32_t rsvd;
} FovCfg;

typedef enum {
  kLivoxLidarDetectNormal = 0x00,
  kLivoxLidarDetectSensitive = 0x01
} LivoxLidarDetectMode;

typedef struct {
  uint8_t in0;
  uint8_t int1;
  uint8_t out0;
  uint8_t out1;
} FuncIOCfg;

typedef struct {
  bool lidar_log_enable;
  uint32_t lidar_log_cache_size;
  char lidar_log_path[1024];
} LivoxLidarLoggerCfgInfo;

typedef struct {
  char ip_addr[16];  /**< IP address. */
  char net_mask[16]; /**< Subnet mask. */
  char gw_addr[16];  /**< Gateway address. */
} LivoxLidarIpInfo;

typedef struct {
  char host_ip_addr[16];  /**< IP address. */
  uint16_t host_state_info_port;
  uint16_t lidar_state_info_port;
} HostStateInfoIpInfo;

typedef struct {
  char host_ip_addr[16];  /**< IP address. */
  uint16_t host_point_data_port;
  uint16_t lidar_point_data_port;
} HostPointIPInfo;

typedef struct {
  char host_ip_addr[16];  /**< IP address. */
  uint16_t host_imu_data_port; // resv
  uint16_t lidar_imu_data_port; // resv
} HostImuDataIPInfo;

typedef struct {
  char ip_addr[16];  /**< IP address. */
  uint16_t dst_port;
  uint16_t src_port;
} LivoxIpCfg;

typedef struct {
  uint8_t pcl_data_type;
  uint8_t pattern_mode;
  uint8_t dual_emit_en;
  uint8_t point_send_en;
  LivoxLidarIpInfo lidar_ip_info;
  HostPointIPInfo host_point_ip_info;
  HostImuDataIPInfo host_imu_ip_info;
  LivoxLidarInstallAttitude install_attitude;
  uint32_t blind_spot_set;
  uint8_t work_mode;
  uint8_t glass_heat;
  uint8_t imu_data_en;
  uint8_t fusa_en;
  char sn[16];
  char product_info[64];
  uint8_t version_app[4];
  uint8_t version_load[4];
  uint8_t version_hardware[4];
  uint8_t mac[6];
  uint8_t cur_work_state;
  uint64_t status_code;
} LivoxLidarStateInfo;

typedef struct {
  uint8_t             pcl_data_type;            // 0x0000
  uint8_t             pattern_mode;             // 0x0001
  uint8_t             dual_emit_en;             // 0x0002
  uint8_t             point_send_en;            // 0x0003  
  LivoxLidarIpInfo    lidar_ipcfg;              // 0x0004
  HostStateInfoIpInfo host_state_info;          // 0x0005
  HostPointIPInfo     pointcloud_host_ipcfg;    // 0x0006
  HostImuDataIPInfo   imu_host_ipcfg;           // 0x0007
  LivoxIpCfg          ctl_host_ipcfg;           // 0x0008
  LivoxIpCfg          log_host_ipcfg;           // 0x0009
  
  int32_t             vehicle_speed;            // 0x0010
  int32_t             environment_temp;         // 0x0011  
  LivoxLidarInstallAttitude install_attitude;   // 0x0012
  uint32_t            blind_spot_set;           // 0x0013
  uint8_t             frame_rate;               // 0x0014
  FovCfg              fov_cfg0;                 // 0x0015
  FovCfg              fov_cfg1;                 // 0x0016
  uint8_t             fov_cfg_en;               // 0x0017 
  uint8_t             detect_mode;              // 0x0018
  uint8_t             func_io_cfg[4];           // 0x0019
  uint8_t             work_tgt_mode;            // 0x001A
  uint8_t             glass_heat;               // 0x001B
  uint8_t             imu_data_en;              // 0x001C
  uint8_t             fusa_en;                  // 0x001D

  char                sn[16];                   // 0x8000
  char                product_info[64];         // 0x8001
  uint8_t             version_app[4];           // 0x8002
  uint8_t             version_loader[4];        // 0x8003
  uint8_t             version_hardware[4];      // 0x8004
  uint8_t             mac[6];                   // 0x8005
  uint8_t             cur_work_state;           // 0x8006
  int32_t             core_temp;                // 0x8007
  uint32_t            powerup_cnt;              // 0x8008
  uint64_t            local_time_now;           // 0x8009
  uint64_t            last_sync_time;           // 0x800A
  int64_t             time_offset;              // 0x800B
  uint8_t             time_sync_type;           // 0x800C
  uint8_t             status_code[32];          // 0x800D
  uint16_t            lidar_diag_status;        // 0x800E
  uint8_t             lidar_flash_status;       // 0x800F
  uint8_t             fw_type;                  // 0x8010
  uint32_t            hms_code[8];              // 0x8011
  uint8_t             ROI_Mode;                 // 0xFFFE
} DirectLidarStateInfo;

typedef struct {
  uint8_t ret_code;
  LivoxLidarStateInfo livox_lidar_state_info;
} LivoxLidarQueryInternalInfoResponse;

typedef enum {
  kLivoxLidarStopPowerOnHeatingOrDiagnosticHeating = 0x00,
  kLivoxLidarTurnOnHeating = 0x01,
  kLivoxLidarDiagnosticHeating = 0x02,
  kLivoxLidarStopSelfHeating = 0x03
} LivoxLidarGlassHeat;

typedef struct {
  uint8_t log_send_method;
  uint16_t log_id;
  uint16_t log_frequency;
  uint8_t is_save_setting;
  uint8_t check_code;
} LivoxLidarLogParam;

typedef struct {
  uint8_t ret_code;
} LivoxLidarLoggerResponse;

typedef struct {
  uint16_t timeout; /**< delay reboot time */
} LivoxLidarRebootRequest;

typedef struct {
  uint8_t ret_code; /**< Return code. */
} LivoxLidarRebootResponse;

typedef struct {
  uint8_t data[16];
} LivoxLidarResetRequest;

typedef struct {
  uint8_t ret_code;
} LivoxLidarResetResponse;

/**
 * Upgrade related data struct
 */
typedef enum {
  kLivoxLidarUpgradeIdle = 0,
  kLivoxLidarUpgradeRequest = 1,
  kLivoxLidarUpgradeXferFirmware = 2,
  kLivoxLidarUpgradeCompleteXferFirmware = 3,
  kLivoxLidarUpgradeGetUpgradeProgress = 4,
  kLivoxLidarUpgradeComplete = 5,
  kLivoxLidarUpgradeTimeout = 6,
  kLivoxLidarUpgradeErr = 7,
  kLivoxLidarUpgradeUndef = 8
} LivoxLidarFsmState;

typedef enum {
  kLivoxLidarEventRequestUpgrade = 0,
  kLivoxLidarEventXferFirmware = 1,
  kLivoxLidarEventCompleteXferFirmware = 2,
  kLivoxLidarEventGetUpgradeProgress = 3,
  kLivoxLidarEventComplete = 4,
  kLivoxLidarEventReinit = 5,
  kLivoxLidarEventTimeout = 6,
  kLivoxLidarEventErr = 7,
  kLivoxLidarEventUndef = 8
} LivoxLidarFsmEvent;

typedef struct {
  LivoxLidarFsmEvent state;
  uint8_t progress;
} LivoxLidarUpgradeState;

typedef struct {
  uint8_t ret; // succ: 0, fail: 1
} LivoxLidarRmcSyncTimeResponse;

#pragma pack()

/**
 * Callback function for receiving point cloud data.
 * @param handle                 device handle.
 * @param data                   device's data.
 * @param data_num               number of points in data.
 * @param client_data            user data associated with the command.
 */
typedef void (*LivoxLidarPointCloudCallBack)(const uint32_t handle, const uint8_t dev_type, LivoxLidarEthernetPacket* data, void* client_data);

/**
 * Callback function for receiving point cloud data.
 * @param handle                 device handle.
 * @param data                   device's command data.
 * @param client_data            user data associated with the command.
 */
typedef void (*LivoxLidarCmdObserverCallBack)(const uint32_t handle, const LivoxLidarCmdPacket* data, void* client_data);

/**
 * Callback function for point cloud observer.
 * @param handle                 device handle.
 * @param data                   device's data.
 * @param data_num               number of points in data.
 * @param client_data            user data associated with the command.
 */
typedef void (*LivoxLidarPointCloudObserver) (uint32_t handle, const uint8_t dev_type, LivoxLidarEthernetPacket *data, void *client_data);

/**
 * Callback function for receiving IMU data.
 * @param data                   device's data.
 * @param data_num               number of IMU data.
 * @param client_data            user data associated with the command.
 */
typedef void (*LivoxLidarImuDataCallback)(const uint32_t handle, const uint8_t dev_type, LivoxLidarEthernetPacket* data, void* client_data);

/**
 * Callback function for receiving Status Info.
 * @param status_info            status info.
 * @param client_data            user data associated with the command.
 */
typedef void(*LivoxLidarInfoCallback)(const uint32_t handle, const uint8_t dev_type, const char* info, void* client_data);

/**
 * Callback function for receiving Status Info.
 * @param status                 status info.
 * @param client_data            user data associated with the command.
 */
typedef void(*LivoxLidarInfoChangeCallback)(const uint32_t handle, const LivoxLidarInfo* info, void* client_data);

typedef void (*QueryLivoxLidarInternalInfoCallback)(livox_status status, uint32_t handle,
        LivoxLidarDiagInternalInfoResponse* response, void* client_data);

/**
 * Callback function for receiving response from the lidar on the configuration of parameter.
 * @param  status                 status info.
 * @param  response               lidar return code and error key.
 * @param  client_data            user data associated with the command.
 * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
 */
typedef void (*LivoxLidarAsyncControlCallback)(livox_status status, uint32_t handle, 
                                               LivoxLidarAsyncControlResponse *response, void *client_data);
/**
 * Callback function for receiving the reset setting response from lidar.
 * @param  status                 status info.
 * @param  response               lidar return code.
 * @param  client_data            user data associated with the command.
 * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
 */
typedef void (*LivoxLidarResetCallback)(livox_status status, uint32_t handle, LivoxLidarResetResponse* response, void* client_data);


/**
 * Callback function for receiving the log setting response from lidar.
 * @param  status                 status info.
 * @param  response               lidar return code.
 * @param  client_data            user data associated with the command.
 * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
 */
typedef void (*LivoxLidarLoggerCallback)(livox_status status, uint32_t handle,
                                         LivoxLidarLoggerResponse* response, void* client_data);

/**
 * Callback function for receiving the Reboot setting response from lidar.
 * @param  status                 status info.
 * @param  response               lidar return code.
 * @param  client_data            user data associated with the command.
 * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
 */
typedef void (*LivoxLidarRebootCallback)(livox_status status, uint32_t handle, LivoxLidarRebootResponse* response, void* client_data);

typedef void (*OnLivoxLidarUpgradeProgressCallback)(uint32_t handle, LivoxLidarUpgradeState state, void *client_data);

/**
 * Callback function for receiving point cloud data.
 * @param status                 status info.
 * @param handle                 device handle.
 * @param data                   device's command data.
 * @param client_data            user data associated with the command.
 */
typedef void (*LivoxLidarRmcSyncTimeCallBack)(livox_status status, uint32_t handle, LivoxLidarRmcSyncTimeResponse* data, void* client_data);

#endif  // LIVOX_LIDAR_DEF_H_