Program Listing for File rs_types.h

Return to documentation for file (/tmp/ws/src/librealsense2/include/librealsense2/h/rs_types.h)

/* License: Apache 2.0. See LICENSE file in root directory.
   Copyright(c) 2017 Intel Corporation. All Rights Reserved. */

#ifndef LIBREALSENSE_RS2_TYPES_H
#define LIBREALSENSE_RS2_TYPES_H

#ifdef __cplusplus
extern "C" {
#endif

typedef enum rs2_notification_category{
    RS2_NOTIFICATION_CATEGORY_FRAMES_TIMEOUT,
    RS2_NOTIFICATION_CATEGORY_FRAME_CORRUPTED,
    RS2_NOTIFICATION_CATEGORY_HARDWARE_ERROR,
    RS2_NOTIFICATION_CATEGORY_HARDWARE_EVENT,
    RS2_NOTIFICATION_CATEGORY_UNKNOWN_ERROR,
    RS2_NOTIFICATION_CATEGORY_FIRMWARE_UPDATE_RECOMMENDED,
    RS2_NOTIFICATION_CATEGORY_POSE_RELOCALIZATION,
    RS2_NOTIFICATION_CATEGORY_COUNT
} rs2_notification_category;
const char* rs2_notification_category_to_string(rs2_notification_category category);

typedef enum rs2_exception_type
{
    RS2_EXCEPTION_TYPE_UNKNOWN,
    RS2_EXCEPTION_TYPE_CAMERA_DISCONNECTED,
    RS2_EXCEPTION_TYPE_BACKEND,
    RS2_EXCEPTION_TYPE_INVALID_VALUE,
    RS2_EXCEPTION_TYPE_WRONG_API_CALL_SEQUENCE,
    RS2_EXCEPTION_TYPE_NOT_IMPLEMENTED,
    RS2_EXCEPTION_TYPE_DEVICE_IN_RECOVERY_MODE,
    RS2_EXCEPTION_TYPE_IO,
    RS2_EXCEPTION_TYPE_COUNT
} rs2_exception_type;
const char* rs2_exception_type_to_string(rs2_exception_type type);

typedef enum rs2_distortion
{
    RS2_DISTORTION_NONE                  ,
    RS2_DISTORTION_MODIFIED_BROWN_CONRADY,
    RS2_DISTORTION_INVERSE_BROWN_CONRADY ,
    RS2_DISTORTION_FTHETA                ,
    RS2_DISTORTION_BROWN_CONRADY         ,
    RS2_DISTORTION_KANNALA_BRANDT4       ,
    RS2_DISTORTION_COUNT
} rs2_distortion;
const char* rs2_distortion_to_string(rs2_distortion distortion);

typedef struct rs2_intrinsics
{
    int           width;
    int           height;
    float         ppx;
    float         ppy;
    float         fx;
    float         fy;
    rs2_distortion model;
    float         coeffs[5];
} rs2_intrinsics;

#pragma pack( push, 1 )
    typedef struct rs2_dsm_params
    {
        unsigned long long timestamp;
        unsigned short version;
        unsigned char model;
        unsigned char flags[5];
        float h_scale;
        float v_scale;
        float h_offset;
        float v_offset;
        float rtd_offset;
        unsigned char temp_x2;
        float mc_h_scale;
        float mc_v_scale;
        unsigned char weeks_since_calibration;
        unsigned char ac_weeks_since_calibaration;
        unsigned char reserved[1];
    } rs2_dsm_params;
#pragma pack( pop )

typedef enum rs2_dsm_correction_model
{
    RS2_DSM_CORRECTION_NONE,
    RS2_DSM_CORRECTION_AOT,
    RS2_DSM_CORRECTION_TOA,
    RS2_DSM_CORRECTION_COUNT
} rs2_dsm_correction_model;

typedef struct rs2_motion_device_intrinsic
{
    /* \internal
    * Scale X       cross axis  cross axis  Bias X \n
    * cross axis    Scale Y     cross axis  Bias Y \n
    * cross axis    cross axis  Scale Z     Bias Z */
    float data[3][4];
    float noise_variances[3];
    float bias_variances[3];
} rs2_motion_device_intrinsic;

typedef struct rs2_vertex
{
    float xyz[3];
} rs2_vertex;

typedef struct rs2_pixel
{
    int ij[2];
} rs2_pixel;

typedef struct rs2_vector
{
    float x, y, z;
}rs2_vector;

typedef struct rs2_quaternion
{
    float x, y, z, w;
}rs2_quaternion;

typedef struct rs2_pose
{
    rs2_vector      translation;
    rs2_vector      velocity;
    rs2_vector      acceleration;
    rs2_quaternion  rotation;
    rs2_vector      angular_velocity;
    rs2_vector      angular_acceleration;
    unsigned int    tracker_confidence;
    unsigned int    mapper_confidence;
} rs2_pose;

typedef enum rs2_log_severity {
    RS2_LOG_SEVERITY_DEBUG,
    RS2_LOG_SEVERITY_INFO ,
    RS2_LOG_SEVERITY_WARN ,
    RS2_LOG_SEVERITY_ERROR,
    RS2_LOG_SEVERITY_FATAL,
    RS2_LOG_SEVERITY_NONE ,
    RS2_LOG_SEVERITY_COUNT,
    RS2_LOG_SEVERITY_ALL = RS2_LOG_SEVERITY_DEBUG
 } rs2_log_severity;
const char* rs2_log_severity_to_string(rs2_log_severity info);

typedef enum rs2_extension
{
    RS2_EXTENSION_UNKNOWN,
    RS2_EXTENSION_DEBUG,
    RS2_EXTENSION_INFO,
    RS2_EXTENSION_MOTION,
    RS2_EXTENSION_OPTIONS,
    RS2_EXTENSION_VIDEO,
    RS2_EXTENSION_ROI,
    RS2_EXTENSION_DEPTH_SENSOR,
    RS2_EXTENSION_VIDEO_FRAME,
    RS2_EXTENSION_MOTION_FRAME,
    RS2_EXTENSION_COMPOSITE_FRAME,
    RS2_EXTENSION_POINTS,
    RS2_EXTENSION_DEPTH_FRAME,
    RS2_EXTENSION_ADVANCED_MODE,
    RS2_EXTENSION_RECORD,
    RS2_EXTENSION_VIDEO_PROFILE,
    RS2_EXTENSION_PLAYBACK,
    RS2_EXTENSION_DEPTH_STEREO_SENSOR,
    RS2_EXTENSION_DISPARITY_FRAME,
    RS2_EXTENSION_MOTION_PROFILE,
    RS2_EXTENSION_POSE_FRAME,
    RS2_EXTENSION_POSE_PROFILE,
    RS2_EXTENSION_TM2,
    RS2_EXTENSION_SOFTWARE_DEVICE,
    RS2_EXTENSION_SOFTWARE_SENSOR,
    RS2_EXTENSION_DECIMATION_FILTER,
    RS2_EXTENSION_THRESHOLD_FILTER,
    RS2_EXTENSION_DISPARITY_FILTER,
    RS2_EXTENSION_SPATIAL_FILTER,
    RS2_EXTENSION_TEMPORAL_FILTER,
    RS2_EXTENSION_HOLE_FILLING_FILTER,
    RS2_EXTENSION_ZERO_ORDER_FILTER,
    RS2_EXTENSION_RECOMMENDED_FILTERS,
    RS2_EXTENSION_POSE,
    RS2_EXTENSION_POSE_SENSOR,
    RS2_EXTENSION_WHEEL_ODOMETER,
    RS2_EXTENSION_GLOBAL_TIMER,
    RS2_EXTENSION_UPDATABLE,
    RS2_EXTENSION_UPDATE_DEVICE,
    RS2_EXTENSION_L500_DEPTH_SENSOR,
    RS2_EXTENSION_TM2_SENSOR,
    RS2_EXTENSION_AUTO_CALIBRATED_DEVICE,
    RS2_EXTENSION_COLOR_SENSOR,
    RS2_EXTENSION_MOTION_SENSOR,
    RS2_EXTENSION_FISHEYE_SENSOR,
    RS2_EXTENSION_DEPTH_HUFFMAN_DECODER, // DEPRECATED
    RS2_EXTENSION_SERIALIZABLE,
    RS2_EXTENSION_FW_LOGGER,
    RS2_EXTENSION_AUTO_CALIBRATION_FILTER,
    RS2_EXTENSION_DEVICE_CALIBRATION,
    RS2_EXTENSION_CALIBRATED_SENSOR,
    RS2_EXTENSION_HDR_MERGE,
    RS2_EXTENSION_SEQUENCE_ID_FILTER,
    RS2_EXTENSION_MAX_USABLE_RANGE_SENSOR,
    RS2_EXTENSION_DEBUG_STREAM_SENSOR,
    RS2_EXTENSION_CALIBRATION_CHANGE_DEVICE,
    RS2_EXTENSION_COUNT
} rs2_extension;
const char* rs2_extension_type_to_string(rs2_extension type);
const char* rs2_extension_to_string(rs2_extension type);

typedef enum rs2_matchers
{
   RS2_MATCHER_DI,      //compare depth and ir based on frame number

   RS2_MATCHER_DI_C,    //compare depth and ir based on frame number,
                        //compare the pair of corresponding depth and ir with color based on closest timestamp,
                        //commonly used by SR300

   RS2_MATCHER_DLR_C,   //compare depth, left and right ir based on frame number,
                        //compare the set of corresponding depth, left and right with color based on closest timestamp,
                        //commonly used by RS415, RS435

   RS2_MATCHER_DLR,     //compare depth, left and right ir based on frame number,
                        //commonly used by RS400, RS405, RS410, RS420, RS430

   RS2_MATCHER_DIC,     //compare depth, ir and confidence based on frame number used by RS500

   RS2_MATCHER_DIC_C,    //compare depth, ir and confidence based on frame number,
                         //compare the set of corresponding depth, ir and confidence with color based on closest timestamp,
                         //commonly used by RS515

   RS2_MATCHER_DEFAULT, //the default matcher compare all the streams based on closest timestamp

   RS2_MATCHER_COUNT
} rs2_matchers;
const char* rs2_matchers_to_string(rs2_matchers stream);

typedef struct rs2_device_info rs2_device_info;
typedef struct rs2_device rs2_device;
typedef struct rs2_error rs2_error;
typedef struct rs2_log_message rs2_log_message;
typedef struct rs2_raw_data_buffer rs2_raw_data_buffer;
typedef struct rs2_frame rs2_frame;
typedef struct rs2_frame_queue rs2_frame_queue;
typedef struct rs2_pipeline rs2_pipeline;
typedef struct rs2_pipeline_profile rs2_pipeline_profile;
typedef struct rs2_config rs2_config;
typedef struct rs2_device_list rs2_device_list;
typedef struct rs2_stream_profile_list rs2_stream_profile_list;
typedef struct rs2_processing_block_list rs2_processing_block_list;
typedef struct rs2_stream_profile rs2_stream_profile;
typedef struct rs2_frame_callback rs2_frame_callback;
typedef struct rs2_log_callback rs2_log_callback;
typedef struct rs2_syncer rs2_syncer;
typedef struct rs2_device_serializer rs2_device_serializer;
typedef struct rs2_source rs2_source;
typedef struct rs2_processing_block rs2_processing_block;
typedef struct rs2_frame_processor_callback rs2_frame_processor_callback;
typedef struct rs2_playback_status_changed_callback rs2_playback_status_changed_callback;
typedef struct rs2_update_progress_callback rs2_update_progress_callback;
typedef struct rs2_context rs2_context;
typedef struct rs2_device_hub rs2_device_hub;
typedef struct rs2_sensor_list rs2_sensor_list;
typedef struct rs2_sensor rs2_sensor;
typedef struct rs2_options rs2_options;
typedef struct rs2_options_list rs2_options_list;
typedef struct rs2_devices_changed_callback rs2_devices_changed_callback;
typedef struct rs2_notification rs2_notification;
typedef struct rs2_notifications_callback rs2_notifications_callback;
typedef struct rs2_firmware_log_message rs2_firmware_log_message;
typedef struct rs2_firmware_log_parsed_message rs2_firmware_log_parsed_message;
typedef struct rs2_firmware_log_parser rs2_firmware_log_parser;
typedef struct rs2_terminal_parser rs2_terminal_parser;
typedef void (*rs2_log_callback_ptr)(rs2_log_severity, rs2_log_message const *, void * arg);
typedef void (*rs2_notification_callback_ptr)(rs2_notification*, void*);
typedef void(*rs2_software_device_destruction_callback_ptr)(void*);
typedef void (*rs2_devices_changed_callback_ptr)(rs2_device_list*, rs2_device_list*, void*);
typedef void (*rs2_frame_callback_ptr)(rs2_frame*, void*);
typedef void (*rs2_frame_processor_callback_ptr)(rs2_frame*, rs2_source*, void*);
typedef void(*rs2_update_progress_callback_ptr)(const float, void*);

typedef double      rs2_time_t;
typedef long long   rs2_metadata_type;
rs2_error * rs2_create_error(const char* what, const char* name, const char* args, rs2_exception_type type);
rs2_exception_type rs2_get_librealsense_exception_type(const rs2_error* error);
const char* rs2_get_failed_function            (const rs2_error* error);
const char* rs2_get_failed_args                (const rs2_error* error);
const char* rs2_get_error_message              (const rs2_error* error);
void        rs2_free_error                     (rs2_error* error);

#ifdef __cplusplus
}
#endif
#endif