Classes | Typedefs | Enumerations | Functions | Variables
librealsense::platform Namespace Reference

Classes

class  android_backend
 
class  auto_reset_event
 
class  backend
 
struct  backend_device_group
 
class  buffer
 
class  buffers_mgr
 
struct  call
 
struct  callback_data
 
class  cm_node
 
class  command_transfer
 
class  command_transfer_usb
 
class  compression_algorithm
 
struct  control_range
 
class  device_watcher
 
class  device_watcher_usbhost
 
class  event_base
 
struct  extension_unit
 
struct  FEATURE_REPORT
 
struct  frame_object
 
struct  frame_rate
 
struct  guid
 
class  handle_libusb
 
class  handle_usbhost
 
class  handle_winusb
 
class  hid_custom_sensor
 
class  hid_device
 
struct  hid_device_info
 
struct  hid_header
 
class  hid_input
 
struct  hid_input_info
 
struct  hid_profile
 
struct  hid_sensor
 
struct  hid_sensor_data
 
struct  hid_sensor_input
 
class  iio_hid_sensor
 
struct  lookup_key
 
class  manual_reset_event
 
struct  mf_profile
 
class  multi_pins_hid_device
 
class  multi_pins_uvc_device
 
class  named_mutex
 
class  os_time_service
 
class  playback_backend
 
class  playback_backend_exception
 
struct  playback_device_info
 
class  playback_device_watcher
 
class  playback_hid_device
 
class  playback_usb_device
 
class  playback_uvc_device
 
struct  profile_and_callback
 
struct  pu_control
 
struct  REALSENSE_FEATURE_REPORT
 
struct  REALSENSE_HID_REPORT
 
class  record_backend
 
class  record_device_watcher
 
class  record_hid_device
 
class  record_usb_device
 
class  record_uvc_device
 
class  recording
 
class  recording_time_service
 
class  retry_controls_work_around
 
class  rs_backend
 
class  rs_backend_linux
 
class  rs_backend_windows
 
class  rs_hid_device
 
class  rs_uvc_device
 
class  safe_handle
 
struct  sensor_data
 
class  sensor_events
 
class  source_reader_callback
 
struct  stream_profile
 
class  time_service
 
struct  tm2_device_info
 
struct  usb_config_descriptor
 
class  usb_context
 
struct  usb_descriptor
 
class  usb_device
 
struct  usb_device_info
 
class  usb_device_libusb
 
class  usb_device_mock
 
class  usb_device_usbhost
 
class  usb_device_winusb
 
class  usb_endpoint
 
class  usb_endpoint_libusb
 
class  usb_endpoint_usbhost
 
class  usb_endpoint_winusb
 
class  usb_enumerator
 
class  usb_interface
 
struct  usb_interface_descriptor
 
class  usb_interface_libusb
 
class  usb_interface_usbhost
 
class  usb_interface_winusb
 
class  usb_messenger
 
class  usb_messenger_libusb
 
class  usb_messenger_usbhost
 
class  usb_messenger_winusb
 
class  usb_request
 
class  usb_request_base
 
class  usb_request_callback
 
class  usb_request_libusb
 
class  usb_request_usbhost
 
class  usb_request_winusb
 
class  uvc_device
 
struct  uvc_device_info
 
struct  uvc_header
 
class  uvc_parser
 
class  uvc_streamer
 
struct  uvc_streamer_context
 
class  v4l_backend
 
class  v4l_hid_device
 
class  v4l_uvc_device
 
class  v4l_uvc_interface
 
class  v4l_uvc_meta_device
 
class  win_event_device_watcher
 
class  winapi_error
 
class  wmf_backend
 
class  wmf_hid_device
 
class  wmf_hid_sensor
 
class  wmf_uvc_device
 

Typedefs

typedef std::vector< std::pair< stream_profile, frame_callback > > configurations
 
typedef std::function< void(backend_device_group old, backend_device_group curr)> device_changed_callback
 
typedef enum librealsense::platform::_endpoint_direction endpoint_direction
 
typedef enum librealsense::platform::_endpoint_type endpoint_type
 
typedef std::function< void(const uvc_device_info &, IMFActivate *)> enumeration_callback
 
typedef ULONG(__stdcall * fnRtlGetVersion) (PRTL_OSVERSIONINFOW lpVersionInformation)
 
typedef std::function< void(stream_profile, frame_object, std::function< void()>)> frame_callback
 
typedef struct librealsense::platform::frame_rate frame_rate
 
typedef std::function< void(const sensor_data &)> hid_callback
 
typedef struct librealsense::platform::mf_profile mf_profile
 
typedef std::shared_ptr< usb_devicers_usb_device
 
