-
Notifications
You must be signed in to change notification settings - Fork 82
/
livox_lidar_api.h
483 lines (424 loc) · 21.5 KB
/
livox_lidar_api.h
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
//
// 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_SDK_H_
#define LIVOX_LIDAR_SDK_H_
#ifdef __cplusplus
extern "C" {
#endif
#include <stdbool.h>
#include <stdint.h>
#include "livox_lidar_def.h"
/**
* Return SDK's version information in a numeric form.
* @param version Pointer to a version structure for returning the version information.
*/
void GetLivoxLidarSdkVer(LivoxLidarSdkVer *version);
/**
* Initialize the SDK.
* @return true if successfully initialized, otherwise false.
*/
bool LivoxLidarSdkInit(const char* path, const char* host_ip = "", const LivoxLidarLoggerCfgInfo* log_cfg_info = nullptr);
/**
* Start the device scanning routine which runs on a separate thread.
* @return true if successfully started, otherwise false.
*/
bool LivoxLidarSdkStart();
/**
* Uninitialize the SDK.
*/
void LivoxLidarSdkUninit();
/**
* Set the callback to receive point cloud data.
* @param handle device handle.
* @param client_data user data associated with the command.
*/
void SetLivoxLidarPointCloudCallBack(LivoxLidarPointCloudCallBack cb, void* client_data);
/**
* Add the lidar command data observer.
* @param handle device handle.
* @param client_data user data associated with the command.
*/
void LivoxLidarAddCmdObserver(LivoxLidarCmdObserverCallBack cb, void* client_data);
/**
* Remove the lidar command data observer.
*/
void LivoxLidarRemoveCmdObserver();
/**
* Set the point cloud observer.
* @param cb callback to receive Status Info.
* @param client_data user data associated with the command.
*/
uint16_t LivoxLidarAddPointCloudObserver(LivoxLidarPointCloudObserver cb, void *client_data);
/**
* remove point cloud observer.
* @param id the observer id.
*/
void LivoxLidarRemovePointCloudObserver(uint16_t id);
/**
* Set the callback to receive IMU data.
* @param cb callback to receive Status Info.
* @param client_data user data associated with the command.
*/
void SetLivoxLidarImuDataCallback(LivoxLidarImuDataCallback cb, void* client_data);
/**
* Set the callback to receive Status Info.
* @param cb callback to receive Status Info.
* @param client_data user data associated with the command.
*/
void SetLivoxLidarInfoCallback(LivoxLidarInfoCallback cb, void* client_data);
/**
* DisableLivoxLidar console log output.
*/
void DisableLivoxSdkConsoleLogger();
/**
* Save the log file.
*/
void SaveLivoxLidarSdkLoggerFile();
/**
* Set the callback to receive Status Info.
* @param cb callback to receive Status Info.
* @param client_data user data associated with the command.
*/
void SetLivoxLidarInfoChangeCallback(LivoxLidarInfoChangeCallback cb, void* client_data);
livox_status QueryLivoxLidarInternalInfo(uint32_t handle, QueryLivoxLidarInternalInfoCallback cb, void* client_data);
livox_status QueryLivoxLidarFwType(uint32_t handle, QueryLivoxLidarInternalInfoCallback cb, void* client_data);
livox_status QueryLivoxLidarFirmwareVer(uint32_t handle, QueryLivoxLidarInternalInfoCallback cb, void* client_data);
/**
* Set LiDAR pcl data type.
* @param handle device handle.
* @param data_type the type to change, the val:kLivoxLidarCartesianCoordinateHighData,
* kLivoxLidarCartesianCoordinateLowData,
* kLivoxLidarSphericalCoordinateData
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status SetLivoxLidarPclDataType(uint32_t handle, LivoxLidarPointDataType data_type, LivoxLidarAsyncControlCallback cb, void* client_data);
/**
* Set LiDAR sacn pattern.
* @param handle device handle.
* @param scan_type the type to change, the val:kLivoxLidarScanPatternRepetive,
* kLivoxLidarScanPatternNoneRepetive
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status SetLivoxLidarScanPattern(uint32_t handle, LivoxLidarScanPattern scan_pattern, LivoxLidarAsyncControlCallback cb, void* client_data);
/**
* Set LiDAR dual emit.
* @param handle device handle.
* @param enable if set dual emit the enable is true, else the enable is false
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status SetLivoxLidarDualEmit(uint32_t handle, bool enable, LivoxLidarAsyncControlCallback cb, void* client_data);
/**
* Enbale LiDAR point send.
* @param handle device handle.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status EnableLivoxLidarPointSend(uint32_t handle, LivoxLidarAsyncControlCallback cb, void* client_data);
/**
* Disable LiDAR point send.
* @param handle device handle.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status DisableLivoxLidarPointSend(uint32_t handle, LivoxLidarAsyncControlCallback cb, void* client_data);
/**
* Set LiDAR Ip info.
* @param handle device handle.
* @param ipconfig lidar ip info.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status SetLivoxLidarIp(uint32_t handle, LivoxLidarIpInfo* ip_config,
LivoxLidarAsyncControlCallback cb, void* client_data);
/**
* Set LiDAR state Ip info.
* @param handle device handle.
* @param host_state_info_ipcfg lidar ip info.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status SetLivoxLidarStateInfoHostIPCfg(uint32_t handle, HostStateInfoIpInfo* host_state_info_ipcfg,
LivoxLidarAsyncControlCallback cb, void* client_data);
/**
* Set LiDAR point cloud host ip info.
* @param handle device handle.
* @param host_point_ipcfg lidar ip info.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status SetLivoxLidarPointDataHostIPCfg(uint32_t handle, HostPointIPInfo* host_point_ipcfg,
LivoxLidarAsyncControlCallback cb, void* client_data);
/**
* Set LiDAR imu data host ip info.
* @param handle device handle.
* @param host_imu_ipcfg lidar ip info.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status SetLivoxLidarImuDataHostIPCfg(uint32_t handle, HostImuDataIPInfo* host_imu_ipcfg,
LivoxLidarAsyncControlCallback cb, void* client_data);
/**
* Get LiDAR extrinsic parameters.
* @param handle device handle.
* @param install_attitude extrinsic parameters.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status SetLivoxLidarInstallAttitude(uint32_t handle, LivoxLidarInstallAttitude* install_attitude,
LivoxLidarAsyncControlCallback cb, void* client_data);
/**
* Set LiDAR fov cfg0.
* @param handle device handle.
* @param fov_cfg0 fov cfg.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status SetLivoxLidarFovCfg0(uint32_t handle, FovCfg* fov_cfg0, LivoxLidarAsyncControlCallback cb, void* client_data);
/**
* Set LiDAR fov.
* @param handle device handle.
* @param fov_cfg1 fov cfg.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status SetLivoxLidarFovCfg1(uint32_t handle, FovCfg* fov_cfg1, LivoxLidarAsyncControlCallback cb, void* client_data);
/**
* Enable LiDAR fov cfg1.
* @param handle device handle.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status EnableLivoxLidarFov(uint32_t handle, uint8_t fov_en, LivoxLidarAsyncControlCallback cb, void* client_data);
/**
* Disable LiDAR fov.
* @param handle device handle.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status DisableLivoxLidarFov(uint32_t handle, LivoxLidarAsyncControlCallback cb, void* client_data);
/**
* Set LiDAR detect mode.
* @param handle device handle.
* @param mode detect mode
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status SetLivoxLidarDetectMode(uint32_t handle, LivoxLidarDetectMode mode, LivoxLidarAsyncControlCallback cb, void* client_data);
/**
* Set LiDAR func io cfg.
* @param handle device handle.
* @param func_io_cfg func io cfg; 0:IN0,1:IN1, 2:OUT0, 3:OUT1;Mid360 lidar 8, 10, 12, 11
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status SetLivoxLidarFuncIOCfg(uint32_t handle, FuncIOCfg* func_io_cfg, LivoxLidarAsyncControlCallback cb, void* client_data);
/**
* Set LiDAR blind spot.
* @param handle device handle.
* @param blind_spot blind spot.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status SetLivoxLidarBlindSpot(uint32_t handle, uint32_t blind_spot, LivoxLidarAsyncControlCallback cb, void* client_data);
/**
* Set LiDAR work mode.
* @param handle device handle.
* @param work_mode lidar work mode.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status SetLivoxLidarWorkMode(uint32_t handle, LivoxLidarWorkMode work_mode, LivoxLidarAsyncControlCallback cb, void* client_data);
/**
* Enable glass heating functionality.
* @param handle device handle.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status EnableLivoxLidarGlassHeat(uint32_t handle, LivoxLidarAsyncControlCallback cb, void* client_data);
/**
* Disable glass heating functionality.
* @param handle device handle.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status DisableLivoxLidarGlassHeat(uint32_t handle, LivoxLidarAsyncControlCallback cb, void* client_data);
// mid360 lidar does not support this function.
/**
* Enable LiDAR force heat function.
* @param handle device handle.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status StartForcedHeating(uint32_t handle, LivoxLidarAsyncControlCallback cb, void* client_data);
// mid360 lidar does not support this function.
/**
* Disable LiDAR force heat function.
* @param handle device handle.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status StopForcedHeating(uint32_t handle, LivoxLidarAsyncControlCallback cb, void* client_data);
/**
* Set LiDAR glass heat.
* @param handle device handle.
* @param glass_heat lidar glass heat.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
[[deprecated("Please USE EnableLivoxLidarGlassHeat() / StartForcedHeating() / ... instead")]]
livox_status SetLivoxLidarGlassHeat(uint32_t handle, LivoxLidarGlassHeat glass_heat, LivoxLidarAsyncControlCallback cb, void* client_data);
/**
* Enable LiDAR imu data.
* @param handle device handle.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status EnableLivoxLidarImuData(uint32_t handle, LivoxLidarAsyncControlCallback cb, void* client_data);
/**
* Disable LiDAR imu data.
* @param handle device handle.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status DisableLivoxLidarImuData(uint32_t handle, LivoxLidarAsyncControlCallback cb, void* client_data);
// mid360 lidar does not support
/**
* Enable LiDAR fusa function.
* @param handle device handle.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status EnableLivoxLidarFusaFunciont(uint32_t handle, LivoxLidarAsyncControlCallback cb, void* client_data);
// mid360 lidar does not support
/**
* Disable LiDAR fusa function.
* @param handle device handle.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status DisableLivoxLidarFusaFunciont(uint32_t handle, LivoxLidarAsyncControlCallback cb, void* client_data);
/**
* Reset LiDAR.
* @param handle device handle.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status LivoxLidarRequestReset(uint32_t handle, LivoxLidarResetCallback cb, void* client_data);
/**
* Start logger. Currently, only setting real-time log is supported.
* @param handle device handle.
* @param log_type The type of log file that has been configured.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status LivoxLidarStartLogger(const uint32_t handle, const LivoxLidarLogType log_type, LivoxLidarLoggerCallback cb, void* client_data);
/**
* Start logger. Currently, only setting real-time log is supported.
* @param handle device handle.
* @param log_type The type of log file that has been configured.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status LivoxLidarStopLogger(const uint32_t handle, const LivoxLidarLogType log_type, LivoxLidarLoggerCallback cb, void* client_data);
/**
* Set LiDAR debug point cloud switch.
* @param handle device handle.
* @param enable true for enabling debug point cloud
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error codes.
*/
livox_status SetLivoxLidarDebugPointCloud(uint32_t handle, bool enable, LivoxLidarLoggerCallback cb, void* client_data);
/**
* Set LiDAR GPS "GPRMC" string to synchronize the time.
* @param handle device handle.
* @param rmc GPS "GPRMC" string.
* @param rmc_length GPS "GPRMC" string length.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error codes.
*/
livox_status SetLivoxLidarRmcSyncTime(uint32_t handle, const char* rmc, uint16_t rmc_length, LivoxLidarRmcSyncTimeCallBack cb, void* client_data);
/**
* Set LiDAR work mode after boot.
* @param handle device handle.
* @param work_mode lidar work mode after boot.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status SetLivoxLidarWorkModeAfterBoot(const uint32_t handle,const LivoxLidarWorkModeAfterBoot work_mode, LivoxLidarAsyncControlCallback cb, void* client_data);
/*******Upgrade Module***********/
/**
* Reboot lidar.
* @param handle device handle.
* @param cb callback for the command.
* @param client_data user data associated with the command.
* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code.
*/
livox_status LivoxLidarRequestReboot(uint32_t handle, LivoxLidarRebootCallback cb, void* client_data);
/**
* Start the device scanning routine which runs on a separate thread.
* @return true if successfully Open firmware file path, otherwise false.
*/
bool SetLivoxLidarUpgradeFirmwarePath(const char* firmware_path);
void SetLivoxLidarUpgradeProgressCallback(OnLivoxLidarUpgradeProgressCallback cb, void* client_data);
void UpgradeLivoxLidars(const uint32_t* handle, const uint8_t lidar_num);
#ifdef __cplusplus
}
#endif
#endif // LIVOX_LIDAR_SDK_H_