Intel® RealSense™ Cross Platform API
Intel Realsense Cross-platform API
rs.h
Go to the documentation of this file.
1 /* License: Apache 2.0. See LICENSE file in root directory.
2  Copyright(c) 2015 Intel Corporation. All Rights Reserved. */
3 
4 #ifndef LIBREALSENSE_RS_H
5 #define LIBREALSENSE_RS_H
6 
7 #ifdef __cplusplus
8 extern "C" {
9 #endif
10 
11 #define RS_API_MAJOR_VERSION 1
12 #define RS_API_MINOR_VERSION 12
13 #define RS_API_PATCH_VERSION 1
14 
15 #define STRINGIFY(arg) #arg
16 #define VAR_ARG_STRING(arg) STRINGIFY(arg)
17 
18 /* Versioning rules : For each release at least one of [MJR/MNR/PTCH] triple is promoted */
19 /* : Versions that differ by RS_API_PATCH_VERSION only are interface-compatible, i.e. no user-code changes required */
20 /* : Versions that differ by MAJOR/MINOR VERSION component can introduce API changes */
21 /* Version in encoded integer format (1,9,x) -> 01090x. note that each component is limited into [0-99] range by design */
22 #define RS_API_VERSION (((RS_API_MAJOR_VERSION) * 10000) + ((RS_API_MINOR_VERSION) * 100) + (RS_API_PATCH_VERSION))
23 /* Return version in "X.Y.Z" format */
24 #define RS_API_VERSION_STR (VAR_ARG_STRING(RS_API_MAJOR_VERSION.RS_API_MINOR_VERSION.RS_API_PATCH_VERSION))
25 
26 /* streams are different types of data provided by RealSense devices */
27 typedef enum rs_stream
28 {
42 } rs_stream;
43 
44 /* formats define how each stream can be encoded
45  rs_format is closely relateed to Linux pixel-formats, but is trying to abstract away the platform specific constructs */
46 typedef enum rs_format
47 {
63 } rs_format;
64 
65 /* Output buffer format sets how librealsense will work with frame memory */
67 {
72 
73 /* Presets hint general preference that is translated by librealsense into concrete resultion and fps */
74 typedef enum rs_preset
75 {
80 } rs_preset;
81 
82 /* Source allows the user to choose between available hardware subdevices */
83 typedef enum rs_source
84 {
89 } rs_source;
90 
91 /* Distortion model define how pixel coordinates should be mapped to sensor coordinates */
92 typedef enum rs_distortion
93 {
100 
101 /* For SR300 device, ivcam_presets provide optimized settings for specific types of usage */
102 typedef enum rs_ivcam_preset
103 {
117 
118 /* Camera options define general configuration controls.
119  These can generally be mapped to camera UVC controls, and unless stated otherwise can be set/queried at any time */
120 typedef enum rs_option
121 {
191 
192 } rs_option;
193 
194 /* frame metadata enum discriminates between the different types of values provided from the device with each frame */
195 typedef enum rs_frame_metadata
196 {
201 
202 /* rs_capabilities defines the full set of functionality that a RealSense device might provide
203  to check what functionality is supported by a particular device at runtime call dev->supports(capability) */
204 typedef enum rs_capabilities
205 {
217 
218 /* This type defines proprietary formats for direct communication with device firmware */
219 typedef enum rs_blob_type {
222 } rs_blob_type;
223 
224 /* Camera Info feilds are read-only strings that can be queried from the device
225  Not all info feilds are available on all camera types
226  This information is mainly available for camera debug and troubleshooting and should not be used in applications */
227 typedef enum rs_camera_info {
253 
254 /* Severity of the librealsense logger */
255 typedef enum rs_log_severity {
264 
265 /* Source device that tiggered specific timestamp event from the motion module */
266 typedef enum rs_event_source
267 {
277 
278 /* When working with motion microcontroller, motion data timestamps are always in microcontroller timestamp domain.
279  Some frames, however, might not succesfully receive microcontroller timestamp and will be marked as camera domain */
281 {
286 
287 /* Video stream intrinsics */
288 typedef struct rs_intrinsics
289 {
290  int width;
291  int height;
292  float ppx;
293  float ppy;
294  float fx;
295  float fy;
296  rs_distortion model;
297  float coeffs[5];
298 } rs_intrinsics;
299 
300 /* represents motion device intrinsic - scale, bias and variances */
302 {
303  /* Scale X cross axis cross axis Bias X */
304  /* cross axis Scale Y cross axis Bias Y */
305  /* cross axis cross axis Scale Z Bias Z */
306  float data[3][4];
307 
308  float noise_variances[3];
309  float bias_variances[3];
311 
312 /* represents motion module intrinsics including accelerometer and gyro intrinsics */
313 typedef struct rs_motion_intrinsics
314 {
318 
319 /* Cross-stream extrinsics, encode the topology of how the different devices are connected */
320 typedef struct rs_extrinsics
321 {
322  float rotation[9];
323  float translation[3];
324 } rs_extrinsics;
325 
326 /* Timestamp data from the motion microcontroller */
327 typedef struct rs_timestamp_data
328 {
329  double timestamp;
330  rs_event_source source_id;
331  unsigned long long frame_number;
333 
334 /* Motion data from Gyro / Accel from the microcontroller */
335 typedef struct rs_motion_data
336 {
338  unsigned int is_valid;
339  float axes[3];
341 
342 
343 typedef struct rs_context rs_context;
344 typedef struct rs_device rs_device;
345 typedef struct rs_error rs_error;
346 typedef struct rs_frameset rs_frameset;
347 typedef struct rs_frame_ref rs_frame_ref;
352 
353 typedef void (*rs_frame_callback_ptr)(rs_device * dev, rs_frame_ref * frame, void * user);
354 typedef void (*rs_motion_callback_ptr)(rs_device * , rs_motion_data, void * );
355 typedef void (*rs_timestamp_callback_ptr)(rs_device * , rs_timestamp_data, void * );
356 typedef void (*rs_log_callback_ptr)(rs_log_severity min_severity, const char * message, void * user);
357 
364 rs_context * rs_create_context(int api_version, rs_error ** error);
365 
371 void rs_delete_context(rs_context * context, rs_error ** error);
372 
378 int rs_get_device_count(const rs_context * context, rs_error ** error);
379 
386 rs_device * rs_get_device(rs_context * context, int index, rs_error ** error);
387 
393 const char * rs_get_device_name(const rs_device * device, rs_error ** error);
394 
400 const char * rs_get_device_serial(const rs_device * device, rs_error ** error);
401 
407 const char * rs_get_device_info(const rs_device * device, rs_camera_info info, rs_error ** error);
408 
414 const char * rs_get_device_usb_port_id(const rs_device * device, rs_error ** error);
415 
421 const char * rs_get_device_firmware_version(const rs_device * device, rs_error ** error);
422 
430 void rs_get_device_extrinsics(const rs_device * device, rs_stream from_stream, rs_stream to_stream, rs_extrinsics * extrin, rs_error ** error);
431 
438 void rs_get_motion_extrinsics_from(const rs_device * device, rs_stream from, rs_extrinsics * extrin, rs_error ** error);
439 
445 float rs_get_device_depth_scale(const rs_device * device, rs_error ** error);
446 
453 int rs_device_supports_option(const rs_device * device, rs_option option, rs_error ** error);
454 
461 int rs_get_stream_mode_count(const rs_device * device, rs_stream stream, rs_error ** error);
462 
473 void rs_get_stream_mode(const rs_device * device, rs_stream stream, int index, int * width, int * height, rs_format * format, int * framerate, rs_error ** error);
474 
485 void rs_enable_stream_ex(rs_device * device, rs_stream stream, int width, int height, rs_format format, int framerate, rs_output_buffer_format output_format, rs_error ** error);
486 
496 void rs_enable_stream(rs_device * device, rs_stream stream, int width, int height, rs_format format, int framerate, rs_error ** error);
497 
504 void rs_enable_stream_preset(rs_device * device, rs_stream stream, rs_preset preset, rs_error ** error);
505 
511 void rs_disable_stream(rs_device * device, rs_stream stream, rs_error ** error);
512 
519 int rs_is_stream_enabled(const rs_device * device, rs_stream stream, rs_error ** error);
520 
527 int rs_get_stream_width(const rs_device * device, rs_stream stream, rs_error ** error);
528 
535 int rs_get_stream_height(const rs_device * device, rs_stream stream, rs_error ** error);
536 
543 rs_format rs_get_stream_format(const rs_device * device, rs_stream stream, rs_error ** error);
544 
551 int rs_get_stream_framerate(const rs_device * device, rs_stream stream, rs_error ** error);
552 
559 void rs_get_stream_intrinsics(const rs_device * device, rs_stream stream, rs_intrinsics * intrin, rs_error ** error);
560 
566 void rs_get_motion_intrinsics(const rs_device * device, rs_motion_intrinsics * intrinsic, rs_error ** error);
567 
575 void rs_set_frame_callback(rs_device * device, rs_stream stream, rs_frame_callback_ptr on_frame, void * user, rs_error ** error);
576 
585 void rs_enable_motion_tracking(rs_device * device,
586  rs_motion_callback_ptr on_motion_event, void * motion_handler,
587  rs_timestamp_callback_ptr on_timestamp_event, void * timestamp_handler,
588  rs_error ** error);
589 
600 void rs_enable_motion_tracking_cpp(rs_device * device,
601  rs_motion_callback * motion_callback,
602  rs_timestamp_callback * timestamp_callback,
603  rs_error ** error);
604 
612 void rs_set_frame_callback_cpp(rs_device * device, rs_stream stream, rs_frame_callback * callback, rs_error ** error);
613 
617 void rs_disable_motion_tracking(rs_device * device, rs_error ** error);
618 
622 int rs_is_motion_tracking_active(rs_device * device, rs_error ** error);
623 
624 
629 void rs_start_device(rs_device * device, rs_error ** error);
630 
635 void rs_stop_device(rs_device * device, rs_error ** error);
636 
642 void rs_start_source(rs_device * device, rs_source source, rs_error ** error);
643 
649 void rs_stop_source(rs_device * device, rs_source source, rs_error ** error);
650 
656 int rs_is_device_streaming(const rs_device * device, rs_error ** error);
657 
666 void rs_get_device_option_range(rs_device * device, rs_option option, double * min, double * max, double * step, rs_error ** error);
667 
677 void rs_get_device_option_range_ex(rs_device * device, rs_option option, double * min, double * max, double * step, double * def, rs_error ** error);
678 
686 void rs_get_device_options(rs_device * device, const rs_option * options, unsigned int count, double * values, rs_error ** error);
687 
695 void rs_set_device_options(rs_device * device, const rs_option * options, unsigned int count, const double * values, rs_error ** error);
696 
703 void rs_reset_device_options_to_default(rs_device * device, const rs_option* options, int count, rs_error ** error);
704 
711 double rs_get_device_option(rs_device * device, rs_option option, rs_error ** error);
712 
713 
720 const char * rs_get_device_option_description(rs_device * device, rs_option option, rs_error ** error);
721 
722 
729 void rs_set_device_option(rs_device * device, rs_option option, double value, rs_error ** error);
730 
735 void rs_wait_for_frames(rs_device * device, rs_error ** error);
736 
742 int rs_poll_for_frames(rs_device * device, rs_error ** error);
743 
749 int rs_supports(rs_device * device, rs_capabilities capability, rs_error ** error);
750 
756 int rs_supports_camera_info(rs_device * device, rs_camera_info info_param, rs_error ** error);
757 
764 double rs_get_detached_frame_metadata(const rs_frame_ref * frame, rs_frame_metadata frame_metadata, rs_error ** error);
765 
771 int rs_supports_frame_metadata(const rs_frame_ref * frame, rs_frame_metadata frame_metadata, rs_error ** error);
772 
779 double rs_get_frame_timestamp(const rs_device * device, rs_stream stream, rs_error ** error);
780 
787 unsigned long long rs_get_frame_number(const rs_device * device, rs_stream stream, rs_error ** error);
788 
795 const void * rs_get_frame_data(const rs_device * device, rs_stream stream, rs_error ** error);
796 
803 void rs_release_frame(rs_device * device, rs_frame_ref * frame, rs_error ** error);
804 
810 double rs_get_detached_frame_timestamp(const rs_frame_ref * frame, rs_error ** error);
811 
818 rs_timestamp_domain rs_get_detached_frame_timestamp_domain(const rs_frame_ref * frameset, rs_error ** error);
819 
825 unsigned long long rs_get_detached_frame_number(const rs_frame_ref * frame, rs_error ** error);
826 
832 const void * rs_get_detached_frame_data(const rs_frame_ref * frame, rs_error ** error);
833 
839 int rs_get_detached_frame_width(const rs_frame_ref * frame, rs_error ** error);
840 
846 int rs_get_detached_frame_height(const rs_frame_ref * frame, rs_error ** error);
847 
853 int rs_get_detached_framerate(const rs_frame_ref * frameset, rs_error ** error);
854 
860 int rs_get_detached_frame_stride(const rs_frame_ref * frame, rs_error ** error);
861 
867 int rs_get_detached_frame_bpp(const rs_frame_ref * frame, rs_error ** error);
868 
874 rs_format rs_get_detached_frame_format(const rs_frame_ref * frame, rs_error ** error);
875 
881 rs_stream rs_get_detached_frame_stream_type(const rs_frame_ref * frameset, rs_error ** error);
882 
889 void rs_send_blob_to_device(rs_device * device, rs_blob_type type, void * data, int size, rs_error ** error);
890 
896 int rs_get_api_version (rs_error ** error);
897 
903 const char * rs_get_failed_function (const rs_error * error);
904 
910 const char * rs_get_failed_args (const rs_error * error);
911 
917 const char * rs_get_error_message (const rs_error * error);
918 
923 void rs_free_error (rs_error * error);
924 
925 const char * rs_stream_to_string (rs_stream stream);
926 const char * rs_format_to_string (rs_format format);
927 const char * rs_preset_to_string (rs_preset preset);
928 const char * rs_distortion_to_string (rs_distortion distortion);
929 const char * rs_option_to_string (rs_option option);
930 const char * rs_capabilities_to_string(rs_capabilities capability);
931 const char * rs_source_to_string (rs_source source);
932 const char * rs_event_to_string (rs_event_source event);
933 const char * rs_blob_type_to_string (rs_blob_type type);
934 const char * rs_camera_info_to_string(rs_camera_info info);
935 const char * rs_camera_info_to_string(rs_camera_info info);
936 const char * rs_timestamp_domain_to_string(rs_timestamp_domain info);
937 const char * rs_frame_metadata_to_string(rs_frame_metadata md);
938 
944 void rs_log_to_console(rs_log_severity min_severity, rs_error ** error);
945 
952 void rs_log_to_file(rs_log_severity min_severity, const char * file_path, rs_error ** error);
953 
960 void rs_log_to_callback_cpp(rs_log_severity min_severity, rs_log_callback * callback, rs_error ** error);
961 
969 void rs_log_to_callback(rs_log_severity min_severity, rs_log_callback_ptr on_log, void * user, rs_error ** error);
970 
971 #ifdef __cplusplus
972 }
973 #endif
974 #endif
Definition: rs.h:32
int rs_get_stream_width(const rs_device *device, rs_stream stream, rs_error **error)
int rs_supports(rs_device *device, rs_capabilities capability, rs_error **error)
void rs_get_motion_extrinsics_from(const rs_device *device, rs_stream from, rs_extrinsics *extrin, rs_error **error)
void rs_get_stream_intrinsics(const rs_device *device, rs_stream stream, rs_intrinsics *intrin, rs_error **error)
float coeffs[5]
Definition: rs.h:297
Definition: rs.h:85
Definition: rs.h:156
rs_timestamp_data timestamp_data
Definition: rs.h:337
const char * rs_stream_to_string(rs_stream stream)
void rs_start_source(rs_device *device, rs_source source, rs_error **error)
rs_event_source source_id
Definition: rs.h:330
void rs_disable_motion_tracking(rs_device *device, rs_error **error)
Definition: rs.h:79
void rs_log_to_callback_cpp(rs_log_severity min_severity, rs_log_callback *callback, rs_error **error)
Definition: rscore.hpp:132
void rs_enable_motion_tracking(rs_device *device, rs_motion_callback_ptr on_motion_event, void *motion_handler, rs_timestamp_callback_ptr on_timestamp_event, void *timestamp_handler, rs_error **error)
Definition: rs.h:211
const char * rs_source_to_string(rs_source source)
Definition: rs.h:76
Definition: rs.h:258
Definition: rs.h:136
Definition: rs.h:237
Definition: rs.h:94
int rs_supports_frame_metadata(const rs_frame_ref *frame, rs_frame_metadata frame_metadata, rs_error **error)
void(* rs_frame_callback_ptr)(rs_device *dev, rs_frame_ref *frame, void *user)
Definition: rs.h:353
Definition: rs.h:55
Definition: rs.h:154
Definition: rs.h:210
Definition: rs.h:113
Definition: rs.h:275
const char * rs_camera_info_to_string(rs_camera_info info)
Definition: rs.h:241
int rs_get_device_count(const rs_context *context, rs_error **error)
Definition: rs.h:256
frame_metadata
Definition: rs.hpp:155
Definition: rs.h:114
rs_blob_type
Definition: rs.h:219
void rs_log_to_console(rs_log_severity min_severity, rs_error **error)
struct rs_intrinsics rs_intrinsics
Definition: rs.h:151
rs_format rs_get_detached_frame_format(const rs_frame_ref *frame, rs_error **error)
void rs_enable_stream_ex(rs_device *device, rs_stream stream, int width, int height, rs_format format, int framerate, rs_output_buffer_format output_format, rs_error **error)
void rs_get_device_options(rs_device *device, const rs_option *options, unsigned int count, double *values, rs_error **error)
Definition: rs.h:239
void rs_set_device_options(rs_device *device, const rs_option *options, unsigned int count, const double *values, rs_error **error)
void(* rs_motion_callback_ptr)(rs_device *, rs_motion_data, void *)
Definition: rs.h:354
Definition: rs.h:233
unsigned long long rs_get_detached_frame_number(const rs_frame_ref *frame, rs_error **error)
struct rs_frameset rs_frameset
Definition: rs.h:346
Definition: rs.h:97
Definition: rs.h:105
Definition: rs.h:269
double rs_get_frame_timestamp(const rs_device *device, rs_stream stream, rs_error **error)
const void * rs_get_frame_data(const rs_device *device, rs_stream stream, rs_error **error)
int rs_is_device_streaming(const rs_device *device, rs_error **error)
Definition: rs.h:213
float ppy
Definition: rs.h:293
Definition: rs.h:110
Definition: rs.h:209
Definition: rs.h:152
const char * rs_frame_metadata_to_string(rs_frame_metadata md)
Definition: rs.h:272
Definition: rs.h:270
Definition: rs.h:214
rs_timestamp_domain rs_get_detached_frame_timestamp_domain(const rs_frame_ref *frameset, rs_error **error)
const char * rs_distortion_to_string(rs_distortion distortion)
struct rs_timestamp_data rs_timestamp_data
Definition: rs.h:190
void rs_delete_context(rs_context *context, rs_error **error)
void(* rs_log_callback_ptr)(rs_log_severity min_severity, const char *message, void *user)
Definition: rs.h:356
void rs_set_device_option(rs_device *device, rs_option option, double value, rs_error **error)
const char * rs_get_device_name(const rs_device *device, rs_error **error)
Definition: rs.h:208
void rs_reset_device_options_to_default(rs_device *device, const rs_option *options, int count, rs_error **error)
Definition: rs.h:301
Definition: rs.h:228
int rs_get_detached_framerate(const rs_frame_ref *frameset, rs_error **error)
rs_option
Definition: rs.h:120
const char * rs_get_error_message(const rs_error *error)
float rs_get_device_depth_scale(const rs_device *device, rs_error **error)
const char * rs_blob_type_to_string(rs_blob_type type)
Definition: rs.h:128
rs_output_buffer_format
Definition: rs.h:66
Definition: rs.h:126
const char * rs_get_device_usb_port_id(const rs_device *device, rs_error **error)
rs_timestamp_domain
Definition: rs.h:280
Definition: rs.h:262
void rs_log_to_callback(rs_log_severity min_severity, rs_log_callback_ptr on_log, void *user, rs_error **error)
void rs_log_to_file(rs_log_severity min_severity, const char *file_path, rs_error **error)
Definition: rs.h:251
Definition: rs.h:109
option
Definition: rs.hpp:82
struct rs_extrinsics rs_extrinsics
void rs_get_stream_mode(const rs_device *device, rs_stream stream, int index, int *width, int *height, rs_format *format, int *framerate, rs_error **error)
event
Definition: rs.hpp:220
Definition: rs.h:59
Definition: rs.h:49
Definition: rs.h:268
int rs_get_stream_mode_count(const rs_device *device, rs_stream stream, rs_error **error)
Definition: rs.h:124
int rs_poll_for_frames(rs_device *device, rs_error **error)
Definition: rs.h:189
double timestamp
Definition: rs.h:329
Definition: rs.h:131
const char * rs_get_failed_function(const rs_error *error)
Definition: rs.h:115
rs_format rs_get_stream_format(const rs_device *device, rs_stream stream, rs_error **error)
Definition: rs.h:125
rs_context * rs_create_context(int api_version, rs_error **error)
const char * rs_capabilities_to_string(rs_capabilities capability)
double rs_get_device_option(rs_device *device, rs_option option, rs_error **error)
void rs_get_device_option_range_ex(rs_device *device, rs_option option, double *min, double *max, double *step, double *def, rs_error **error)
int rs_get_detached_frame_bpp(const rs_frame_ref *frame, rs_error **error)
stream
Definition: rs.hpp:20
Definition: rs.h:52
Definition: rs.h:273
void rs_disable_stream(rs_device *device, rs_stream stream, rs_error **error)
void rs_set_frame_callback(rs_device *device, rs_stream stream, rs_frame_callback_ptr on_frame, void *user, rs_error **error)
void rs_release_frame(rs_device *device, rs_frame_ref *frame, rs_error **error)
Definition: rs.h:158
Definition: rs.h:104
Definition: rs.h:260
Definition: rs.h:234
Definition: rs.h:335
void rs_get_device_extrinsics(const rs_device *device, rs_stream from_stream, rs_stream to_stream, rs_extrinsics *extrin, rs_error **error)
Definition: rs.h:60
rs_camera_info
Definition: rs.h:227
int rs_device_supports_option(const rs_device *device, rs_option option, rs_error **error)
Definition: rs.h:313
Definition: rs.h:130
format
Definition: rs.hpp:38
void rs_send_blob_to_device(rs_device *device, rs_blob_type type, void *data, int size, rs_error **error)
int rs_get_detached_frame_height(const rs_frame_ref *frame, rs_error **error)
Definition: rs.h:207
Definition: rs.h:221
const char * rs_get_device_firmware_version(const rs_device *device, rs_error **error)
Definition: rs.h:61
Definition: rs.h:87
Definition: rs.h:155
Definition: rs.h:257
const char * rs_get_device_option_description(rs_device *device, rs_option option, rs_error **error)
void rs_enable_stream(rs_device *device, rs_stream stream, int width, int height, rs_format format, int framerate, rs_error **error)
source
Definition: rs.hpp:212
const char * rs_get_failed_args(const rs_error *error)
Definition: rscore.hpp:125
Definition: rs.h:78
Definition: rs.h:284
rs_format
Definition: rs.h:46
Definition: rs.h:261
const char * rs_event_to_string(rs_event_source event)
Definition: rs.h:51
Definition: rscore.hpp:118
double rs_get_detached_frame_timestamp(const rs_frame_ref *frame, rs_error **error)
Definition: rscore.hpp:146
const char * rs_get_device_info(const rs_device *device, rs_camera_info info, rs_error **error)
Definition: rs.h:243
struct rs_error rs_error
Definition: rs.h:345
Definition: rs.h:48
void rs_stop_source(rs_device *device, rs_source source, rs_error **error)
int rs_get_detached_frame_width(const rs_frame_ref *frame, rs_error **error)
Definition: rs.h:327
Definition: rs.h:180
int rs_get_detached_frame_stride(const rs_frame_ref *frame, rs_error **error)
unsigned long long rs_get_frame_number(const rs_device *device, rs_stream stream, rs_error **error)
Definition: rs.h:153
int rs_supports_camera_info(rs_device *device, rs_camera_info info_param, rs_error **error)
void rs_free_error(rs_error *error)
Definition: rs.h:50
Definition: rs.h:56
int height
Definition: rs.h:291
void(* rs_timestamp_callback_ptr)(rs_device *, rs_timestamp_data, void *)
Definition: rs.h:355
float fy
Definition: rs.h:295
struct rs_motion_device_intrinsic rs_motion_device_intrinsic
unsigned int is_valid
Definition: rs.h:338
int rs_get_api_version(rs_error **error)
Definition: rs.h:199
Definition: rs.h:86
rs_source
Definition: rs.h:83
struct rs_motion_intrinsics rs_motion_intrinsics
int width
Definition: rs.h:290
Definition: rs.h:98
Definition: rs.h:35
Definition: rs.h:288
int rs_is_motion_tracking_active(rs_device *device, rs_error **error)
Definition: rs.h:178
Definition: rs.h:271
Definition: rs.h:88
Definition: rs.h:320
const char * rs_timestamp_domain_to_string(rs_timestamp_domain info)
void rs_get_device_option_range(rs_device *device, rs_option option, double *min, double *max, double *step, rs_error **error)
Definition: rs.h:198
const char * rs_preset_to_string(rs_preset preset)
rs_motion_device_intrinsic acc
Definition: rs.h:315
rs_preset
Definition: rs.h:74
Definition: rs.h:187
int rs_get_stream_framerate(const rs_device *device, rs_stream stream, rs_error **error)
const char * rs_format_to_string(rs_format format)
distortion
Definition: rs.hpp:72
rs_stream
Definition: rs.h:27
const char * rs_option_to_string(rs_option option)
struct rs_motion_data rs_motion_data
Definition: rs.h:259
Definition: rs.h:244
Definition: rs.h:179
Definition: rs.h:54
Definition: rs.h:215
Definition: rs.h:129
Definition: rs.h:62
unsigned long long frame_number
Definition: rs.h:331
rs_log_severity
Definition: rs.h:255
Definition: rs.h:139
double rs_get_detached_frame_metadata(const rs_frame_ref *frame, rs_frame_metadata frame_metadata, rs_error **error)
float fx
Definition: rs.h:294
rs_capabilities
Definition: rs.h:204
void rs_set_frame_callback_cpp(rs_device *device, rs_stream stream, rs_frame_callback *callback, rs_error **error)
Definition: rs.h:274
Definition: rs.h:246
Definition: rscore.hpp:64
rs_device * rs_get_device(rs_context *context, int index, rs_error **error)
const char * rs_get_device_serial(const rs_device *device, rs_error **error)
void rs_wait_for_frames(rs_device *device, rs_error **error)
Definition: rs.h:206
Definition: rs.h:137
void rs_enable_stream_preset(rs_device *device, rs_stream stream, rs_preset preset, rs_error **error)
rs_motion_device_intrinsic gyro
Definition: rs.h:316
rs_distortion model
Definition: rs.h:296
Definition: rscore.hpp:139
Definition: rscore.hpp:44
rs_distortion
Definition: rs.h:92
void rs_start_device(rs_device *device, rs_error **error)
Definition: rs.h:53
void rs_stop_device(rs_device *device, rs_error **error)
float ppx
Definition: rs.h:292
rs_frame_metadata
Definition: rs.h:195
Definition: rs.h:134
Definition: rs.h:236
Definition: rs.h:33
Definition: rs.h:29
Definition: rs.h:34
Definition: rs.h:77
Definition: rs.h:57
int rs_is_stream_enabled(const rs_device *device, rs_stream stream, rs_error **error)
Definition: rs.h:282
rs_ivcam_preset
Definition: rs.h:102
Definition: rs.h:58
int rs_get_stream_height(const rs_device *device, rs_stream stream, rs_error **error)
Definition: rs.h:41
Definition: rs.h:112
Definition: rs.h:31
Definition: rs.h:123
rs_stream rs_get_detached_frame_stream_type(const rs_frame_ref *frameset, rs_error **error)
rs_event_source
Definition: rs.h:266
Definition: rs.h:127
const void * rs_get_detached_frame_data(const rs_frame_ref *frame, rs_error **error)
Definition: rs.h:30
void rs_get_motion_intrinsics(const rs_device *device, rs_motion_intrinsics *intrinsic, rs_error **error)
Definition: rs.h:135
preset
Definition: rs.hpp:64
Definition: rs.h:111
void rs_enable_motion_tracking_cpp(rs_device *device, rs_motion_callback *motion_callback, rs_timestamp_callback *timestamp_callback, rs_error **error)
Definition: rs.h:245
Definition: rs.h:235