typedef std::shared_ptr< usb_endpointrs_usb_endpoint
 
typedef std::shared_ptr< usb_interfacers_usb_interface
 
typedef std::shared_ptr< usb_messengerrs_usb_messenger
 
typedef std::shared_ptr< usb_requestrs_usb_request
 
typedef std::shared_ptr< usb_request_callbackrs_usb_request_callback
 
typedef std::tuple< uint32_t, uint32_t, uint32_t, uint32_tstream_profile_tuple
 
typedef enum librealsense::platform::_usb_class usb_class
 
typedef enum librealsense::platform::_usb_status usb_status
 
typedef enum librealsense::platform::_usb_subclass usb_subclass
 

Enumerations

enum  _endpoint_direction { RS2_USB_ENDPOINT_DIRECTION_WRITE = 0, RS2_USB_ENDPOINT_DIRECTION_READ = 0x80 }
 
enum  _endpoint_type { RS2_USB_ENDPOINT_CONTROL, RS2_USB_ENDPOINT_ISOCHRONOUS, RS2_USB_ENDPOINT_BULK, RS2_USB_ENDPOINT_INTERRUPT }
 
enum  _usb_class {
  RS2_USB_CLASS_UNSPECIFIED = 0x00, RS2_USB_CLASS_AUDIO = 0x01, RS2_USB_CLASS_COM = 0x02, RS2_USB_CLASS_HID = 0x03,
  RS2_USB_CLASS_PID = 0x05, RS2_USB_CLASS_IMAGE = 0x06, RS2_USB_CLASS_PRINTER = 0x07, RS2_USB_CLASS_MASS_STORAGE = 0x08,
  RS2_USB_CLASS_HUB = 0x09, RS2_USB_CLASS_CDC_DATA = 0x0A, RS2_USB_CLASS_SMART_CARD = 0x0B, RS2_USB_CLASS_CONTENT_SECURITY = 0x0D,
  RS2_USB_CLASS_VIDEO = 0x0E, RS2_USB_CLASS_PHDC = 0x0F, RS2_USB_CLASS_AV = 0x10, RS2_USB_CLASS_BILLBOARD = 0x11,
  RS2_USB_CLASS_DIAGNOSTIC_DEVIE = 0xDC, RS2_USB_CLASS_WIRELESS_CONTROLLER = 0xE0, RS2_USB_CLASS_MISCELLANEOUS = 0xEF, RS2_USB_CLASS_APPLICATION_SPECIFIC = 0xFE,
  RS2_USB_CLASS_VENDOR_SPECIFIC = 0xFF
}
 
enum  _usb_status {
  RS2_USB_STATUS_SUCCESS = 0, RS2_USB_STATUS_IO = -1, RS2_USB_STATUS_INVALID_PARAM = -2, RS2_USB_STATUS_ACCESS = -3,
  RS2_USB_STATUS_NO_DEVICE = -4, RS2_USB_STATUS_NOT_FOUND = -5, RS2_USB_STATUS_BUSY = -6, RS2_USB_STATUS_TIMEOUT = -7,
  RS2_USB_STATUS_OVERFLOW = -8, RS2_USB_STATUS_PIPE = -9, RS2_USB_STATUS_INTERRUPTED = -10, RS2_USB_STATUS_NO_MEM = -11,
  RS2_USB_STATUS_NOT_SUPPORTED = -12, RS2_USB_STATUS_OTHER = -13
}
 
enum  _usb_subclass { RS2_USB_SUBCLASS_VIDEO_CONTROL = 0x01, RS2_USB_SUBCLASS_VIDEO_STREAMING = 0x02 }
 
enum  call_type {
  call_type::none, call_type::query_uvc_devices, call_type::query_usb_devices, call_type::send_command,
  call_type::create_usb_device, call_type::create_uvc_device, call_type::uvc_get_location, call_type::uvc_set_power_state,
  call_type::uvc_get_power_state, call_type::uvc_lock, call_type::uvc_unlock, call_type::uvc_get_pu,
  call_type::uvc_set_pu, call_type::uvc_get_pu_range, call_type::uvc_get_xu_range, call_type::uvc_init_xu,
  call_type::uvc_set_xu, call_type::uvc_get_xu, call_type::uvc_stream_profiles, call_type::uvc_probe_commit,
  call_type::uvc_play, call_type::uvc_start_callbacks, call_type::uvc_stop_callbacks, call_type::uvc_close,
  call_type::uvc_frame, call_type::create_hid_device, call_type::query_hid_devices, call_type::hid_register_profiles,
  call_type::hid_open, call_type::hid_close, call_type::hid_stop_capture, call_type::hid_start_capture,
  call_type::hid_frame, call_type::hid_get_sensors, call_type::hid_get_custom_report_data, call_type::device_watcher_start,
  call_type::device_watcher_event, call_type::device_watcher_stop, call_type::uvc_get_usb_specification
}
 
