rs.h
Go to the documentation of this file.
00001 /* License: Apache 2.0. See LICENSE file in root directory.
00002    Copyright(c) 2015 Intel Corporation. All Rights Reserved. */
00003 
00010 #ifndef LIBREALSENSE_RS_H
00011 #define LIBREALSENSE_RS_H
00012 
00013 #ifdef __cplusplus
00014 extern "C" {
00015 #endif
00016 
00017 #define RS_API_MAJOR_VERSION    1
00018 #define RS_API_MINOR_VERSION    12
00019 #define RS_API_PATCH_VERSION    3
00020 
00021 #define STRINGIFY(arg) #arg
00022 #define VAR_ARG_STRING(arg) STRINGIFY(arg)
00023 
00024 /* Versioning rules            : For each release at least one of [MJR/MNR/PTCH] triple is promoted                                             */
00025 /*                             : Versions that differ by RS_API_PATCH_VERSION only are interface-compatible, i.e. no user-code changes required */
00026 /*                             : Versions that differ by MAJOR/MINOR VERSION component can introduce API changes                                */
00027 /* Version in encoded integer format (1,9,x) -> 01090x. note that each component is limited into [0-99] range by design                         */
00028 #define RS_API_VERSION  (((RS_API_MAJOR_VERSION) * 10000) + ((RS_API_MINOR_VERSION) * 100) + (RS_API_PATCH_VERSION))
00029 /* Return version in "X.Y.Z" format */
00030 #define RS_API_VERSION_STR (VAR_ARG_STRING(RS_API_MAJOR_VERSION.RS_API_MINOR_VERSION.RS_API_PATCH_VERSION))
00031 
00033 typedef enum rs_stream
00034 {
00035     RS_STREAM_DEPTH                            , 
00036     RS_STREAM_COLOR                            , 
00037     RS_STREAM_INFRARED                         , 
00038     RS_STREAM_INFRARED2                        , 
00039     RS_STREAM_FISHEYE                          , 
00040     RS_STREAM_POINTS                           , 
00041     RS_STREAM_RECTIFIED_COLOR                  , 
00042     RS_STREAM_COLOR_ALIGNED_TO_DEPTH           , 
00043     RS_STREAM_INFRARED2_ALIGNED_TO_DEPTH       , 
00044     RS_STREAM_DEPTH_ALIGNED_TO_COLOR           , 
00045     RS_STREAM_DEPTH_ALIGNED_TO_RECTIFIED_COLOR , 
00046     RS_STREAM_DEPTH_ALIGNED_TO_INFRARED2       , 
00047     RS_STREAM_COUNT                              
00048 } rs_stream;
00049 
00053 typedef enum rs_format
00054 {
00055     RS_FORMAT_ANY         , 
00056     RS_FORMAT_Z16         , 
00057     RS_FORMAT_DISPARITY16 , 
00058     RS_FORMAT_XYZ32F      , 
00059     RS_FORMAT_YUYV        , 
00060     RS_FORMAT_RGB8        , 
00061     RS_FORMAT_BGR8        , 
00062     RS_FORMAT_RGBA8       , 
00063     RS_FORMAT_BGRA8       , 
00064     RS_FORMAT_Y8          , 
00065     RS_FORMAT_Y16         , 
00066     RS_FORMAT_RAW10       , 
00067     RS_FORMAT_RAW16       , 
00068     RS_FORMAT_RAW8        , 
00069     RS_FORMAT_COUNT         
00070 } rs_format;
00071 
00073 typedef enum rs_output_buffer_format
00074 {
00075     RS_OUTPUT_BUFFER_FORMAT_CONTINUOUS     , 
00076     RS_OUTPUT_BUFFER_FORMAT_NATIVE         , 
00077     RS_OUTPUT_BUFFER_FORMAT_COUNT            
00078 } rs_output_buffer_format;
00079 
00081 typedef enum rs_preset
00082 {
00083     RS_PRESET_BEST_QUALITY     , 
00084     RS_PRESET_LARGEST_IMAGE    , 
00085     RS_PRESET_HIGHEST_FRAMERATE, 
00086     RS_PRESET_COUNT              
00087 } rs_preset;
00088 
00090 typedef enum rs_source
00091 {
00092     RS_SOURCE_VIDEO          , 
00093     RS_SOURCE_MOTION_TRACKING, 
00094     RS_SOURCE_ALL            , 
00095     RS_SOURCE_COUNT            
00096 } rs_source;
00097 
00099 typedef enum rs_distortion
00100 {
00101     RS_DISTORTION_NONE                  , 
00102     RS_DISTORTION_MODIFIED_BROWN_CONRADY, 
00103     RS_DISTORTION_INVERSE_BROWN_CONRADY , 
00104     RS_DISTORTION_FTHETA                , 
00105     RS_DISTORTION_COUNT                   
00106 } rs_distortion;
00107 
00109 typedef enum rs_ivcam_preset
00110 {
00111     RS_IVCAM_PRESET_SHORT_RANGE             , 
00112     RS_IVCAM_PRESET_LONG_RANGE              , 
00113     RS_IVCAM_PRESET_BACKGROUND_SEGMENTATION , 
00114     RS_IVCAM_PRESET_GESTURE_RECOGNITION     , 
00115     RS_IVCAM_PRESET_OBJECT_SCANNING         , 
00116     RS_IVCAM_PRESET_FACE_ANALYTICS          , 
00117     RS_IVCAM_PRESET_FACE_LOGIN              , 
00118     RS_IVCAM_PRESET_GR_CURSOR               , 
00119     RS_IVCAM_PRESET_DEFAULT                 , 
00120     RS_IVCAM_PRESET_MID_RANGE               , 
00121     RS_IVCAM_PRESET_IR_ONLY                 , 
00122     RS_IVCAM_PRESET_COUNT                     
00123 } rs_ivcam_preset;
00124 
00128 typedef enum rs_option
00129 {
00130     RS_OPTION_COLOR_BACKLIGHT_COMPENSATION                    , 
00131     RS_OPTION_COLOR_BRIGHTNESS                                , 
00132     RS_OPTION_COLOR_CONTRAST                                  , 
00133     RS_OPTION_COLOR_EXPOSURE                                  , 
00134     RS_OPTION_COLOR_GAIN                                      , 
00135     RS_OPTION_COLOR_GAMMA                                     , 
00136     RS_OPTION_COLOR_HUE                                       , 
00137     RS_OPTION_COLOR_SATURATION                                , 
00138     RS_OPTION_COLOR_SHARPNESS                                 , 
00139     RS_OPTION_COLOR_WHITE_BALANCE                             , 
00140     RS_OPTION_COLOR_ENABLE_AUTO_EXPOSURE                      , 
00141     RS_OPTION_COLOR_ENABLE_AUTO_WHITE_BALANCE                 , 
00142     RS_OPTION_F200_LASER_POWER                                , 
00143     RS_OPTION_F200_ACCURACY                                   , 
00144     RS_OPTION_F200_MOTION_RANGE                               , 
00145     RS_OPTION_F200_FILTER_OPTION                              , 
00146     RS_OPTION_F200_CONFIDENCE_THRESHOLD                       , 
00147     RS_OPTION_F200_DYNAMIC_FPS                                , 
00148     RS_OPTION_SR300_AUTO_RANGE_ENABLE_MOTION_VERSUS_RANGE     , 
00149     RS_OPTION_SR300_AUTO_RANGE_ENABLE_LASER                   , 
00150     RS_OPTION_SR300_AUTO_RANGE_MIN_MOTION_VERSUS_RANGE        , 
00151     RS_OPTION_SR300_AUTO_RANGE_MAX_MOTION_VERSUS_RANGE        , 
00152     RS_OPTION_SR300_AUTO_RANGE_START_MOTION_VERSUS_RANGE      , 
00153     RS_OPTION_SR300_AUTO_RANGE_MIN_LASER                      , 
00154     RS_OPTION_SR300_AUTO_RANGE_MAX_LASER                      , 
00155     RS_OPTION_SR300_AUTO_RANGE_START_LASER                    , 
00156     RS_OPTION_SR300_AUTO_RANGE_UPPER_THRESHOLD                , 
00157     RS_OPTION_SR300_AUTO_RANGE_LOWER_THRESHOLD                , 
00158     RS_OPTION_R200_LR_AUTO_EXPOSURE_ENABLED                   , 
00159     RS_OPTION_R200_LR_GAIN                                    , 
00160     RS_OPTION_R200_LR_EXPOSURE                                , 
00161     RS_OPTION_R200_EMITTER_ENABLED                            , 
00162     RS_OPTION_R200_DEPTH_UNITS                                , 
00163     RS_OPTION_R200_DEPTH_CLAMP_MIN                            , 
00164     RS_OPTION_R200_DEPTH_CLAMP_MAX                            , 
00165     RS_OPTION_R200_DISPARITY_MULTIPLIER                       , 
00166     RS_OPTION_R200_DISPARITY_SHIFT                            , 
00167     RS_OPTION_R200_AUTO_EXPOSURE_MEAN_INTENSITY_SET_POINT     , 
00168     RS_OPTION_R200_AUTO_EXPOSURE_BRIGHT_RATIO_SET_POINT       , 
00169     RS_OPTION_R200_AUTO_EXPOSURE_KP_GAIN                      , 
00170     RS_OPTION_R200_AUTO_EXPOSURE_KP_EXPOSURE                  , 
00171     RS_OPTION_R200_AUTO_EXPOSURE_KP_DARK_THRESHOLD            , 
00172     RS_OPTION_R200_AUTO_EXPOSURE_TOP_EDGE                     , 
00173     RS_OPTION_R200_AUTO_EXPOSURE_BOTTOM_EDGE                  , 
00174     RS_OPTION_R200_AUTO_EXPOSURE_LEFT_EDGE                    , 
00175     RS_OPTION_R200_AUTO_EXPOSURE_RIGHT_EDGE                   , 
00176     RS_OPTION_R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_DECREMENT    , 
00177     RS_OPTION_R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_INCREMENT    , 
00178     RS_OPTION_R200_DEPTH_CONTROL_MEDIAN_THRESHOLD             , 
00179     RS_OPTION_R200_DEPTH_CONTROL_SCORE_MINIMUM_THRESHOLD      , 
00180     RS_OPTION_R200_DEPTH_CONTROL_SCORE_MAXIMUM_THRESHOLD      , 
00181     RS_OPTION_R200_DEPTH_CONTROL_TEXTURE_COUNT_THRESHOLD      , 
00182     RS_OPTION_R200_DEPTH_CONTROL_TEXTURE_DIFFERENCE_THRESHOLD , 
00183     RS_OPTION_R200_DEPTH_CONTROL_SECOND_PEAK_THRESHOLD        , 
00184     RS_OPTION_R200_DEPTH_CONTROL_NEIGHBOR_THRESHOLD           , 
00185     RS_OPTION_R200_DEPTH_CONTROL_LR_THRESHOLD                 , 
00186     RS_OPTION_FISHEYE_EXPOSURE                                , 
00187     RS_OPTION_FISHEYE_GAIN                                    , 
00188     RS_OPTION_FISHEYE_STROBE                                  , 
00189     RS_OPTION_FISHEYE_EXTERNAL_TRIGGER                        , 
00190     RS_OPTION_FISHEYE_ENABLE_AUTO_EXPOSURE                    , 
00191     RS_OPTION_FISHEYE_AUTO_EXPOSURE_MODE                      , 
00192     RS_OPTION_FISHEYE_AUTO_EXPOSURE_ANTIFLICKER_RATE          , 
00193     RS_OPTION_FISHEYE_AUTO_EXPOSURE_PIXEL_SAMPLE_RATE         , 
00194     RS_OPTION_FISHEYE_AUTO_EXPOSURE_SKIP_FRAMES               , 
00195     RS_OPTION_FRAMES_QUEUE_SIZE                               , 
00196     RS_OPTION_HARDWARE_LOGGER_ENABLED                         , 
00197     RS_OPTION_TOTAL_FRAME_DROPS                               , 
00198     RS_OPTION_COUNT                                           , 
00200 } rs_option;
00201 
00203 typedef enum rs_frame_metadata
00204 {
00205     RS_FRAME_METADATA_ACTUAL_EXPOSURE, 
00206     RS_FRAME_METADATA_ACTUAL_FPS,      
00207     RS_FRAME_METADATA_COUNT            
00208 } rs_frame_metadata;
00209 
00213 typedef enum rs_capabilities
00214 {
00215     RS_CAPABILITIES_DEPTH,                      
00216     RS_CAPABILITIES_COLOR,                      
00217     RS_CAPABILITIES_INFRARED,                   
00218     RS_CAPABILITIES_INFRARED2,                  
00219     RS_CAPABILITIES_FISH_EYE,                   
00220     RS_CAPABILITIES_MOTION_EVENTS,              
00221     RS_CAPABILITIES_MOTION_MODULE_FW_UPDATE,    
00222     RS_CAPABILITIES_ADAPTER_BOARD,              
00223     RS_CAPABILITIES_ENUMERATION,                
00224     RS_CAPABILITIES_COUNT,                      
00225 } rs_capabilities;
00226 
00228 typedef enum rs_blob_type {
00229     RS_BLOB_TYPE_MOTION_MODULE_FIRMWARE_UPDATE, 
00230     RS_BLOB_TYPE_COUNT                          
00231 }  rs_blob_type;
00232 
00237 typedef enum rs_camera_info {
00238     RS_CAMERA_INFO_DEVICE_NAME                   , 
00239     RS_CAMERA_INFO_DEVICE_SERIAL_NUMBER          , 
00240     RS_CAMERA_INFO_CAMERA_FIRMWARE_VERSION       , 
00241     RS_CAMERA_INFO_ADAPTER_BOARD_FIRMWARE_VERSION, 
00242     RS_CAMERA_INFO_MOTION_MODULE_FIRMWARE_VERSION, 
00243     RS_CAMERA_INFO_CAMERA_TYPE                   , 
00244     RS_CAMERA_INFO_OEM_ID                        , 
00245     RS_CAMERA_INFO_ISP_FW_VERSION                , 
00246     RS_CAMERA_INFO_CONTENT_VERSION               , 
00247     RS_CAMERA_INFO_MODULE_VERSION                , 
00248     RS_CAMERA_INFO_IMAGER_MODEL_NUMBER           , 
00249     RS_CAMERA_INFO_BUILD_DATE                    , 
00250     RS_CAMERA_INFO_CALIBRATION_DATE              , 
00251     RS_CAMERA_INFO_PROGRAM_DATE                  , 
00252     RS_CAMERA_INFO_FOCUS_ALIGNMENT_DATE          , 
00253     RS_CAMERA_INFO_EMITTER_TYPE                  , 
00254     RS_CAMERA_INFO_FOCUS_VALUE                   , 
00255     RS_CAMERA_INFO_LENS_TYPE                     , 
00256     RS_CAMERA_INFO_3RD_LENS_TYPE                 , 
00257     RS_CAMERA_INFO_LENS_COATING__TYPE            , 
00258     RS_CAMERA_INFO_3RD_LENS_COATING_TYPE         , 
00259     RS_CAMERA_INFO_NOMINAL_BASELINE              , 
00260     RS_CAMERA_INFO_3RD_NOMINAL_BASELINE          , 
00261     RS_CAMERA_INFO_COUNT                           
00262 } rs_camera_info;
00263 
00265 typedef enum rs_log_severity {
00266     RS_LOG_SEVERITY_DEBUG, 
00267     RS_LOG_SEVERITY_INFO , 
00268     RS_LOG_SEVERITY_WARN , 
00269     RS_LOG_SEVERITY_ERROR, 
00270     RS_LOG_SEVERITY_FATAL, 
00271     RS_LOG_SEVERITY_NONE , 
00272     RS_LOG_SEVERITY_COUNT  
00273 } rs_log_severity;
00274 
00276 typedef enum rs_event_source
00277 {
00278     RS_EVENT_IMU_ACCEL     , 
00279     RS_EVENT_IMU_GYRO      , 
00280     RS_EVENT_IMU_DEPTH_CAM , 
00281     RS_EVENT_IMU_MOTION_CAM, 
00282     RS_EVENT_G0_SYNC       , 
00283     RS_EVENT_G1_SYNC       , 
00284     RS_EVENT_G2_SYNC       , 
00285     RS_EVENT_SOURCE_COUNT    
00286 }rs_event_source;
00287 
00292 typedef enum rs_timestamp_domain
00293 {
00294     RS_TIMESTAMP_DOMAIN_CAMERA         , 
00295     RS_TIMESTAMP_DOMAIN_MICROCONTROLLER, 
00296     RS_TIMESTAMP_DOMAIN_COUNT            
00297 }rs_timestamp_domain;
00298 
00300 typedef struct rs_intrinsics
00301 {
00302     int           width;     
00303     int           height;    
00304     float         ppx;       
00305     float         ppy;       
00306     float         fx;        
00307     float         fy;        
00308     rs_distortion model;     
00309     float         coeffs[5]; 
00310 } rs_intrinsics;
00311 
00313 typedef struct rs_motion_device_intrinsic
00314 {
00315     /* Scale X        cross axis        cross axis      Bias X */
00316     /* cross axis     Scale Y           cross axis      Bias Y */
00317     /* cross axis     cross axis        Scale Z         Bias Z */
00318     float data[3][4];          
00320     float noise_variances[3];  
00321     float bias_variances[3];   
00322 } rs_motion_device_intrinsic;
00323 
00325 typedef struct rs_motion_intrinsics
00326 {
00327     rs_motion_device_intrinsic acc;
00328     rs_motion_device_intrinsic gyro;
00329 } rs_motion_intrinsics;
00330 
00332 typedef struct rs_extrinsics
00333 {
00334     float rotation[9];    
00335     float translation[3]; 
00336 } rs_extrinsics;
00337 
00339 typedef struct rs_timestamp_data
00340 {
00341     double              timestamp;     
00342     rs_event_source     source_id;     
00343     unsigned long long  frame_number;  
00344 } rs_timestamp_data;
00345 
00347 typedef struct rs_motion_data
00348 {
00349     rs_timestamp_data   timestamp_data; 
00350     unsigned int        is_valid;   
00351     float               axes[3];    
00352 } rs_motion_data;
00353 
00354 
00355 typedef struct rs_context rs_context;
00356 typedef struct rs_device rs_device;
00357 typedef struct rs_error rs_error;
00358 typedef struct rs_frameset rs_frameset;
00359 typedef struct rs_frame_ref rs_frame_ref;
00360 typedef struct rs_motion_callback rs_motion_callback;
00361 typedef struct rs_frame_callback rs_frame_callback;
00362 typedef struct rs_timestamp_callback rs_timestamp_callback;
00363 typedef struct rs_log_callback rs_log_callback;
00364 
00365 typedef void (*rs_frame_callback_ptr)(rs_device * dev, rs_frame_ref * frame, void * user);
00366 typedef void (*rs_motion_callback_ptr)(rs_device * , rs_motion_data, void * );
00367 typedef void (*rs_timestamp_callback_ptr)(rs_device * , rs_timestamp_data, void * );
00368 typedef void (*rs_log_callback_ptr)(rs_log_severity min_severity, const char * message, void * user);
00369 
00376 rs_context * rs_create_context(int api_version, rs_error ** error);
00377 
00385 void rs_delete_context(rs_context * context, rs_error ** error);
00386 
00393 int rs_get_device_count(const rs_context * context, rs_error ** error);
00394 
00402 rs_device * rs_get_device(rs_context * context, int index, rs_error ** error);
00403 
00410 const char * rs_get_device_name(const rs_device * device, rs_error ** error);
00411 
00418 const char * rs_get_device_serial(const rs_device * device, rs_error ** error);
00419 
00427 const char * rs_get_device_info(const rs_device * device, rs_camera_info info, rs_error ** error);
00428 
00435 const char * rs_get_device_usb_port_id(const rs_device * device, rs_error ** error);
00436 
00443 const char * rs_get_device_firmware_version(const rs_device * device, rs_error ** error);
00444 
00453 void rs_get_device_extrinsics(const rs_device * device, rs_stream from_stream, rs_stream to_stream, rs_extrinsics * extrin, rs_error ** error);
00454 
00462 void rs_get_motion_extrinsics_from(const rs_device * device, rs_stream from, rs_extrinsics * extrin, rs_error ** error);
00463 
00470 float rs_get_device_depth_scale(const rs_device * device, rs_error ** error);
00471 
00479 int rs_device_supports_option(const rs_device * device, rs_option option, rs_error ** error);
00480 
00488 int rs_get_stream_mode_count(const rs_device * device, rs_stream stream, rs_error ** error);
00489 
00501 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);
00502 
00514 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);
00515 
00526 void rs_enable_stream(rs_device * device, rs_stream stream, int width, int height, rs_format format, int framerate, rs_error ** error);
00527 
00535 void rs_enable_stream_preset(rs_device * device, rs_stream stream, rs_preset preset, rs_error ** error);
00536 
00543 void rs_disable_stream(rs_device * device, rs_stream stream, rs_error ** error);
00544 
00552 int rs_is_stream_enabled(const rs_device * device, rs_stream stream, rs_error ** error);
00553 
00561 int rs_get_stream_width(const rs_device * device, rs_stream stream, rs_error ** error);
00562 
00570 int rs_get_stream_height(const rs_device * device, rs_stream stream, rs_error ** error);
00571 
00579 rs_format rs_get_stream_format(const rs_device * device, rs_stream stream, rs_error ** error);
00580 
00588 int rs_get_stream_framerate(const rs_device * device, rs_stream stream, rs_error ** error);
00589 
00597 void rs_get_stream_intrinsics(const rs_device * device, rs_stream stream, rs_intrinsics * intrin, rs_error ** error);
00598 
00605 void rs_get_motion_intrinsics(const rs_device * device, rs_motion_intrinsics * intrinsic, rs_error ** error);
00606 
00616 void rs_set_frame_callback(rs_device * device, rs_stream stream, rs_frame_callback_ptr on_frame, void * user, rs_error ** error);
00617 
00628 void rs_enable_motion_tracking(rs_device * device,
00629     rs_motion_callback_ptr on_motion_event, void * motion_handler,
00630     rs_timestamp_callback_ptr on_timestamp_event, void * timestamp_handler,
00631     rs_error ** error);
00632 
00654 void rs_enable_motion_tracking_cpp(rs_device * device,
00655     rs_motion_callback * motion_callback,
00656     rs_timestamp_callback * timestamp_callback,
00657     rs_error ** error);
00658 
00669 void rs_set_frame_callback_cpp(rs_device * device, rs_stream stream, rs_frame_callback * callback, rs_error ** error);
00670 
00676 void rs_disable_motion_tracking(rs_device * device, rs_error ** error);
00677 
00684 int rs_is_motion_tracking_active(rs_device * device, rs_error ** error);
00685 
00686 
00692 void rs_start_device(rs_device * device, rs_error ** error);
00693 
00699 void rs_stop_device(rs_device * device, rs_error ** error);
00700 
00707 void rs_start_source(rs_device * device, rs_source source, rs_error ** error);
00708 
00715 void rs_stop_source(rs_device * device, rs_source source, rs_error ** error);
00716 
00723 int rs_is_device_streaming(const rs_device * device, rs_error ** error);
00724 
00734 void rs_get_device_option_range(rs_device * device, rs_option option, double * min, double * max, double * step, rs_error ** error);
00735 
00746 void rs_get_device_option_range_ex(rs_device * device, rs_option option, double * min, double * max, double * step, double * def, rs_error ** error);
00747 
00756 void rs_get_device_options(rs_device * device, const rs_option * options, unsigned int count, double * values, rs_error ** error);
00757 
00766 void rs_set_device_options(rs_device * device, const rs_option * options, unsigned int count, const double * values, rs_error ** error);
00767 
00775 void rs_reset_device_options_to_default(rs_device * device, const rs_option* options, int count, rs_error ** error);
00776 
00784 double rs_get_device_option(rs_device * device, rs_option option, rs_error ** error);
00785 
00786 
00794 const char * rs_get_device_option_description(rs_device * device, rs_option option, rs_error ** error);
00795 
00796 
00804 void rs_set_device_option(rs_device * device, rs_option option, double value, rs_error ** error);
00805 
00811 void rs_wait_for_frames(rs_device * device, rs_error ** error);
00812 
00819 int rs_poll_for_frames(rs_device * device, rs_error ** error);
00820 
00828 int rs_supports(rs_device * device, rs_capabilities capability, rs_error ** error);
00829 
00837 int rs_supports_camera_info(rs_device * device, rs_camera_info info_param, rs_error ** error);
00838 
00846 double rs_get_detached_frame_metadata(const rs_frame_ref * frame, rs_frame_metadata frame_metadata, rs_error ** error);
00847 
00855 int rs_supports_frame_metadata(const rs_frame_ref * frame, rs_frame_metadata frame_metadata, rs_error ** error);
00856 
00864 double rs_get_frame_timestamp(const rs_device * device, rs_stream stream, rs_error ** error);
00865 
00873 unsigned long long rs_get_frame_number(const rs_device * device, rs_stream stream, rs_error ** error);
00874 
00882 const void * rs_get_frame_data(const rs_device * device, rs_stream stream, rs_error ** error);
00883 
00891 void rs_release_frame(rs_device * device, rs_frame_ref * frame, rs_error ** error);
00892 
00899 double rs_get_detached_frame_timestamp(const rs_frame_ref * frame, rs_error ** error);
00900 
00909 rs_timestamp_domain rs_get_detached_frame_timestamp_domain(const rs_frame_ref * frame, rs_error ** error);
00910 
00917 unsigned long long rs_get_detached_frame_number(const rs_frame_ref * frame, rs_error ** error);
00918 
00925 const void * rs_get_detached_frame_data(const rs_frame_ref * frame, rs_error ** error);
00926 
00933 int rs_get_detached_frame_width(const rs_frame_ref * frame, rs_error ** error);
00934 
00941 int rs_get_detached_frame_height(const rs_frame_ref * frame, rs_error ** error);
00942 
00949 int rs_get_detached_framerate(const rs_frame_ref * frame, rs_error ** error);
00950 
00957 int rs_get_detached_frame_stride(const rs_frame_ref * frame, rs_error ** error);
00958 
00965 int rs_get_detached_frame_bpp(const rs_frame_ref * frame, rs_error ** error);
00966 
00973 rs_format rs_get_detached_frame_format(const rs_frame_ref * frame, rs_error ** error);
00974 
00981 rs_stream rs_get_detached_frame_stream_type(const rs_frame_ref * frame, rs_error ** error);
00982 
00992 void rs_send_blob_to_device(rs_device * device, rs_blob_type type, void * data, int size, rs_error ** error);
00993 
00999 int          rs_get_api_version      (rs_error ** error);
01000 
01006 const char * rs_get_failed_function  (const rs_error * error);
01007 
01013 const char * rs_get_failed_args      (const rs_error * error);
01014 
01020 const char * rs_get_error_message    (const rs_error * error);
01021 
01026 void         rs_free_error           (rs_error * error);
01027 
01028 const char * rs_stream_to_string     (rs_stream stream); 
01029 const char * rs_format_to_string     (rs_format format);
01030 const char * rs_preset_to_string     (rs_preset preset);
01031 const char * rs_distortion_to_string (rs_distortion distortion);
01032 const char * rs_option_to_string     (rs_option option);
01033 const char * rs_capabilities_to_string(rs_capabilities capability);
01034 const char * rs_source_to_string     (rs_source source);
01035 const char * rs_event_to_string      (rs_event_source event);
01036 const char * rs_blob_type_to_string  (rs_blob_type type);
01037 const char * rs_camera_info_to_string(rs_camera_info info);
01038 const char * rs_camera_info_to_string(rs_camera_info info);
01039 const char * rs_timestamp_domain_to_string(rs_timestamp_domain info);
01040 const char * rs_frame_metadata_to_string(rs_frame_metadata md);
01041 
01047 void rs_log_to_console(rs_log_severity min_severity, rs_error ** error);
01048 
01055 void rs_log_to_file(rs_log_severity min_severity, const char * file_path, rs_error ** error);
01056 
01063 void rs_log_to_callback_cpp(rs_log_severity min_severity, rs_log_callback * callback, rs_error ** error);
01064 
01072 void rs_log_to_callback(rs_log_severity min_severity, rs_log_callback_ptr on_log, void * user, rs_error ** error);
01073 
01074 #ifdef __cplusplus
01075 }
01076 #endif
01077 #endif


librealsense
Author(s): Sergey Dorodnicov , Mark Horn , Reagan Lopez
autogenerated on Tue Jun 25 2019 19:54:39