forked from IntelRealSense/librealsense
-
Notifications
You must be signed in to change notification settings - Fork 4
/
rs_sensor.h
551 lines (487 loc) · 29.8 KB
/
rs_sensor.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
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
/* License: Apache 2.0. See LICENSE file in root directory.
Copyright(c) 2017 Intel Corporation. All Rights Reserved. */
/** \file rs_sensor.h
* \brief
* Exposes RealSense sensor functionality for C compilers
*/
#ifndef LIBREALSENSE_RS2_SENSOR_H
#define LIBREALSENSE_RS2_SENSOR_H
#ifdef __cplusplus
extern "C" {
#endif
#include "rs_types.h"
/** \brief Read-only strings that can be queried from the device.
Not all information attributes are available on all camera types.
This information is mainly available for camera debug and troubleshooting and should not be used in applications. */
typedef enum rs2_camera_info {
RS2_CAMERA_INFO_NAME , /**< Friendly name */
RS2_CAMERA_INFO_SERIAL_NUMBER , /**< Device serial number */
RS2_CAMERA_INFO_FIRMWARE_VERSION , /**< Primary firmware version */
RS2_CAMERA_INFO_RECOMMENDED_FIRMWARE_VERSION , /**< Recommended firmware version */
RS2_CAMERA_INFO_PHYSICAL_PORT , /**< Unique identifier of the port the device is connected to (platform specific) */
RS2_CAMERA_INFO_DEBUG_OP_CODE , /**< If device supports firmware logging, this is the command to send to get logs from firmware */
RS2_CAMERA_INFO_ADVANCED_MODE , /**< True iff the device is in advanced mode */
RS2_CAMERA_INFO_PRODUCT_ID , /**< Product ID as reported in the USB descriptor */
RS2_CAMERA_INFO_CAMERA_LOCKED , /**< True iff EEPROM is locked */
RS2_CAMERA_INFO_USB_TYPE_DESCRIPTOR , /**< Designated USB specification: USB2/USB3 */
RS2_CAMERA_INFO_PRODUCT_LINE , /**< Device product line D400/SR300/L500/T200 */
RS2_CAMERA_INFO_ASIC_SERIAL_NUMBER , /**< ASIC serial number */
RS2_CAMERA_INFO_COUNT /**< Number of enumeration values. Not a valid input: intended to be used in for-loops. */
} rs2_camera_info;
const char* rs2_camera_info_to_string(rs2_camera_info info);
/** \brief Streams are different types of data provided by RealSense devices. */
typedef enum rs2_stream
{
RS2_STREAM_ANY,
RS2_STREAM_DEPTH , /**< Native stream of depth data produced by RealSense device */
RS2_STREAM_COLOR , /**< Native stream of color data captured by RealSense device */
RS2_STREAM_INFRARED , /**< Native stream of infrared data captured by RealSense device */
RS2_STREAM_FISHEYE , /**< Native stream of fish-eye (wide) data captured from the dedicate motion camera */
RS2_STREAM_GYRO , /**< Native stream of gyroscope motion data produced by RealSense device */
RS2_STREAM_ACCEL , /**< Native stream of accelerometer motion data produced by RealSense device */
RS2_STREAM_GPIO , /**< Signals from external device connected through GPIO */
RS2_STREAM_POSE , /**< 6 Degrees of Freedom pose data, calculated by RealSense device */
RS2_STREAM_CONFIDENCE , /**< 4 bit per-pixel depth confidence level */
RS2_STREAM_COUNT
} rs2_stream;
const char* rs2_stream_to_string(rs2_stream stream);
/** \brief A stream's format identifies how binary data is encoded within a frame. */
typedef enum rs2_format
{
RS2_FORMAT_ANY , /**< When passed to enable stream, librealsense will try to provide best suited format */
RS2_FORMAT_Z16 , /**< 16-bit linear depth values. The depth is meters is equal to depth scale * pixel value. */
RS2_FORMAT_DISPARITY16 , /**< 16-bit float-point disparity values. Depth->Disparity conversion : Disparity = Baseline*FocalLength/Depth. */
RS2_FORMAT_XYZ32F , /**< 32-bit floating point 3D coordinates. */
RS2_FORMAT_YUYV , /**< 32-bit y0, u, y1, v data for every two pixels. Similar to YUV422 but packed in a different order - https://en.wikipedia.org/wiki/YUV */
RS2_FORMAT_RGB8 , /**< 8-bit red, green and blue channels */
RS2_FORMAT_BGR8 , /**< 8-bit blue, green, and red channels -- suitable for OpenCV */
RS2_FORMAT_RGBA8 , /**< 8-bit red, green and blue channels + constant alpha channel equal to FF */
RS2_FORMAT_BGRA8 , /**< 8-bit blue, green, and red channels + constant alpha channel equal to FF */
RS2_FORMAT_Y8 , /**< 8-bit per-pixel grayscale image */
RS2_FORMAT_Y16 , /**< 16-bit per-pixel grayscale image */
RS2_FORMAT_RAW10 , /**< Four 10 bits per pixel luminance values packed into a 5-byte macropixel */
RS2_FORMAT_RAW16 , /**< 16-bit raw image */
RS2_FORMAT_RAW8 , /**< 8-bit raw image */
RS2_FORMAT_UYVY , /**< Similar to the standard YUYV pixel format, but packed in a different order */
RS2_FORMAT_MOTION_RAW , /**< Raw data from the motion sensor */
RS2_FORMAT_MOTION_XYZ32F , /**< Motion data packed as 3 32-bit float values, for X, Y, and Z axis */
RS2_FORMAT_GPIO_RAW , /**< Raw data from the external sensors hooked to one of the GPIO's */
RS2_FORMAT_6DOF , /**< Pose data packed as floats array, containing translation vector, rotation quaternion and prediction velocities and accelerations vectors */
RS2_FORMAT_DISPARITY32 , /**< 32-bit float-point disparity values. Depth->Disparity conversion : Disparity = Baseline*FocalLength/Depth */
RS2_FORMAT_Y10BPACK , /**< 16-bit per-pixel grayscale image unpacked from 10 bits per pixel packed ([8:8:8:8:2222]) grey-scale image. The data is unpacked to LSB and padded with 6 zero bits */
RS2_FORMAT_DISTANCE , /**< 32-bit float-point depth distance value. */
RS2_FORMAT_MJPEG , /**< Bitstream encoding for video in which an image of each frame is encoded as JPEG-DIB */
RS2_FORMAT_COUNT /**< Number of enumeration values. Not a valid input: intended to be used in for-loops. */
} rs2_format;
const char* rs2_format_to_string(rs2_format format);
/** \brief Cross-stream extrinsics: encodes the topology describing how the different devices are oriented. */
typedef struct rs2_extrinsics
{
float rotation[9]; /**< Column-major 3x3 rotation matrix */
float translation[3]; /**< Three-element translation vector, in meters */
} rs2_extrinsics;
/**
* Deletes sensors list, any sensors created from this list will remain unaffected
* \param[in] info_list list to delete
*/
void rs2_delete_sensor_list(rs2_sensor_list* info_list);
/**
* Determines number of sensors in a list
* \param[in] info_list The list of connected sensors captured using rs2_query_sensors
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return Sensors count
*/
int rs2_get_sensors_count(const rs2_sensor_list* info_list, rs2_error** error);
/**
* delete relasense sensor
* \param[in] sensor realsense sensor to delete
*/
void rs2_delete_sensor(rs2_sensor* sensor);
/**
* create sensor by index
* \param[in] index the zero based index of sensor to retrieve
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return the requested sensor, should be released by rs2_delete_sensor
*/
rs2_sensor* rs2_create_sensor(const rs2_sensor_list* list, int index, rs2_error** error);
/**
* This is a helper function allowing the user to discover the device from one of its sensors
* \param[in] sensor Pointer to a sensor
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return new device wrapper for the device of the sensor. Needs to be released by delete_device
*/
rs2_device* rs2_create_device_from_sensor(const rs2_sensor* sensor, rs2_error** error);
/**
* retrieve sensor specific information, like versions of various internal components
* \param[in] sensor the RealSense sensor
* \param[in] info camera info type to retrieve
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return the requested camera info string, in a format specific to the device model
*/
const char* rs2_get_sensor_info(const rs2_sensor* sensor, rs2_camera_info info, rs2_error** error);
/**
* check if specific sensor info is supported
* \param[in] info the parameter to check for support
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return true if the parameter both exist and well-defined for the specific device
*/
int rs2_supports_sensor_info(const rs2_sensor* sensor, rs2_camera_info info, rs2_error** error);
/**
* Test if the given sensor can be extended to the requested extension
* \param[in] sensor Realsense sensor
* \param[in] extension The extension to which the sensor should be tested if it is extendable
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return non-zero value iff the sensor can be extended to the given extension
*/
int rs2_is_sensor_extendable_to(const rs2_sensor* sensor, rs2_extension extension, rs2_error** error);
/** When called on a depth sensor, this method will return the number of meters represented by a single depth unit
* \param[in] sensor depth sensor
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return the number of meters represented by a single depth unit
*/
float rs2_get_depth_scale(rs2_sensor* sensor, rs2_error** error);
/**
* Retrieve the stereoscopic baseline value from frame. Applicable to stereo-based depth modules
* \param[out] float Stereoscopic baseline in millimeters
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
float rs2_depth_stereo_frame_get_baseline(const rs2_frame* frame_ref, rs2_error** error);
/**
* Retrieve the stereoscopic baseline value from sensor. Applicable to stereo-based depth modules
* \param[out] float Stereoscopic baseline in millimeters
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
float rs2_get_stereo_baseline(rs2_sensor* sensor, rs2_error** error);
/**
* \brief sets the active region of interest to be used by auto-exposure algorithm
* \param[in] sensor the RealSense sensor
* \param[in] min_x lower horizontal bound in pixels
* \param[in] min_y lower vertical bound in pixels
* \param[in] max_x upper horizontal bound in pixels
* \param[in] max_y upper vertical bound in pixels
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
void rs2_set_region_of_interest(const rs2_sensor* sensor, int min_x, int min_y, int max_x, int max_y, rs2_error** error);
/**
* \brief gets the active region of interest to be used by auto-exposure algorithm
* \param[in] sensor the RealSense sensor
* \param[out] min_x lower horizontal bound in pixels
* \param[out] min_y lower vertical bound in pixels
* \param[out] max_x upper horizontal bound in pixels
* \param[out] max_y upper vertical bound in pixels
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
void rs2_get_region_of_interest(const rs2_sensor* sensor, int* min_x, int* min_y, int* max_x, int* max_y, rs2_error** error);
/**
* open subdevice for exclusive access, by committing to a configuration
* \param[in] device relevant RealSense device
* \param[in] profile stream profile that defines single stream configuration
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
void rs2_open(rs2_sensor* device, const rs2_stream_profile* profile, rs2_error** error);
/**
* open subdevice for exclusive access, by committing to composite configuration, specifying one or more stream profiles
* this method should be used for interdependent streams, such as depth and infrared, that have to be configured together
* \param[in] device relevant RealSense device
* \param[in] profiles list of stream profiles discovered by get_stream_profiles
* \param[in] count number of simultaneous stream profiles to configure
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
void rs2_open_multiple(rs2_sensor* device, const rs2_stream_profile** profiles, int count, rs2_error** error);
/**
* stop any streaming from specified subdevice
* \param[in] sensor RealSense device
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
void rs2_close(const rs2_sensor* sensor, rs2_error** error);
/**
* start streaming from specified configured sensor
* \param[in] sensor RealSense device
* \param[in] on_frame function pointer to register as per-frame callback
* \param[in] user auxiliary data the user wishes to receive together with every frame callback
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
void rs2_start(const rs2_sensor* sensor, rs2_frame_callback_ptr on_frame, void* user, rs2_error** error);
/**
* start streaming from specified configured sensor
* \param[in] sensor RealSense device
* \param[in] callback callback object created from c++ application. ownership over the callback object is moved into the relevant streaming lock
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
void rs2_start_cpp(const rs2_sensor* sensor, rs2_frame_callback* callback, rs2_error** error);
/**
* start streaming from specified configured sensor of specific stream to frame queue
* \param[in] sensor RealSense Sensor
* \param[in] queue frame-queue to store new frames into
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
void rs2_start_queue(const rs2_sensor* sensor, rs2_frame_queue* queue, rs2_error** error);
/**
* stops streaming from specified configured device
* \param[in] sensor RealSense sensor
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
void rs2_stop(const rs2_sensor* sensor, rs2_error** error);
/**
* set callback to get notifications from specified sensor
* \param[in] sensor RealSense device
* \param[in] on_notification function pointer to register as per-notifications callback
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
void rs2_set_notifications_callback(const rs2_sensor* sensor, rs2_notification_callback_ptr on_notification, void* user, rs2_error** error);
/**
* set callback to get notifications from specified device
* \param[in] sensor RealSense sensor
* \param[in] callback callback object created from c++ application. ownership over the callback object is moved into the relevant subdevice lock
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
void rs2_set_notifications_callback_cpp(const rs2_sensor* sensor, rs2_notifications_callback* callback, rs2_error** error);
/**
* retrieve description from notification handle
* \param[in] notification handle returned from a callback
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return the notification description
*/
const char* rs2_get_notification_description(rs2_notification* notification, rs2_error** error);
/**
* retrieve timestamp from notification handle
* \param[in] notification handle returned from a callback
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return the notification timestamp
*/
rs2_time_t rs2_get_notification_timestamp(rs2_notification* notification, rs2_error** error);
/**
* retrieve severity from notification handle
* \param[in] notification handle returned from a callback
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return the notification severity
*/
rs2_log_severity rs2_get_notification_severity(rs2_notification* notification, rs2_error** error);
/**
* retrieve category from notification handle
* \param[in] notification handle returned from a callback
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return the notification category
*/
rs2_notification_category rs2_get_notification_category(rs2_notification* notification, rs2_error** error);
/**
* retrieve serialized data from notification handle
* \param[in] notification handle returned from a callback
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return the serialized data (in JSON format)
*/
const char* rs2_get_notification_serialized_data(rs2_notification* notification, rs2_error** error);
/**
* check if physical subdevice is supported
* \param[in] device input RealSense device
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return list of stream profiles that given subdevice can provide, should be released by rs2_delete_profiles_list
*/
rs2_stream_profile_list* rs2_get_stream_profiles(rs2_sensor* device, rs2_error** error);
/**
* Get pointer to specific stream profile
* \param[in] list the list of supported profiles returned by rs2_get_supported_profiles
* \param[in] index the zero based index of the streaming mode
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
const rs2_stream_profile* rs2_get_stream_profile(const rs2_stream_profile_list* list, int index, rs2_error** error);
/**
* Extract common parameters of a stream profiles
* \param[in] mode input stream profile
* \param[out] stream stream type of the input profile
* \param[out] format binary data format of the input profile
* \param[out] index stream index the input profile in case there are multiple streams of the same type
* \param[out] unique_id identifier for the stream profile, unique within the application
* \param[out] framerate expected rate for data frames to arrive, meaning expected number of frames per second
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
void rs2_get_stream_profile_data(const rs2_stream_profile* mode, rs2_stream* stream, rs2_format* format, int* index, int* unique_id, int* framerate, rs2_error** error);
/**
* Override some of the parameters of the stream profile
* \param[in] mode input stream profile
* \param[in] stream stream type for the profile
* \param[in] format binary data format of the profile
* \param[in] index stream index the profile in case there are multiple streams of the same type
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
void rs2_set_stream_profile_data(rs2_stream_profile* mode, rs2_stream stream, int index, rs2_format format, rs2_error** error);
/**
* Creates a copy of stream profile, assigning new values to some of the fields
* \param[in] mode input stream profile
* \param[in] stream stream type for the profile
* \param[in] format binary data format of the profile
* \param[in] index stream index the profile in case there are multiple streams of the same type
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return new stream profile, must be deleted by rs2_delete_stream_profile
*/
rs2_stream_profile* rs2_clone_stream_profile(const rs2_stream_profile* mode, rs2_stream stream, int index, rs2_format format, rs2_error** error);
/**
* Creates a copy of stream profile, assigning new values to some of the fields
* \param[in] mode input stream profile
* \param[in] stream stream type for the profile
* \param[in] format binary data format of the profile
* \param[in] width new width for the profile
* \param[in] height new height for the profile
* \param[in] intr new intrinsics for the profile
* \param[in] index stream index the profile in case there are multiple streams of the same type
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return new stream profile, must be deleted by rs2_delete_stream_profile
*/
rs2_stream_profile* rs2_clone_video_stream_profile(const rs2_stream_profile* mode, rs2_stream stream, int index, rs2_format format, int width, int height, const rs2_intrinsics* intr, rs2_error** error);
/**
* Delete stream profile allocated by rs2_clone_stream_profile
* Should not be called on stream profiles returned by the device
* \param[in] mode input stream profile
*/
void rs2_delete_stream_profile(rs2_stream_profile* mode);
/**
* Try to extend stream profile to an extension type
* \param[in] mode input stream profile
* \param[in] type extension type, for example RS2_EXTENSION_VIDEO_STREAM_PROFILE
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return non-zero if profile is extendable to specified extension, zero otherwise
*/
int rs2_stream_profile_is(const rs2_stream_profile* mode, rs2_extension type, rs2_error** error);
/**
* When called on a video stream profile, will return the width and the height of the stream
* \param[in] mode input stream profile
* \param[out] width width in pixels of the video stream
* \param[out] height height in pixels of the video stream
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
void rs2_get_video_stream_resolution(const rs2_stream_profile* mode, int* width, int* height, rs2_error** error);
/**
* Obtain the intrinsics of a specific stream configuration from the device.
* \param[in] mode input stream profile
* \param[out] intrinsics Pointer to the struct to store the data in
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
void rs2_get_motion_intrinsics(const rs2_stream_profile* mode, rs2_motion_device_intrinsic * intrinsics, rs2_error ** error);
/**
* Returns non-zero if selected profile is recommended for the sensor
* This is an optional hint we offer to suggest profiles with best performance-quality tradeof
* \param[in] mode input stream profile
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return non-zero if selected profile is recommended for the sensor
*/
int rs2_is_stream_profile_default(const rs2_stream_profile* mode, rs2_error** error);
/**
* get the number of supported stream profiles
* \param[in] list the list of supported profiles returned by rs2_get_supported_profiles
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return number of supported subdevice profiles
*/
int rs2_get_stream_profiles_count(const rs2_stream_profile_list* list, rs2_error** error);
/**
* delete stream profiles list
* \param[in] list the list of supported profiles returned by rs2_get_supported_profiles
*/
void rs2_delete_stream_profiles_list(rs2_stream_profile_list* list);
/**
* \param[in] from origin stream profile
* \param[in] to target stream profile
* \param[out] extrin extrinsics from origin to target
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
void rs2_get_extrinsics(const rs2_stream_profile* from,
const rs2_stream_profile* to,
rs2_extrinsics* extrin, rs2_error** error);
/**
* \param[in] from origin stream profile
* \param[in] to target stream profile
* \param[out] extrin extrinsics from origin to target
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
void rs2_register_extrinsics(const rs2_stream_profile* from,
const rs2_stream_profile* to,
rs2_extrinsics extrin, rs2_error** error);
/**
* When called on a video profile, returns the intrinsics of specific stream configuration
* \param[in] mode input stream profile
* \param[out] intrinsics resulting intrinsics for the video profile
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
*/
void rs2_get_video_stream_intrinsics(const rs2_stream_profile* mode, rs2_intrinsics* intrinsics, rs2_error** error);
/**
* Returns the list of recommended processing blocks for a specific sensor.
* Order and configuration of the blocks are decided by the sensor
* \param[in] sensor input sensor
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return list of supported sensor recommended processing blocks
*/
rs2_processing_block_list* rs2_get_recommended_processing_blocks(rs2_sensor* sensor, rs2_error** error);
/**
* Returns specific processing blocks from processing blocks list
* \param[in] list the processing blocks list
* \param[in] index the requested processing block
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return processing block
*/
rs2_processing_block* rs2_get_processing_block(const rs2_processing_block_list* list, int index, rs2_error** error);
/**
* Returns the processing blocks list size
* \param[in] list the processing blocks list
* \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return the processing block list size
*/
int rs2_get_recommended_processing_blocks_count(const rs2_processing_block_list* list, rs2_error** error);
/**
* Deletes processing blocks list
* \param[in] list list to delete
*/
void rs2_delete_recommended_processing_blocks(rs2_processing_block_list* list);
/**
* Imports a localization map from file to tm2 tracking device
* \param[in] sensor TM2 position-tracking sensor
* \param[in] lmap_blob Localization map raw buffer, serialized
* \param[in] blob_size The buffer's size in bytes
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return Non-zero if succeeded, otherwise 0
*/
int rs2_import_localization_map(const rs2_sensor* sensor, const unsigned char* lmap_blob, unsigned int blob_size, rs2_error** error);
/**
* Extract and store the localization map of tm2 tracking device to file
* \param[in] sensor TM2 position-tracking sensor
* \param[in] lmap_fname The file name of the localization map
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return Device's response in a rs2_raw_data_buffer, which should be released by rs2_delete_raw_data
*/
//void rs2_export_localization_map(const rs2_sensor* sensor, const char* lmap_fname, rs2_error** error);
const rs2_raw_data_buffer* rs2_export_localization_map(const rs2_sensor* sensor, rs2_error** error);
/**
* Create a named location tag
* \param[in] sensor T2xx position-tracking sensor
* \param[in] guid Null-terminated string of up to 127 characters
* \param[in] pos Position in meters, relative to the current tracking session
* \param[in] orient Quaternion orientation, expressed the the coordinate system of the current tracking session
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return Non-zero if succeeded, otherwise 0
*/
int rs2_set_static_node(const rs2_sensor* sensor, const char* guid, const rs2_vector pos, const rs2_quaternion orient, rs2_error** error);
/**
* Create a named location tag
* \param[in] sensor T2xx position-tracking sensor
* \param[in] guid Null-terminated string of up to 127 characters
* \param[out] pos Position in meters of the tagged (stored) location
* \param[out] orient Quaternion orientation of the tagged (stored) location
* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored
* \return Non-zero if succeeded, otherwise 0
*/
int rs2_get_static_node(const rs2_sensor* sensor, const char* guid, rs2_vector *pos, rs2_quaternion *orient, rs2_error** error);
/** Load Wheel odometer settings from host to device
* \param[in] odometry_config_buf odometer configuration/calibration blob serialized from jsom file
* \return true on success
*/
int rs2_load_wheel_odometry_config(const rs2_sensor* sensor, const unsigned char* odometry_config_buf, unsigned int blob_size, rs2_error** error);
/** Send wheel odometry data for each individual sensor (wheel)
* \param[in] wo_sensor_id - Zero-based index of (wheel) sensor with the same type within device
* \param[in] frame_num - Monotonocally increasing frame number, managed per sensor.
* \param[in] translational_velocity - Translational velocity of the wheel sensor [meter/sec]
* \return true on success
*/
int rs2_send_wheel_odometry(const rs2_sensor* sensor, char wo_sensor_id, unsigned int frame_num,
const rs2_vector translational_velocity, rs2_error** error);
#ifdef __cplusplus
}
#endif
#endif // LIBREALSENSE_RS2_SENSOR_H