enum  create_and_open_status { Mutex_Succeed, Mutex_TotalFailure, Mutex_AlreadyExist }
 
enum  custom_sensor_report_field {
  minimum, maximum, name, size,
  unit_expo, units, value
}
 
enum  device_type {
  device_type::uvc, device_type::usb, device_type::hid, device_type::hid_sensor,
  device_type::hid_input
}
 
enum  HID_REQUEST_CODE {
  HID_REQUEST_GET_REPORT = 0x1, HID_REQUEST_GET_IDLE = 0x2, HID_REQUEST_GET_PROTOCOL = 0x3, HID_REQUEST_SET_REPORT = 0x9,
  HID_REQUEST_SET_IDLE = 0xa, HID_REQUEST_SET_PROTOCOL = 0xb
}
 
enum  power_state { D0, D3 }
 
enum  supported_kernel_buf_types : uint8_t { e_video_buf, e_metadata_buf, e_max_kernel_buf_type }
 
enum  USB_REQUEST_CODE { USB_REQUEST_CODE_GET = 0xa1, USB_REQUEST_CODE_SET = 0x21 }
 
enum  usb_spec : uint16_t {
  usb_undefined = 0, usb1_type = 0x0100, usb1_1_type = 0x0110, usb2_type = 0x0200,
  usb2_01_type = 0x0201, usb2_1_type = 0x0210, usb3_type = 0x0300, usb3_1_type = 0x0310,
  usb3_2_type = 0x0320
}
 

Functions

bool check (const char *call, HRESULT hr, bool to_throw)
 
std::shared_ptr< backendcreate_backend ()
 
std::shared_ptr< hid_devicecreate_rshid_device (hid_device_info info)
 
std::shared_ptr< uvc_devicecreate_rsuvc_device (uvc_device_info info)
 
long from_100micros (long val)
 
void get_block_range (const std::vector< usb_descriptor > &descs, int mi, int &begin, int &end)
 
static uint32_t get_dev_capabilities (const std::string dev_name)
 
USB_DEVICE_DESCRIPTOR get_device_descriptor (WINUSB_INTERFACE_HANDLE handle)
 
std::vector< uint8_tget_device_descriptors (WINUSB_INTERFACE_HANDLE handle)
 
std::string get_device_path (libusb_device *usb_device)
 
bool get_id (DEVINST devinst, std::string *p_out_str)
 
std::string get_id (DEVINST devinst)
 
usb_device_info get_info (const std::wstring device_wstr)
 
std::wstring get_path (HANDLE h, ULONG index)
 
std::vector< usb_device_infoget_subdevices (libusb_device *device, libusb_device_descriptor desc)
 
static usb_spec get_usb_connection_type (std::string path)
 
bool get_usb_descriptors (uint16_t device_vid, uint16_t device_pid, const std::string &device_uid, std::string &location, usb_spec &spec, std::string &serial)
 
bool get_usb_device_descriptors (DEVINST devinst, uint16_t device_vid, uint16_t device_pid, const std::string &device_uid, std::string &location, usb_spec &spec, std::string &serial, std::string &parent_uid)
 
bool handle_node (const std::wstring &targetKey, HANDLE h, ULONG index)
 
std::tuple< std::string, usb_spechandle_usb_hub (const std::wstring &targetKey, const std::wstring &path)
 
std::string hr_to_string (HRESULT hr)
 
std::wstring instance_id_from_device_path (LPCWSTR path)
 
void internal_callback (struct libusb_transfer *transfer)
 
static bool is_heighr_or_equel_to_min_version (std::string api_version, std::string min_api_version)
 
bool is_win10_redstone2 ()
 
static usb_status libusb_status_to_rs (int sts)
 
PSECURITY_DESCRIPTOR make_allow_all_security_descriptor (void)
 
bool operator== (const hid_device_info &a, const hid_device_info &b)
 
bool operator== (const stream_profile &a, const stream_profile &b)
 
bool operator== (const uvc_device_info &a, const uvc_device_info &b)
 
bool operator== (const usb_device_info &a, const usb_device_info &b)
 
bool operator== (const playback_device_info &a, const playback_device_info &b)
 
bool operator== (const tm2_device_info &a, const tm2_device_info &b)
 
bool parse_usb_path_from_device_id (uint16_t &vid, uint16_t &pid, uint16_t &mi, std::string &unique_id, const std::string &device_id)
 
