Program Listing for File rs_device.h

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

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

#ifndef LIBREALSENSE_RS2_DEVICE_H
#define LIBREALSENSE_RS2_DEVICE_H

#ifdef __cplusplus
extern "C" {
#endif

#include "rs_types.h"
#include "rs_sensor.h"

int rs2_get_device_count(const rs2_device_list* info_list, rs2_error** error);

void rs2_delete_device_list(rs2_device_list* info_list);

int rs2_device_list_contains(const rs2_device_list* info_list, const rs2_device* device, rs2_error** error);

rs2_device* rs2_create_device(const rs2_device_list* info_list, int index, rs2_error** error);

void rs2_delete_device(rs2_device* device);

const char* rs2_get_device_info(const rs2_device* device, rs2_camera_info info, rs2_error** error);

int rs2_supports_device_info(const rs2_device* device, rs2_camera_info info, rs2_error** error);

void rs2_hardware_reset(const rs2_device * device, rs2_error ** error);

const rs2_raw_data_buffer* rs2_build_debug_protocol_command(rs2_device* device, unsigned opcode, unsigned param1, unsigned param2,
    unsigned param3, unsigned param4, void* data, unsigned size_of_data, rs2_error** error);

const rs2_raw_data_buffer* rs2_send_and_receive_raw_data(rs2_device* device, void* raw_data_to_send, unsigned size_of_raw_data_to_send, rs2_error** error);

int rs2_is_device_extendable_to(const rs2_device* device, rs2_extension extension, rs2_error ** error);

rs2_sensor_list* rs2_query_sensors(const rs2_device* device, rs2_error** error);

void rs2_loopback_enable(const rs2_device* device, const char* from_file, rs2_error** error);

void rs2_loopback_disable(const rs2_device* device, rs2_error** error);

int rs2_loopback_is_enabled(const rs2_device* device, rs2_error** error);

void rs2_connect_tm2_controller(const rs2_device* device, const unsigned char* mac_addr, rs2_error** error);

void rs2_disconnect_tm2_controller(const rs2_device* device, int id, rs2_error** error);


void rs2_reset_to_factory_calibration(const rs2_device* device, rs2_error** e);

void rs2_write_calibration(const rs2_device* device, rs2_error** e);

void rs2_update_firmware_cpp(const rs2_device* device, const void* fw_image, int fw_image_size, rs2_update_progress_callback* callback, rs2_error** error);

void rs2_update_firmware(const rs2_device* device, const void* fw_image, int fw_image_size, rs2_update_progress_callback_ptr callback, void* client_data, rs2_error** error);

const rs2_raw_data_buffer* rs2_create_flash_backup_cpp(const rs2_device* device, rs2_update_progress_callback* callback, rs2_error** error);

const rs2_raw_data_buffer* rs2_create_flash_backup(const rs2_device* device, rs2_update_progress_callback_ptr callback, void* client_data, rs2_error** error);

#define RS2_UNSIGNED_UPDATE_MODE_UPDATE     0
#define RS2_UNSIGNED_UPDATE_MODE_READ_ONLY  1
#define RS2_UNSIGNED_UPDATE_MODE_FULL       2

void rs2_update_firmware_unsigned_cpp(const rs2_device* device, const void* fw_image, int fw_image_size, rs2_update_progress_callback* callback, int update_mode, rs2_error** error);

int rs2_check_firmware_compatibility(const rs2_device* device, const void* fw_image, int fw_image_size, rs2_error** error);

void rs2_update_firmware_unsigned(const rs2_device* device, const void* fw_image, int fw_image_size, rs2_update_progress_callback_ptr callback, void* client_data, int update_mode, rs2_error** error);

void rs2_enter_update_state(const rs2_device* device, rs2_error** error);

const rs2_raw_data_buffer* rs2_run_on_chip_calibration_cpp(rs2_device* device, const void* json_content, int content_size, float* health, rs2_update_progress_callback* progress_callback, int timeout_ms, rs2_error** error);

const rs2_raw_data_buffer* rs2_run_on_chip_calibration(rs2_device* device, const void* json_content, int content_size, float* health, rs2_update_progress_callback_ptr callback, void* client_data, int timeout_ms, rs2_error** error);

const rs2_raw_data_buffer* rs2_run_tare_calibration_cpp(rs2_device* dev, float ground_truth_mm, const void* json_content, int content_size, float* health, rs2_update_progress_callback* progress_callback, int timeout_ms, rs2_error** error);


const rs2_raw_data_buffer* rs2_process_calibration_frame(rs2_device* dev, const rs2_frame* f, float* const health, rs2_update_progress_callback* progress_callback, int timeout_ms, rs2_error** error);


typedef enum rs2_calibration_type
{
    RS2_CALIBRATION_AUTO_DEPTH_TO_RGB,
    RS2_CALIBRATION_MANUAL_DEPTH_TO_RGB,
    RS2_CALIBRATION_THERMAL,
    RS2_CALIBRATION_TYPE_COUNT
} rs2_calibration_type;
const char* rs2_calibration_type_to_string( rs2_calibration_type );

typedef enum rs2_calibration_status
{
    // Anything >= 0 is not an issue
    RS2_CALIBRATION_TRIGGERED      =  0,  // AC triggered and is active; conditions are valid
    RS2_CALIBRATION_SPECIAL_FRAME  =  1,  // Special frame received; expect a frame-drop!
    RS2_CALIBRATION_STARTED        =  2,  // Have all frames in hand; starting processing
    RS2_CALIBRATION_NOT_NEEDED     =  3,  // Finished; existing calibration within tolerances; nothing done!
    RS2_CALIBRATION_SUCCESSFUL     =  4,  // Finished; have new calibration in-hand

    RS2_CALIBRATION_RETRY          = -1,  // Initiating retry (asked for a new special frame)
    RS2_CALIBRATION_FAILED         = -2,  // Unexpected: exception, device removed, stream stopped, etc.
    RS2_CALIBRATION_SCENE_INVALID  = -3,  // Scene was not good enough for calibration; will retry
    RS2_CALIBRATION_BAD_RESULT     = -4,  // Calibration finished, but results aren't good; will retry
    RS2_CALIBRATION_BAD_CONDITIONS = -5,  // Trigger was attempted but conditions (temp/APD) were invalid (still inactive)

    RS2_CALIBRATION_STATUS_FIRST   = -5,
    RS2_CALIBRATION_STATUS_LAST    =  4,
    RS2_CALIBRATION_STATUS_COUNT = RS2_CALIBRATION_STATUS_LAST - RS2_CALIBRATION_STATUS_FIRST + 1,
} rs2_calibration_status;
const char* rs2_calibration_status_to_string( rs2_calibration_status );

typedef struct rs2_calibration_change_callback rs2_calibration_change_callback;
typedef void (*rs2_calibration_change_callback_ptr)(rs2_calibration_status, void* arg);

void rs2_register_calibration_change_callback( rs2_device* dev, rs2_calibration_change_callback_ptr callback, void* user, rs2_error** error );

void rs2_register_calibration_change_callback_cpp( rs2_device* dev, rs2_calibration_change_callback* callback, rs2_error** error );

void rs2_trigger_device_calibration( rs2_device* dev, rs2_calibration_type type, rs2_error** error );

const rs2_raw_data_buffer* rs2_run_tare_calibration(rs2_device* dev, float ground_truth_mm, const void* json_content, int content_size, float* health, rs2_update_progress_callback_ptr callback, void* client_data, int timeout_ms, rs2_error** error);

const rs2_raw_data_buffer* rs2_get_calibration_table(const rs2_device* dev, rs2_error** error);

void rs2_set_calibration_table(const rs2_device* device, const void* calibration, int calibration_size, rs2_error** error);

/* Serialize JSON content, returns ASCII-serialized JSON string on success. otherwise nullptr */
rs2_raw_data_buffer* rs2_serialize_json(rs2_device* dev, rs2_error** error);

/* Load JSON and apply advanced-mode controls */
void rs2_load_json(rs2_device* dev, const void* json_content, unsigned content_size, rs2_error** error);

const rs2_raw_data_buffer* rs2_run_focal_length_calibration_cpp(rs2_device* device, rs2_frame_queue* left_queue , rs2_frame_queue* right_queue, float target_width, float target_height, int adjust_both_sides,
    float* ratio, float* angle, rs2_update_progress_callback * progress_callback, rs2_error** error);

const rs2_raw_data_buffer* rs2_run_focal_length_calibration(rs2_device* device, rs2_frame_queue* left_queue, rs2_frame_queue* right_queue, float target_width, float target_height, int adjust_both_sides,
    float* ratio, float* angle, rs2_update_progress_callback_ptr callback, void* client_data, rs2_error** error);

const rs2_raw_data_buffer* rs2_run_uv_map_calibration_cpp(rs2_device* device, rs2_frame_queue* left_queue, rs2_frame_queue* color_queue, rs2_frame_queue* depth_queue, int py_px_only,
    float * health, int health_size, rs2_update_progress_callback * progress_callback, rs2_error** error);

const rs2_raw_data_buffer* rs2_run_uv_map_calibration(rs2_device* device, rs2_frame_queue* left_queue, rs2_frame_queue* color_queue, rs2_frame_queue* depth_queue,
    int py_px_only, float* health, int health_size, rs2_update_progress_callback_ptr callback, void* client_data, rs2_error** error);

float rs2_calculate_target_z_cpp(rs2_device* device, rs2_frame_queue* queue1, rs2_frame_queue* queue2, rs2_frame_queue* queue3,
    float target_width, float target_height,
    rs2_update_progress_callback* callback, rs2_error** error);

float rs2_calculate_target_z(rs2_device* device, rs2_frame_queue* queue1, rs2_frame_queue* queue2, rs2_frame_queue* queue3,
    float target_width, float target_height, rs2_update_progress_callback_ptr progress_callback, void* client_data, rs2_error** error);

#ifdef __cplusplus
}
#endif
#endif