|
enum | control {
control::command_response = 1,
control::fisheye_xu_strobe = 1,
control::iffley = 2,
control::fisheye_xu_ext_trig = 2,
control::stream_intent = 3,
control::fisheye_exposure = 3,
control::depth_units = 4,
control::min_max = 5,
control::disparity = 6,
control::rectification = 7,
control::emitter = 8,
control::temperature = 9,
control::depth_params = 10,
control::last_error = 12,
control::embedded_count = 13,
control::lr_exposure = 14,
control::lr_autoexposure_parameters = 15,
control::sw_reset = 16,
control::lr_gain = 17,
control::lr_exposure_mode = 18,
control::disparity_shift = 19,
control::status = 20,
control::lr_exposure_discovery = 21,
control::lr_gain_discovery = 22,
control::hw_timestamp = 23
} |
|
enum | ds_emitter_type : uint32_t {
DS_EMITTER_NONE = 0,
DS_EMITTER_LD2 = 1,
DS_EMITTER_LD3 = 2,
DS_EMITTER_LD4_1 = 3,
DS_EMITTER_COUNT = 4
} |
|
enum | ds_lens_coating_type : uint32_t {
DS_LENS_COATING_UNKNOWN = 0,
DS_LENS_COATING_IR_CUT = 1,
DS_LENS_COATING_ALL_PASS = 2,
DS_LENS_COATING_IR_PASS = 3,
DS_LENS_COATING_IR_PASS_859_43 = 4,
DS_LENS_COATING_COUNT = 5
} |
|
enum | ds_lens_type : uint32_t {
DS_LENS_UNKNOWN = 0,
DS_LENS_DSL103 = 1,
DS_LENS_DSL821C = 2,
DS_LENS_DSL202A = 3,
DS_LENS_DSL203 = 4,
DS_LENS_PENTAX2514 = 5,
DS_LENS_DSL924A = 6,
DS_LENS_AZW58 = 7,
DS_LENS_Largan9386 = 8,
DS_LENS_DS6100 = 9,
DS_LENS_DS6177 = 10,
DS_LENS_DS6237 = 11,
DS_LENS_DS6233 = 12,
DS_LENS_DS917 = 13,
DS_LENS_AEOT_1LS0901L = 14,
DS_LENS_COUNT = 15
} |
|
enum | ds_oem_id : uint32_t { DS_OEM_NONE = 0
} |
|
enum | ds_prq_type : uint8_t { DS_PRQ_READY = 1
} |
|
enum | subdevices { SUB_DEVICE_INFRARED = 0,
SUB_DEVICE_DEPTH = 1,
SUB_DEVICE_COLOR = 2,
SUB_DEVICE_FISHEYE = 3
} |
|
|
void | bulk_usb_command (uvc::device &device, std::timed_mutex &mutex, unsigned char out_ep, uint8_t *out, size_t outSize, uint32_t &op, unsigned char in_ep, uint8_t *in, size_t &inSize, int timeout) |
|
void | force_firmware_reset (uvc::device &device) |
|
dc_params | get_depth_params (const uvc::device &device) |
|
uint32_t | get_depth_units (const uvc::device &device) |
|
disp_mode | get_disparity_mode (const uvc::device &device) |
|
uint32_t | get_disparity_shift (const uvc::device &device) |
|
bool | get_emitter_state (const uvc::device &device, bool is_streaming, bool is_depth_enabled) |
|
uint8_t | get_last_error (const uvc::device &device) |
|
ae_params | get_lr_auto_exposure_params (const uvc::device &device, std::vector< supported_option > ae_vec) |
|
rate_value | get_lr_exposure (const uvc::device &device) |
|
discovery | get_lr_exposure_discovery (const uvc::device &device) |
|
uint8_t | get_lr_exposure_mode (const uvc::device &device) |
|
rate_value | get_lr_gain (const uvc::device &device) |
|
discovery | get_lr_gain_discovery (const uvc::device &device) |
|
range | get_min_max_depth (const uvc::device &device) |
|
void | get_register_value (uvc::device &device, uint32_t reg, uint32_t &value) |
|
void | get_stream_status (const uvc::device &device, uint32_t &status) |
|
void | get_stream_status (const uvc::device &device, int &status) |
|
temperature | get_temperature (const uvc::device &device) |
|
std::ostream & | operator<< (std::ostream &out, ds_lens_type type) |
|
std::ostream & | operator<< (std::ostream &out, ds_lens_coating_type type) |
|
std::ostream & | operator<< (std::ostream &out, ds_emitter_type type) |
|
std::ostream & | operator<< (std::ostream &out, ds_oem_id type) |
|
std::ostream & | operator<< (std::ostream &out, ds_prq_type type) |
|
bool | read_admin_sector (uvc::device &dev, unsigned char data[SPI_FLASH_SECTOR_SIZE_IN_BYTES], int whichAdminSector) |
|
void | read_arbitrary_chunk (uvc::device &dev, uint32_t address, void *dataIn, int lengthInBytesIn) |
|
ds_calibration | read_calibration_and_rectification_parameters (const uint8_t(&flash_data_buffer)[SPI_FLASH_SECTOR_SIZE_IN_BYTES]) |
|
ds_head_content | read_camera_head_contents (const uint8_t(&flash_data_buffer)[SPI_FLASH_SECTOR_SIZE_IN_BYTES], uint32_t &serial_number) |
|
ds_info | read_camera_info (uvc::device &device) |
|
bool | read_device_pages (uvc::device &dev, uint32_t address, unsigned char *buffer, uint32_t nPages) |
|
std::string | read_firmware_version (uvc::device &device) |
|
std::string | read_isp_firmware_version (uvc::device &device) |
|
CommandResponsePacket | send_command_and_receive_response (uvc::device &device, const CommandResponsePacket &command) |
|
void | set_depth_params (uvc::device &device, dc_params params) |
|
void | set_depth_units (uvc::device &device, uint32_t units) |
|
void | set_disparity_mode (uvc::device &device, disp_mode mode) |
|
void | set_disparity_shift (uvc::device &device, uint32_t shift) |
|
void | set_emitter_state (uvc::device &device, bool state) |
|
void | set_lr_auto_exposure_params (uvc::device &device, ae_params params) |
|
void | set_lr_exposure (uvc::device &device, rate_value exposure) |
|
void | set_lr_exposure_discovery (uvc::device &device, discovery disc) |
|
void | set_lr_exposure_mode (uvc::device &device, uint8_t mode) |
|
void | set_lr_gain (uvc::device &device, rate_value gain) |
|
void | set_lr_gain_discovery (uvc::device &device, discovery disc) |
|
void | set_min_max_depth (uvc::device &device, range min_max) |
|
void | set_register_value (uvc::device &device, uint32_t reg, uint32_t value) |
|
void | set_stream_intent (uvc::device &device, uint8_t &intent) |
|
void | set_temperature (uvc::device &device, temperature temp) |
|
std::string | time_to_string (double val) |
|
void | xu_read (const uvc::device &device, uvc::extension_unit xu, control xu_ctrl, void *buffer, uint32_t length) |
|
template<class T > |
T | xu_read (const uvc::device &dev, uvc::extension_unit xu, control ctrl) |
|
void | xu_write (uvc::device &device, uvc::extension_unit xu, control xu_ctrl, void *buffer, uint32_t length) |
|
template<class T > |
void | xu_write (uvc::device &dev, uvc::extension_unit xu, control ctrl, const T &value) |
|
ds_calibration rsimpl::ds::read_calibration_and_rectification_parameters |
( |
const uint8_t(&) |
flash_data_buffer[SPI_FLASH_SECTOR_SIZE_IN_BYTES] | ) |
|
< Max number right cameras supported (e.g. one or two, two would support a multi-baseline unit)
< Max number native resolutions the third camera can have (e.g. 1920x1080 and 640x480)
< Max number rectified LR resolution modes the structure supports (e.g. 640x480, 492x372 and 332x252)
< Max number rectified Third resolution modes the structure supports (e.g. 1920x1080, 1280x720, 640x480 and 320x240)
< Number of right cameras < MAX_INTRIN_RIGHT_V0
< Number of native resolutions of third camera < MAX_INTRIN_THIRD_V0
< Number of rectified LR resolution modes < MAX_MODES_LR_V0
< Number of rectified Third resolution modes < MAX_MODES_THIRD_V0
Definition at line 173 of file ds-private.cpp.