bool parse_usb_path_multiple_interface (uint16_t &vid, uint16_t &pid, uint16_t &mi, std::string &unique_id, const std::string &path, std::string &device_guid)
 
bool parse_usb_path_single_interface (uint16_t &vid, uint16_t &pid, std::string &serial, const std::string &path)
 
std::vector< std::wstring > query_by_interface (GUID guid)
 
std::vector< std::wstring > query_by_interface (const std::string &guidStr)
 
std::vector< hid_device_infoquery_hid_devices_info ()
 
std::vector< uvc_device_infoquery_uvc_devices_info ()
 
void ReadFromBuffer (control_range &cfg, BYTE *buffer, int length)
 
void req_io_buff (int fd, uint32_t count, std::string dev_name, v4l2_memory mem_type, v4l2_buf_type type)
 
template<class T >
static void safe_release (T &ppT)
 
 STDMETHODIMP_ (ULONG) source_reader_callback
 
void stream_ctl_on (int fd, v4l2_buf_type type=V4L2_BUF_TYPE_VIDEO_CAPTURE)
 
void stream_off (int fd, v4l2_buf_type type=V4L2_BUF_TYPE_VIDEO_CAPTURE)
 
std::string time_in_HH_MM_SS_MMM ()
 
bool tm_boot (const std::vector< usb_device_info > &devices)
 
long to_100micros (long v)
 
std::vector< std::stringtokenize (std::string string, char separator)
 
static usb_status usbhost_status_to_rs (int sts)
 
void uvc_process_bulk_payload (backend_frame_ptr fp, size_t payload_len, backend_frames_queue &queue)
 
template<typename T >
size_t vector_bytes_size (const typename std::vector< T > &vec)
 
std::string win_to_utf (const WCHAR *s)
 
static usb_status winusb_status_to_rs (DWORD sts)
 
template<typename T >
bool write_fs_attribute (const std::string &path, const T &val)
 
static int xioctl (int fh, unsigned long request, void *arg)
 
static int xioctl (int fh, unsigned long request, void *arg)
 

Variables

static const pu_control ct_controls []
 
const std::map< std::string, usb_classguids
 
const uint32_t hid_buf_len = 128
 
constexpr uint8_t hid_header_size = sizeof(hid_header)
 
static const pu_control pu_controls []
 
static const std::map< usb_spec, std::stringusb_spec_names
 
static std::map< usb_status, std::stringusb_status_to_string
 
constexpr uint8_t uvc_header_size = sizeof(uvc_header)
 

Typedef Documentation

Definition at line 485 of file recorder.h.

Definition at line 574 of file backend.h.

typedef std::function<void(const uvc_device_info&, IMFActivate*)> librealsense::platform::enumeration_callback

Definition at line 47 of file mf-uvc.h.

typedef ULONG(__stdcall* librealsense::platform::fnRtlGetVersion) (PRTL_OSVERSIONINFOW lpVersionInformation)

Definition at line 63 of file win-helpers.cpp.

typedef std::function<void(stream_profile, frame_object, std::function<void()>)> librealsense::platform::frame_callback

Definition at line 177 of file backend.h.

typedef std::function<void(const sensor_data&)> librealsense::platform::hid_callback

Definition at line 327 of file backend.h.

Definition at line 29 of file usb-device.h.

Definition at line 24 of file usb-endpoint.h.

Definition at line 31 of file usb-interface.h.

Definition at line 26 of file usb-messenger.h.

Definition at line 41 of file usb-request.h.

Definition at line 18 of file usb-request.h.

Definition at line 122 of file backend.h.

Enumeration Type Documentation

Enumerator
RS2_USB_ENDPOINT_DIRECTION_WRITE 
RS2_USB_ENDPOINT_DIRECTION_READ 

Definition at line 65 of file usb-types.h.

Enumerator
RS2_USB_ENDPOINT_CONTROL 
RS2_USB_ENDPOINT_ISOCHRONOUS 
RS2_USB_ENDPOINT_BULK 
RS2_USB_ENDPOINT_INTERRUPT 

Definition at line 71 of file usb-types.h.

Enumerator
RS2_USB_CLASS_UNSPECIFIED 
RS2_USB_CLASS_AUDIO 
RS2_USB_CLASS_COM 
RS2_USB_CLASS_HID 
RS2_USB_CLASS_PID 
RS2_USB_CLASS_IMAGE 
RS2_USB_CLASS_PRINTER 
RS2_USB_CLASS_MASS_STORAGE 
RS2_USB_CLASS_HUB 
RS2_USB_CLASS_CDC_DATA 
RS2_USB_CLASS_SMART_CARD 
RS2_USB_CLASS_CONTENT_SECURITY 
RS2_USB_CLASS_VIDEO 
RS2_USB_CLASS_PHDC 
RS2_USB_CLASS_AV 
RS2_USB_CLASS_BILLBOARD 
RS2_USB_CLASS_DIAGNOSTIC_DEVIE 
RS2_USB_CLASS_WIRELESS_CONTROLLER 
RS2_USB_CLASS_MISCELLANEOUS 
RS2_USB_CLASS_APPLICATION_SPECIFIC 
RS2_USB_CLASS_VENDOR_SPECIFIC 

