forked from RobotecAI/RobotecGPULidar
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathcore.h
507 lines (445 loc) · 16.9 KB
/
core.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
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
#pragma once
#include <stdbool.h>
#include <stddef.h>
#include <stdint.h>
#ifdef __cplusplus
#define NO_MANGLING extern "C"
#else // NOT __cplusplus
#define NO_MANGLING
#endif
#if defined _WIN32 || defined __CYGWIN__
#ifdef __GNUC__
#define RGL_VISIBLE __attribute__ ((dllexport))
#else
#define RGL_VISIBLE __declspec(dllexport)
#endif // __GNUC__
#else
#define RGL_VISIBLE __attribute__ ((visibility("default")))
#if __GNUC__ >= 4
#define RGL_VISIBLE __attribute__ ((visibility("default")))
#else
#define RGL_VISIBLE
#endif
#endif // _WIN32 || __CYGWIN__
#define RGL_API NO_MANGLING RGL_VISIBLE
#define RGL_VERSION_MAJOR 0
#define RGL_VERSION_MINOR 11
#define RGL_VERSION_PATCH 3
/**
* Three consecutive 32-bit floats.
*/
typedef struct
{
float value[3];
} rgl_vec3f;
#ifndef __cplusplus
static_assert(sizeof(rgl_vec3f) == 3 * sizeof(float));
#endif
/**
* Three consecutive 32-bit signed integers.
*/
typedef struct
{
int32_t value[3];
} rgl_vec3i;
/**
* Row-major matrix with 3 rows and 4 columns of 32-bit floats.
*/
typedef struct
{
float value[3][4];
} rgl_mat3x4f;
/**
* Represents on-GPU mesh that can be referenced by entities on the scene.
* Each mesh can be referenced by any number of entities on different scenes.
*/
typedef struct Mesh *rgl_mesh_t;
/**
* Opaque handle representing an object visible to lidars.
* An entity is always bound to exactly one scene.
*/
typedef struct Entity *rgl_entity_t;
/**
* TODO(prybicki)
*/
typedef struct Node *rgl_node_t;
/**
* Opaque handle representing a scene - a collection of entities.
* Using scene is optional. NULL can be passed to use an implicit default scene.
*/
typedef struct Scene *rgl_scene_t;
/**
* Status (error) codes returned by all RGL API functions.
* Unrecoverable errors require reloading the library (restarting the application).
*/
typedef enum
{
/**
* Operation successful.
* This is a recoverable error :)
*/
RGL_SUCCESS = 0,
/**
* One of the arguments is invalid (e.g. null pointer) or a number in invalid range.
* Get the error string for more details.
* This is a recoverable error.
*/
RGL_INVALID_ARGUMENT,
/**
* RGL internal state has been corrupted by a previous unrecoverable error.
* Application must be restarted.
*/
RGL_INVALID_STATE,
/**
* Indicates that a logging operation (e.g. configuration) was not successful.
* This is an unrecoverable error.
*/
RGL_LOGGING_ERROR,
/**
* Indicates that provided API object handle is not known by RGL.
* This can be caused by using previously destroyed API object, e.g.
* by previous call to rgl_*_destroy(...) or rgl_cleanup()
* This is a recoverable error.
*/
RGL_INVALID_API_OBJECT,
/**
* Indicates that a given file could not be opened.
* This is a recoverable error.
*/
RGL_INVALID_FILE_PATH,
/**
* Indicates that a tape operation was not successful.
* This is a recoverable error.
*/
RGL_TAPE_ERROR,
/**
* Indicates an error in the pipeline, such as adjacency of incompatible nodes.
* This is a recoverable error.
*/
RGL_INVALID_PIPELINE,
/**
* Indicates a failure during (lazy) initialization.
* This is an unrecoverable error.
*/
RGL_INITIALIZATION_ERROR,
/**
* Requested functionality has been not yet implemented.
* This is a recoverable error.
*/
RGL_NOT_IMPLEMENTED = 404,
/**
* An unhandled internal error has occurred.
* If you see this error, please file a bug report.
* This is an unrecoverable error.
*/
RGL_INTERNAL_EXCEPTION = 500,
} rgl_status_t;
/**
* Available logging verbosity levels.
*/
typedef enum : int
{
RGL_LOG_LEVEL_ALL = 0,
RGL_LOG_LEVEL_TRACE = 0,
RGL_LOG_LEVEL_DEBUG = 1,
RGL_LOG_LEVEL_INFO = 2,
RGL_LOG_LEVEL_WARN = 3,
RGL_LOG_LEVEL_ERROR = 4,
RGL_LOG_LEVEL_CRITICAL = 5,
RGL_LOG_LEVEL_OFF = 6,
RGL_LOG_LEVEL_COUNT = 7
} rgl_log_level_t;
/**
* Available point attributes, used to specify layout of the binary data.
*/
typedef enum
{
RGL_FIELD_XYZ_F32 = 1,
RGL_FIELD_INTENSITY_F32,
RGL_FIELD_IS_HIT_I32,
RGL_FIELD_RAY_IDX_U32,
RGL_FIELD_POINT_IDX_U32,
RGL_FIELD_DISTANCE_F32,
RGL_FIELD_AZIMUTH_F32,
RGL_FIELD_RING_ID_U16,
RGL_FIELD_RETURN_TYPE_U8,
RGL_FIELD_TIME_STAMP_F64,
RGL_FIELD_LASER_RETRO_F32,
// Dummy fields
RGL_FIELD_PADDING_8 = 1024,
RGL_FIELD_PADDING_16,
RGL_FIELD_PADDING_32,
// Dynamic fields
RGL_FIELD_DYNAMIC_FORMAT = 13842,
} rgl_field_t;
/******************************** GENERAL ********************************/
/**
* Returns data describing semantic version as described in https://semver.org/
* Version string can be obtained by formatting "{out_major}.{out_minor}.{out_patch}".
* Hash is provided mostly for debugging and issue reporting.
* @param out_major Address to store major version number
* @param out_minor Address to store minor version number
* @param out_patch Address to store patch version number
*/
RGL_API rgl_status_t
rgl_get_version_info(int32_t *out_major, int32_t *out_minor, int32_t *out_patch);
/**
* Optionally (re)configures internal logging. This feature may be useful for debugging / issue reporting.
* By default (i.e. not calling `rgl_configure_logging`) is equivalent to the following call:
* `rgl_configure_logging(RGL_LOG_LEVEL_INFO, nullptr, true)`
* @param log_level Controls severity of emitted logs: trace=0, debug=1, info=2, warn=3, error=4, critical=5, off=6
* @param log_file_path Path to the file where logs will be saved.
* The file will be created or truncated on each configuration.
* Pass nullptr to disable logging to file
* @param use_stdout If true, logs will be outputted to stdout.
*/
RGL_API rgl_status_t
rgl_configure_logging(rgl_log_level_t log_level, const char* log_file_path, bool use_stdout);
/**
* Returns a pointer to a string explaining last error. This function always succeeds.
* Returned pointer is valid only until next RGL API call.
* @param out_error Address to store pointer to string explaining the cause of the given error.
*/
RGL_API void
rgl_get_last_error_string(const char **out_error_string);
/**
* Removes all user-created API objects: meshes, entities, scenes, lidars, etc.
* Effectively brings the library to the state as-if it was not yet used.
* All API handles are invalidated.
*/
RGL_API rgl_status_t
rgl_cleanup(void);
/******************************** MESH ********************************/
/**
* Creates mesh from vertex and index arrays. CW/CCW order does not matter.
* Provided arrays are copied to the GPU before this function returns.
* @param out_mesh Address to store the resulting mesh handle
* @param vertices An array of rgl_vec3f or binary-compatible data representing mesh vertices
* @param vertex_count Number of elements in the vertices array
* @param indices An array of rgl_vec3i or binary-compatible data representing mesh indices
* @param index_count Number of elements in the indices array
*/
RGL_API rgl_status_t
rgl_mesh_create(rgl_mesh_t *out_mesh,
const rgl_vec3f *vertices,
int32_t vertex_count,
const rgl_vec3i *indices,
int32_t index_count);
/**
* Informs that the given mesh will be no longer used.
* The mesh will be destroyed after all referring entities are destroyed.
* @param mesh Mesh to be marked as no longer needed
*/
RGL_API rgl_status_t
rgl_mesh_destroy(rgl_mesh_t mesh);
/**
* Updates mesh vertex data. The number of vertices must not change.
* This function is intended to update animated meshes.
* @param mesh Mesh to modify
* @param vertices An array of rgl_vec3f or binary-compatible data representing mesh vertices
* @param vertex_count Number of elements in the vertices array. Must be equal to the original vertex count!
*/
RGL_API rgl_status_t
rgl_mesh_update_vertices(rgl_mesh_t mesh,
const rgl_vec3f *vertices,
int32_t vertex_count);
/******************************** ENTITY ********************************/
/**
* Creates an entity and adds it to the given scene.
* Entity is a lightweight object which pairs a reference to a mesh with a 3D affine transform.
* @param out_entity Handle to the created entity.
* @param scene Scene where entity will be added. Pass NULL to use the default scene.
* @param mesh Handle to the mesh which will represent the entity on the scene.
*/
RGL_API rgl_status_t
rgl_entity_create(rgl_entity_t *out_entity, rgl_scene_t scene, rgl_mesh_t mesh);
/**
* Removes an entity from the scene and releases its resources (memory).
* This operation does not affect the mesh used by the entity, since it can be shared among other entities.
* @param entity Entity to remove
*/
RGL_API rgl_status_t
rgl_entity_destroy(rgl_entity_t entity);
/**
* Changes transform (position, rotation, scaling) of the given entity.
* @param entity Entity to modify
* @param transform Pointer to rgl_mat3x4f (or binary-compatible data) representing desired (entity -> world) coordinate system transform.
*/
RGL_API rgl_status_t
rgl_entity_set_pose(rgl_entity_t entity, const rgl_mat3x4f *local_to_world_tf);
/**
* Set laser retro value for the given entity.
* @param entity Entity to modify
* @param int laser retrovalue to set. If not set,it will be set to 100.0.
*/
RGL_API rgl_status_t
rgl_entity_set_laser_retro(rgl_entity_t entity, float retro);
/******************************** NODES ********************************/
/**
* Creates or modifies UseRaysMat3x4fNode.
* The node provides initial rays for its children nodes.
* Initial rays are usually provided in device-local coordinate frame, i.e. close to (0, 0, 0).
* Input: none
* Output: rays
* @param node If (*node) == nullptr, a new node will be created. Otherwise, (*node) will be modified.
* @param rays Pointer to 3x4 affine matrices describing rays poses.
* @param ray_count Size of the `rays` array
*/
RGL_API rgl_status_t
rgl_node_rays_from_mat3x4f(rgl_node_t* node, const rgl_mat3x4f* rays, int32_t ray_count);
/**
* Creates or modifies UseRingIdsNode.
* The node assigns ring ids for existing rays.
* Input: rays
* Output: rays
* @param node If (*node) == nullptr, a new node will be created. Otherwise, (*node) will be modified.
* @param ring_ids Pointer to ring ids.
* @param ray_count Size of the `ring_ids` array.
*/
RGL_API rgl_status_t
rgl_node_rays_set_ring_ids(rgl_node_t* node, const int32_t* ring_ids, int32_t ring_ids_count);
/**
* Creates or modifies TransformRaysNode.
* Effectively, the node performs the following operation for all rays: `outputRay[i] = (*transform) * inputRay[i]`
* This function can be used to account for the pose of the device.
* Graph input: rays
* Graph output: rays
* @param node If (*node) == nullptr, a new node will be created. Otherwise, (*node) will be modified.
* @param transform Pointer to a single 3x4 affine matrix describing the transformation to be applied.
*/
RGL_API rgl_status_t
rgl_node_rays_transform(rgl_node_t* node, const rgl_mat3x4f* transform);
// Applies affine transformation, e.g. to change the coordinate frame.
/**
* Creates or modifies TransformPointsNode.
* The node applies affine transformation to all points.
* It can be used to e.g. change coordinate frame after raytracing.
* Note: affects only RGL_FIELD_XYZ_F32. Other fields are not modified.
* Graph input: point cloud
* Graph output: point cloud (transformed)
* @param node If (*node) == nullptr, a new node will be created. Otherwise, (*node) will be modified.
* @param transform Pointer to a single 3x4 affine matrix describing the transformation to be applied.
*/
RGL_API rgl_status_t
rgl_node_points_transform(rgl_node_t* node, const rgl_mat3x4f* transform);
/**
* Creates or modifies RaytraceNode.
* The node performs GPU-accelerated raytracing on the given scene.
* Fields to be computed will be automatically determined based on connected FormatNodes and YieldPointsNodes
* Graph input: rays
* Graph output: point cloud (sparse)
* @param node If (*node) == nullptr, a new node will be created. Otherwise, (*node) will be modified.
* @param scene Handle to a scene to perform raytracing on. Pass null to use the default scene
* @param range Maximum distance to travel for every ray
*/
RGL_API rgl_status_t
rgl_node_raytrace(rgl_node_t* node, rgl_scene_t scene, float range);
/**
* Creates or modifies FormatNode.
* The node converts internal representation into a binary format defined by `fields` array.
* Note: It is a user's responsibility to ensure proper data structure alignment. See (https://en.wikipedia.org/wiki/Data_structure_alignment).
* Graph input: point cloud
* Graph output: point cloud
* @param node If (*node) == nullptr, a new node will be created. Otherwise, (*node) will be modified.
* @param fields Subsequent fields to be present in the binary output
* @param field_count Number of elements in the `fields` array
*/
RGL_API rgl_status_t
rgl_node_points_format(rgl_node_t* node, const rgl_field_t* fields, int32_t field_count);
/**
* Creates or modifies YieldPointsNode.
* The node is a marker what fields are expected by the user.
* Graph input: point cloud
* Graph output: point cloud
* @param node If (*node) == nullptr, a new node will be created. Otherwise, (*node) will be modified.
* @param fields Subsequent fields expected to be available
* @param field_count Number of elements in the `fields` array
*/
RGL_API rgl_status_t
rgl_node_points_yield(rgl_node_t* node, const rgl_field_t* fields, int32_t field_count);
/**
* Creates or modifies CompactNode.
* The node removes non-hit points. In other words, it converts a point cloud into a dense one.
* Graph input: point cloud
* Graph output: point cloud (compacted)
* @param node If (*node) == nullptr, a new node will be created. Otherwise, (*node) will be modified.
*/
RGL_API rgl_status_t
rgl_node_points_compact(rgl_node_t* node);
/**
* Creates or modifies DownSampleNode.
* The node uses VoxelGrid down-sampling filter from PCL library to reduce the number of points.
* Graph input: point cloud
* Graph output: point cloud (downsampled)
* @param node If (*node) == nullptr, a new node will be created. Otherwise, (*node) will be modified.
* @param leaf_size_* Dimensions of the leaf voxel passed to VoxelGrid filter.
*/
RGL_API rgl_status_t
rgl_node_points_downsample(rgl_node_t* node, float leaf_size_x, float leaf_size_y, float leaf_size_z);
/**
* Creates or modifies WritePCDFileNode.
* The node accumulates (merges) point clouds on each run. On destruction, it saves it to the given file.
* Graph input: point cloud
* Graph output: none
* @param node If (*node) == nullptr, a new node will be created. Otherwise, (*node) will be modified.
* @param file_path Path to the output pcd file.
*/
RGL_API rgl_status_t
rgl_node_points_write_pcd_file(rgl_node_t* node, const char* file_path);
/******************************** GRAPH ********************************/
/**
* Starts execution of the RGL graph containing provided node.
* This function is asynchronous.
* @param node Any node from the graph to execute
*/
RGL_API rgl_status_t
rgl_graph_run(rgl_node_t node);
/**
* Destroys RGL graph (all connected nodes) containing provided node.
* @param node Any node from the graph to destroy
*/
RGL_API rgl_status_t
rgl_graph_destroy(rgl_node_t node);
/**
* Obtains the result information of any node in the graph.
* The function will fill output parameters that are not null.
* I.e. The count of the output elements can be queried using a nullptr out_size_of.
* @param node Node to get output from
* @param field Field to get output from. Formatted output with FormatNode should be marked as RGL_FIELD_DYNAMIC_FORMAT.
* @param out_count Returns the number of available elements (e.g. points). May be null.
* @param out_size_of Returns byte size of a single element (e.g. point). May be null.
*/
RGL_API rgl_status_t
rgl_graph_get_result_size(rgl_node_t node, rgl_field_t field, int32_t* out_count, int32_t* out_size_of);
/**
* Obtains the result data of any node in the graph.
* If the result is not yet available, this function will block.
* @param node Node to get output from
* @param field Field to get output from. Formatted output with FormatNode should be marked as RGL_FIELD_DYNAMIC_FORMAT.
* @param data Returns binary data, expects a buffer of size (*out_count) * (*out_size_of) from rgl_graph_get_result_size(...) call.
*/
RGL_API rgl_status_t
rgl_graph_get_result_data(rgl_node_t node, rgl_field_t field, void* data);
/**
* Activates or deactivates node in the graph.
* Children of inactive nodes do not execute as well.
* Nodes are active by default.
* @param node Node to activate/deactivate.
* @param active Whether node active or not.
*/
RGL_API rgl_status_t
rgl_graph_node_set_active(rgl_node_t node, bool active);
/**
* Adds child to the parent node
* @param parent Node that will be set as the parent of (child)
* @param child Node that will be set as the child of (parent)
*/
RGL_API rgl_status_t
rgl_graph_node_add_child(rgl_node_t parent, rgl_node_t child);
/**
* Removes child from the parent node
* @param parent Node that will be removed as parent from (child)
* @param child Node that will be removed as child from (parent)
*/
RGL_API rgl_status_t
rgl_graph_node_remove_child(rgl_node_t parent, rgl_node_t child);