Definition at line 80 of file usb-types.h.

Enumerator
RS2_USB_STATUS_SUCCESS 
RS2_USB_STATUS_IO 
RS2_USB_STATUS_INVALID_PARAM 
RS2_USB_STATUS_ACCESS 
RS2_USB_STATUS_NO_DEVICE 
RS2_USB_STATUS_NOT_FOUND 
RS2_USB_STATUS_BUSY 
RS2_USB_STATUS_TIMEOUT 
RS2_USB_STATUS_OVERFLOW 
RS2_USB_STATUS_PIPE 
RS2_USB_STATUS_INTERRUPTED 
RS2_USB_STATUS_NO_MEM 
RS2_USB_STATUS_NOT_SUPPORTED 
RS2_USB_STATUS_OTHER 

Definition at line 47 of file usb-types.h.

Enumerator
RS2_USB_SUBCLASS_VIDEO_CONTROL 
RS2_USB_SUBCLASS_VIDEO_STREAMING 

Definition at line 105 of file usb-types.h.

Enumerator
none 
query_uvc_devices 
query_usb_devices 
send_command 
create_usb_device 
create_uvc_device 
uvc_get_location 
uvc_set_power_state 
uvc_get_power_state 
uvc_lock 
uvc_unlock 
uvc_get_pu 
uvc_set_pu 
uvc_get_pu_range 
uvc_get_xu_range 
uvc_init_xu 
uvc_set_xu 
uvc_get_xu 
uvc_stream_profiles 
uvc_probe_commit 
uvc_play 
uvc_start_callbacks 
uvc_stop_callbacks 
uvc_close 
uvc_frame 
create_hid_device 
query_hid_devices 
hid_register_profiles 
hid_open 
hid_close 
hid_stop_capture 
hid_start_capture 
hid_frame 
hid_get_sensors 
hid_get_custom_report_data 
device_watcher_start 
device_watcher_event 
device_watcher_stop 
uvc_get_usb_specification 

Definition at line 20 of file recorder.h.

Enumerator
Mutex_Succeed 
Mutex_TotalFailure 
Mutex_AlreadyExist 

Definition at line 146 of file win-helpers.h.

Enumerator
minimum 
maximum 
name 
size 
unit_expo 
units 
value 

Definition at line 303 of file backend.h.

Enumerator
uvc 
usb 
hid 
hid_sensor 
hid_input 

Definition at line 64 of file recorder.cpp.

Enumerator
HID_REQUEST_GET_REPORT 
HID_REQUEST_GET_IDLE 
HID_REQUEST_GET_PROTOCOL 
HID_REQUEST_SET_REPORT 
HID_REQUEST_SET_IDLE 
HID_REQUEST_SET_PROTOCOL 

Definition at line 36 of file hid-types.h.

Enumerator
D0 
D3 

Definition at line 116 of file backend.h.

Enumerator
e_video_buf 
e_metadata_buf 
e_max_kernel_buf_type 

Definition at line 154 of file backend-v4l2.h.

Enumerator
USB_REQUEST_CODE_GET 
USB_REQUEST_CODE_SET 

Definition at line 31 of file hid-types.h.

Enumerator
usb_undefined 
usb1_type 
usb1_1_type 
usb2_type 
usb2_01_type 
usb2_1_type 
usb3_type 
usb3_1_type 
usb3_2_type 

Definition at line 112 of file usb-types.h.

Function Documentation

bool librealsense::platform::check ( const char *  call,
HRESULT  hr,
bool  to_throw 
)

Definition at line 79 of file win-helpers.cpp.

std::shared_ptr< backend > librealsense::platform::create_backend ( )

Definition at line 11 of file rsusb-backend-android.cpp.

std::shared_ptr< hid_device > librealsense::platform::create_rshid_device ( hid_device_info  info)

Definition at line 38 of file hid-device.cpp.

std::shared_ptr< uvc_device > librealsense::platform::create_rsuvc_device ( uvc_device_info  info)

Definition at line 62 of file uvc-device.cpp.

long librealsense::platform::from_100micros ( long  val)

Definition at line 489 of file mf-uvc.cpp.

void librealsense::platform::get_block_range ( const std::vector< usb_descriptor > &  descs,
int  mi,
int &  begin,
int &  end 
)

Definition at line 342 of file uvc-parser.cpp.

static uint32_t librealsense::platform::get_dev_capabilities ( const std::string  dev_name)
static

Definition at line 446 of file backend-v4l2.cpp.

USB_DEVICE_DESCRIPTOR librealsense::platform::get_device_descriptor ( WINUSB_INTERFACE_HANDLE  handle)

Definition at line 33 of file device-winusb.cpp.

std::vector<uint8_t> librealsense::platform::get_device_descriptors ( WINUSB_INTERFACE_HANDLE  handle)

Definition at line 44 of file device-winusb.cpp.

std::string librealsense::platform::get_device_path ( libusb_device *  usb_device)

Definition at line 15 of file enumerator-libusb.cpp.

bool librealsense::platform::get_id ( DEVINST  devinst,
std::string p_out_str 
)

Definition at line 376 of file win-helpers.cpp.

std::string librealsense::platform::get_id ( DEVINST  devinst)

Definition at line 394 of file win-helpers.cpp.

usb_device_info librealsense::platform::get_info ( const std::wstring  device_wstr)

Definition at line 81 of file enumerator-winusb.cpp.

std::wstring librealsense::platform::get_path ( HANDLE  h,
ULONG  index 
)

Definition at line 295 of file win-helpers.cpp.

std::vector<usb_device_info> librealsense::platform::get_subdevices ( libusb_device *  device,
libusb_device_descriptor  desc 
)

Definition at line 36 of file enumerator-libusb.cpp.

static usb_spec librealsense::platform::get_usb_connection_type ( std::string  path)
static

Definition at line 425 of file backend-v4l2.cpp.

bool librealsense::platform::get_usb_descriptors ( uint16_t  device_vid,
uint16_t  device_pid,
const std::string device_uid,
std::string location,
usb_spec spec,
std::string serial 
)

Definition at line 511 of file win-helpers.cpp.

bool librealsense::platform::get_usb_device_descriptors ( DEVINST  devinst,
uint16_t  device_vid,
uint16_t  device_pid,
const std::string device_uid,
std::string location,
usb_spec spec,
std::string serial,
std::string parent_uid 
)

Definition at line 555 of file win-helpers.cpp.

bool librealsense::platform::handle_node ( const std::wstring &  targetKey,
HANDLE  h,
ULONG  index 
)

Definition at line 264 of file win-helpers.cpp.

std::tuple<std::string,usb_spec> librealsense::platform::handle_usb_hub ( const std::wstring &  targetKey,
const std::wstring &  path 
)

Definition at line 320 of file win-helpers.cpp.

std::string librealsense::platform::hr_to_string ( HRESULT  hr)

Definition at line 54 of file win-helpers.cpp.

std::wstring librealsense::platform::instance_id_from_device_path ( LPCWSTR  path)

Definition at line 427 of file win-helpers.cpp.

void librealsense::platform::internal_callback ( struct libusb_transfer *  transfer)

Definition at line 12 of file request-libusb.cpp.

static bool librealsense::platform::is_heighr_or_equel_to_min_version ( std::string  api_version,
std::string  min_api_version 
)
static

Definition at line 367 of file recorder.cpp.

bool librealsense::platform::is_win10_redstone2 ( )

Definition at line 66 of file win-helpers.cpp.

static usb_status librealsense::platform::libusb_status_to_rs ( int  sts)
static

Definition at line 17 of file handle-libusb.h.

PSECURITY_DESCRIPTOR librealsense::platform::make_allow_all_security_descriptor ( void  )

Definition at line 799 of file win-helpers.cpp.

bool librealsense::platform::operator== ( const hid_device_info a,
const hid_device_info b 
)
inline

Definition at line 97 of file hid-types.h.

bool librealsense::platform::operator== ( const stream_profile a,
const stream_profile b 
)
inline

Definition at line 138 of file backend.h.

bool librealsense::platform::operator== ( const uvc_device_info a,
const uvc_device_info b 
)
inline

Definition at line 215 of file backend.h.

bool librealsense::platform::operator== ( const usb_device_info a,
const usb_device_info b 
)
inline

Definition at line 227 of file backend.h.

bool librealsense::platform::operator== ( const playback_device_info a,
const playback_device_info b 
)
inline

Definition at line 250 of file backend.h.

bool librealsense::platform::operator== ( const tm2_device_info a,
const tm2_device_info b 
)
inline

Definition at line 268 of file backend.h.

bool librealsense::platform::parse_usb_path_from_device_id ( uint16_t vid,
uint16_t pid,
uint16_t mi,
std::string unique_id,
const std::string device_id 
)

Definition at line 216 of file win-helpers.cpp.

bool librealsense::platform::parse_usb_path_multiple_interface ( uint16_t vid,
uint16_t pid,
uint16_t mi,
std::string unique_id,
const std::string path,
std::string device_guid 
)

Definition at line 132 of file win-helpers.cpp.

bool librealsense::platform::parse_usb_path_single_interface ( uint16_t vid,
uint16_t pid,
std::string serial,
const std::string path 
)

Definition at line 186 of file win-helpers.cpp.

std::vector<std::wstring> librealsense::platform::query_by_interface ( GUID  guid)

Definition at line 42 of file enumerator-winusb.cpp.

std::vector<std::wstring> librealsense::platform::query_by_interface ( const std::string guidStr)

Definition at line 73 of file enumerator-winusb.cpp.

std::vector< hid_device_info > librealsense::platform::query_hid_devices_info ( )

Definition at line 13 of file hid-device.cpp.

std::vector< uvc_device_info > librealsense::platform::query_uvc_devices_info ( )

Definition at line 40 of file uvc-device.cpp.

void librealsense::platform::ReadFromBuffer ( control_range cfg,
BYTE buffer,
int  length 
)

Definition at line 329 of file mf-uvc.cpp.

void librealsense::platform::req_io_buff ( int  fd,
uint32_t  count,
std::string  dev_name,
v4l2_memory  mem_type,
v4l2_buf_type  type 
)

Definition at line 480 of file backend-v4l2.cpp.

template<class T >
static void librealsense::platform::safe_release ( T &  ppT)
static

Definition at line 62 of file mf-uvc.h.

librealsense::platform::STDMETHODIMP_ ( ULONG  )

Definition at line 155 of file mf-uvc.cpp.

void librealsense::platform::stream_ctl_on ( int  fd,
v4l2_buf_type  type = V4L2_BUF_TYPE_VIDEO_CAPTURE 
)

Definition at line 468 of file backend-v4l2.cpp.

void librealsense::platform::stream_off ( int  fd,
v4l2_buf_type  type = V4L2_BUF_TYPE_VIDEO_CAPTURE 
)

Definition at line 474 of file backend-v4l2.cpp.

std::string librealsense::platform::time_in_HH_MM_SS_MMM ( )

Definition at line 875 of file backend-v4l2.cpp.

bool librealsense::platform::tm_boot ( const std::vector< usb_device_info > &  devices)

Definition at line 48 of file tm-boot.h.

long librealsense::platform::to_100micros ( long  v)

Definition at line 483 of file mf-uvc.cpp.

std::vector< std::string > librealsense::platform::tokenize ( std::string  string,
char  separator 
)

Definition at line 108 of file win-helpers.cpp.

static usb_status librealsense::platform::usbhost_status_to_rs ( int  sts)
static

Definition at line 23 of file device-usbhost.h.

void librealsense::platform::uvc_process_bulk_payload ( backend_frame_ptr  fp,
size_t  payload_len,
backend_frames_queue queue 
)

Definition at line 42 of file uvc-streamer.cpp.

template<typename T >
size_t librealsense::platform::vector_bytes_size ( const typename std::vector< T > &  vec)

Definition at line 48 of file win-helpers.cpp.

std::string librealsense::platform::win_to_utf ( const WCHAR *  s)

Definition at line 94 of file win-helpers.cpp.

static usb_status librealsense::platform::winusb_status_to_rs ( DWORD  sts)
static

Definition at line 16 of file handle-winusb.h.

template<typename T >
bool librealsense::platform::write_fs_attribute ( const std::string path,
const T &  val 
)
inline

Definition at line 39 of file backend-hid.h.

static int librealsense::platform::xioctl ( int  fh,
unsigned long  request,
void arg 
)
static
static int librealsense::platform::xioctl ( int  fh,
unsigned long  request,
void arg 
)
static

Definition at line 224 of file backend-v4l2.cpp.

Variable Documentation

const pu_control librealsense::platform::ct_controls[]
static
Initial value:
= {
{ RS2_OPTION_AUTO_EXPOSURE_PRIORITY, KSPROPERTY_CAMERACONTROL_AUTO_EXPOSURE_PRIORITY },
}

Definition at line 479 of file mf-uvc.cpp.

const std::map<std::string, usb_class> librealsense::platform::guids
Initial value:
= {
{"{175695cd-30d9-4f87-8be3-5a8270f49a31}", RS2_USB_CLASS_VENDOR_SPECIFIC},
{"{a5dcbf10-6530-11d2-901f-00c04fb951ed}", RS2_USB_CLASS_UNSPECIFIED},
{"{ca3e7ab9-b4c3-4ae6-8251-579ef933890f}", RS2_USB_CLASS_VIDEO},
{"{08090549-ce78-41dc-a0fb-1bd66694bb0c}", RS2_USB_CLASS_VENDOR_SPECIFIC},
{"{68f2c451-0c22-415e-8293-7a903437e725}", RS2_USB_CLASS_VIDEO},
{"{ee390e5d-4f81-4543-a405-3686e712dc7b}", RS2_USB_CLASS_HID},
{"{2f8549de-7dc3-4e5c-9821-d71ba00bec8c}", RS2_USB_CLASS_VENDOR_SPECIFIC},
}

Definition at line 32 of file enumerator-winusb.cpp.

const uint32_t librealsense::platform::hid_buf_len = 128

Definition at line 15 of file backend-hid.h.

constexpr uint8_t librealsense::platform::hid_header_size = sizeof(hid_header)

Definition at line 166 of file backend.h.

const pu_control librealsense::platform::pu_controls[]
static
Initial value:
= {
{ RS2_OPTION_BRIGHTNESS, KSPROPERTY_VIDEOPROCAMP_BRIGHTNESS },
{ RS2_OPTION_CONTRAST, KSPROPERTY_VIDEOPROCAMP_CONTRAST },
{ RS2_OPTION_HUE, KSPROPERTY_VIDEOPROCAMP_HUE },
{ RS2_OPTION_SATURATION, KSPROPERTY_VIDEOPROCAMP_SATURATION },
{ RS2_OPTION_SHARPNESS, KSPROPERTY_VIDEOPROCAMP_SHARPNESS },
{ RS2_OPTION_GAMMA, KSPROPERTY_VIDEOPROCAMP_GAMMA },
{ RS2_OPTION_WHITE_BALANCE, KSPROPERTY_VIDEOPROCAMP_WHITEBALANCE },
{ RS2_OPTION_ENABLE_AUTO_WHITE_BALANCE, KSPROPERTY_VIDEOPROCAMP_WHITEBALANCE, true },
{ RS2_OPTION_BACKLIGHT_COMPENSATION, KSPROPERTY_VIDEOPROCAMP_BACKLIGHT_COMPENSATION },
{ RS2_OPTION_GAIN, KSPROPERTY_VIDEOPROCAMP_GAIN },
{ RS2_OPTION_POWER_LINE_FREQUENCY, KSPROPERTY_VIDEOPROCAMP_POWERLINE_FREQUENCY }
}

Definition at line 464 of file mf-uvc.cpp.

const std::map<usb_spec, std::string> librealsense::platform::usb_spec_names
static
std::map<usb_status,std::string> librealsense::platform::usb_status_to_string
static
Initial value:
=
{
{RS2_USB_STATUS_SUCCESS, "RS2_USB_STATUS_SUCCESS"},
{RS2_USB_STATUS_IO, "RS2_USB_STATUS_IO"},
{RS2_USB_STATUS_INVALID_PARAM, "RS2_USB_STATUS_INVALID_PARAM"},
{RS2_USB_STATUS_ACCESS, "RS2_USB_STATUS_ACCESS"},
{RS2_USB_STATUS_NO_DEVICE, "RS2_USB_STATUS_NO_DEVICE"},
{RS2_USB_STATUS_NOT_FOUND, "RS2_USB_STATUS_NOT_FOUND"},
{RS2_USB_STATUS_BUSY, "RS2_USB_STATUS_BUSY"},
{RS2_USB_STATUS_TIMEOUT, "RS2_USB_STATUS_TIMEOUT"},
{RS2_USB_STATUS_OVERFLOW, "RS2_USB_STATUS_OVERFLOW"},
{RS2_USB_STATUS_PIPE, "RS2_USB_STATUS_PIPE"},
{RS2_USB_STATUS_INTERRUPTED, "RS2_USB_STATUS_INTERRUPTED"},
{RS2_USB_STATUS_NO_MEM, "RS2_USB_STATUS_NO_MEM"},
{RS2_USB_STATUS_NOT_SUPPORTED, "RS2_USB_STATUS_NOT_SUPPORTED"},
{RS2_USB_STATUS_OTHER, "RS2_USB_STATUS_OTHER"}
}

Definition at line 162 of file usb-types.h.

constexpr uint8_t librealsense::platform::uvc_header_size = sizeof(uvc_header)

Definition at line 165 of file backend.h.



librealsense2
Author(s): Sergey Dorodnicov , Doron Hirshberg , Mark Horn , Reagan Lopez , Itay Carpis
autogenerated on Mon May 3 2021 02:50:39