Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
rsimpl Namespace Reference

Namespaces

namespace  ds
namespace  f200
namespace  hw_monitor
namespace  ivcam
namespace  motion_module
namespace  sr300
namespace  uvc
namespace  zr300

Classes

class  auto_exposure_algorithm
class  auto_exposure_mechanism
class  big_endian
struct  bytes
struct  calibration
class  calibration_validator
struct  cam_mode
class  color_timestamp_reader
class  concurrent_queue
struct  data_polling_request
struct  device_config
class  dinghy_timestamp_reader
struct  f200_inzi_pixel
class  final
class  firmware_version
class  fisheye_auto_exposure_state
struct  fisheye_intrinsic
class  fisheye_timestamp_reader
struct  float3
struct  float3x3
class  fps_calc
class  frame_archive
class  frame_callback
class  frame_callback_ptr
class  frame_continuation
struct  frame_interface
struct  frame_timestamp_reader
struct  IMU_extrinsic
struct  IMU_intrinsic
struct  IMU_version
struct  int2
struct  interstream_rule
class  iv_camera
class  log_callback
class  logger_type
struct  mm_extrinsic
struct  MM_intrinsics
class  motion_events_callback
struct  motion_module_calibration
struct  native_pixel_format
struct  pixel_format_unpacker
struct  pose
class  rolling_timestamp_reader
struct  search_request_params
struct  serial_number
class  serial_timestamp_generator
class  small_heap
struct  static_device_info
struct  stream_interface
struct  stream_request
struct  struct_interface
struct  subdevice_mode
struct  subdevice_mode_selection
struct  supported_capability
struct  supported_option
class  syncronizing_archive
class  timestamp_corrector
class  timestamp_corrector_interface
class  timestamp_events_callback
struct  to_string
class  wraparound_mechanism
struct  y12i_pixel
struct  y8i_pixel

Typedefs

typedef uint8_t byte
typedef void(* frame_callback_function_ptr )(rs_device *dev, rs_frame_ref *frame, void *user)
typedef void(* log_callback_function_ptr )(rs_log_severity severity, const char *message, void *user)
typedef std::unique_ptr
< rs_log_callback, void(*)(rs_log_callback *) 
log_callback_ptr )
typedef void(* motion_callback_function_ptr )(rs_device *dev, rs_motion_data data, void *user)
typedef std::unique_ptr
< rs_motion_callback, void(*)(rs_motion_callback *) 
motion_callback_ptr )
typedef void(* timestamp_callback_function_ptr )(rs_device *dev, rs_timestamp_data data, void *user)
typedef std::unique_ptr
< rs_timestamp_callback, void(*)(rs_timestamp_callback *) 
timestamp_callback_ptr )

Enumerations

enum  auto_exposure_modes { static_auto_exposure = 0, auto_exposure_anti_flicker, auto_exposure_hybrid }

Functions

void align_disparity_to_other (byte *disparity_aligned_to_other, const uint16_t *disparity_pixels, float disparity_scale, const rs_intrinsics &disparity_intrin, const rs_extrinsics &disparity_to_other, const rs_intrinsics &other_intrin)
template<class GET_DEPTH , class TRANSFER_PIXEL >
void align_images (const rs_intrinsics &depth_intrin, const rs_extrinsics &depth_to_other, const rs_intrinsics &other_intrin, GET_DEPTH get_depth, TRANSFER_PIXEL transfer_pixel)
template<class GET_DEPTH >
void align_other_to_depth (byte *other_aligned_to_depth, GET_DEPTH get_depth, const rs_intrinsics &depth_intrin, const rs_extrinsics &depth_to_other, const rs_intrinsics &other_intrin, const byte *other_pixels, rs_format other_format)
template<int N, class GET_DEPTH >
void align_other_to_depth_bytes (byte *other_aligned_to_depth, GET_DEPTH get_depth, const rs_intrinsics &depth_intrin, const rs_extrinsics &depth_to_other, const rs_intrinsics &other_intrin, const byte *other_pixels)
void align_other_to_disparity (byte *other_aligned_to_disparity, const uint16_t *disparity_pixels, float disparity_scale, const rs_intrinsics &disparity_intrin, const rs_extrinsics &disparity_to_other, const rs_intrinsics &other_intrin, const byte *other_pixels, rs_format other_format)
void align_other_to_z (byte *other_aligned_to_z, const uint16_t *z_pixels, float z_scale, const rs_intrinsics &z_intrin, const rs_extrinsics &z_to_other, const rs_intrinsics &other_intrin, const byte *other_pixels, rs_format other_format)
void align_z_to_other (byte *z_aligned_to_other, const uint16_t *z_pixels, float z_scale, const rs_intrinsics &z_intrin, const rs_extrinsics &z_to_other, const rs_intrinsics &other_intrin)
bool check_not_all_zeros (std::vector< byte > data)
std::vector< intcompute_rectification_table (const rs_intrinsics &rect_intrin, const rs_extrinsics &rect_to_unrect, const rs_intrinsics &unrect_intrin)
template<size_t SIZE>
void copy_pixels (byte *const dest[], const byte *source, int count)
void copy_raw10 (byte *const dest[], const byte *source, int count)
void correct_lr_auto_exposure_params (rs_device_base *device, ae_params &params)
template<class MAP_DEPTH >
void deproject_depth (float *points, const rs_intrinsics &intrin, const uint16_t *depth, MAP_DEPTH map_depth)
void deproject_disparity (float *points, const rs_intrinsics &disparity_intrin, const uint16_t *disparity_pixels, float disparity_scale)
void deproject_z (float *points, const rs_intrinsics &z_intrin, const uint16_t *z_pixels, float z_scale)
const ds::dinghyget_dinghy (const subdevice_mode &mode, const void *frame)
static static_device_info get_f200_info (std::shared_ptr< uvc::device >, const ivcam::camera_calib_params &c)
int get_image_bpp (rs_format format)
size_t get_image_size (int width, int height, rs_format format)
rs_log_severity get_minimum_severity ()
static static_device_info get_sr300_info (std::shared_ptr< uvc::device >, const ivcam::camera_calib_params &c)
const char * get_string (rs_stream value)
const char * get_string (rs_format value)
const char * get_string (rs_preset value)
const char * get_string (rs_distortion value)
const char * get_string (rs_option value)
const char * get_string (rs_source value)
const char * get_string (rs_capabilities value)
const char * get_string (rs_event_source value)
const char * get_string (rs_blob_type value)
const char * get_string (rs_camera_info value)
const char * get_string (rs_frame_metadata value)
const char * get_string (rs_timestamp_domain value)
 intrinsic_validator ([](rs_stream){return true;})
pose inverse (const pose &a)
bool is_fisheye_uvc_control (rs_option option)
bool is_fisheye_xu_control (rs_option option)
void log (rs_log_severity severity, const std::string &message)
void log_to_callback (rs_log_severity min_severity, rs_log_callback *callback)
void log_to_callback (rs_log_severity min_severity, void(*on_log)(rs_log_severity min_severity, const char *message, void *user), void *user)
void log_to_console (rs_log_severity min_severity)
void log_to_file (rs_log_severity min_severity, const char *file_path)
std::shared_ptr< rs_devicemake_f200_device (std::shared_ptr< uvc::device > device)
std::shared_ptr< rs_devicemake_lr200_device (std::shared_ptr< uvc::device > device)
std::shared_ptr< rs_devicemake_r200_device (std::shared_ptr< uvc::device > device)
std::shared_ptr< rs_devicemake_sr300_device (std::shared_ptr< uvc::device > device)
template<class T , class R , class W >
struct_interface< T, R, W > make_struct_interface (R r, W w)
std::shared_ptr< rs_devicemake_zr300_device (std::shared_ptr< uvc::device > device)
rs_intrinsics MakeColorIntrinsics (const ivcam::camera_calib_params &c, const int2 &dims)
rs_intrinsics MakeDepthIntrinsics (const ivcam::camera_calib_params &c, const int2 &dims)
float3 operator* (const float3 &a, float b)
float3 operator* (const float3x3 &a, const float3 &b)
float3x3 operator* (const float3x3 &a, const float3x3 &b)
float3 operator* (const pose &a, const float3 &b)
pose operator* (const pose &a, const pose &b)
float3 operator+ (const float3 &a, const float3 &b)
bool operator== (const float3 &a, const float3 &b)
bool operator== (const float3x3 &a, const float3x3 &b)
bool operator== (const pose &a, const pose &b)
bool operator== (const rs_intrinsics &a, const rs_intrinsics &b)
uint32_t pack (uint8_t c0, uint8_t c1, uint8_t c2, uint8_t c3)
rs_intrinsics pad_crop_intrinsics (const rs_intrinsics &i, int pad_crop)
calibration read_calibration (uvc::device &device, std::timed_mutex &mutex)
motion_module_calibration read_fisheye_intrinsic (uvc::device &device)
motion_module_calibration read_fisheye_intrinsic (uvc::device &device, std::timed_mutex &mutex)
serial_number read_serial_number (uvc::device &device, std::timed_mutex &mutex)
void rectify_image (uint8_t *rect_pixels, const std::vector< int > &rectification_table, const uint8_t *unrect_pixels, rs_format format)
template<class T >
void rectify_image_pixels (T *rect_pixels, const std::vector< int > &rectification_table, const T *unrect_pixels)
rs_intrinsics scale_intrinsics (const rs_intrinsics &i, int width, int height)
template<class SOURCE , class SPLIT_A , class SPLIT_B >
void split_frame (byte *const dest[], int count, const SOURCE *source, SPLIT_A split_a, SPLIT_B split_b)
template<typename T >
sqr (const T &x)
template<class T >
void stream_args (std::ostream &out, const char *names, const T &last)
template<class T , class... U>
void stream_args (std::ostream &out, const char *names, const T &first, const U &...rest)
static void translate_exception (const char *name, std::string args, rs_error **error)
float3x3 transpose (const float3x3 &a)
template<class SOURCE , class UNPACK >
void unpack_pixels (byte *const dest[], int count, const SOURCE *source, UNPACK unpack)
void unpack_rw10_from_rw8 (byte *const d[], const byte *s, int n)
void unpack_y16_from_y16_10 (byte *const d[], const byte *s, int n)
void unpack_y16_from_y8 (byte *const d[], const byte *s, int n)
void unpack_y16_y16_from_y12i_10 (byte *const dest[], const byte *source, int count)
void unpack_y8_from_y16_10 (byte *const d[], const byte *s, int n)
void unpack_y8_y8_from_y8i (byte *const dest[], const byte *source, int count)
template<rs_format FORMAT>
void unpack_yuy2 (byte *const d[], const byte *s, int n)
void unpack_z16_y16_from_f200_inzi (byte *const dest[], const byte *source, int count)
void unpack_z16_y16_from_sr300_inzi (byte *const dest[], const byte *source, int count)
void unpack_z16_y8_from_f200_inzi (byte *const dest[], const byte *source, int count)
void unpack_z16_y8_from_sr300_inzi (byte *const dest[], const byte *source, int count)
void update_supported_options (uvc::device &dev, const uvc::extension_unit depth_xu, const std::vector< std::pair< rs_option, char >> options, std::vector< supported_option > &supported_options)

Variables

const std::vector< std::pair
< rs_option, char > > 
eu_F200_depth_controls
const std::vector< std::pair
< rs_option, char > > 
eu_SR300_depth_controls
static const cam_mode f200_color_modes []
static const cam_mode f200_depth_modes []
static const cam_mode f200_ir_only_modes []
static logger_type logger
const native_pixel_format pf_f200_invi
const native_pixel_format pf_f200_inzi
const native_pixel_format pf_invz = { 'Z16 ', 1, 2, { { false, &copy_pixels<2>, { { RS_STREAM_DEPTH, RS_FORMAT_Z16 } } } } }
const native_pixel_format pf_raw8 = { 'RAW8', 1, 1,{ { false, &copy_pixels<1>, { { RS_STREAM_FISHEYE, RS_FORMAT_RAW8 } } } } }
const native_pixel_format pf_rw10 = { 'pRAA', 1, 1,{ { false, &copy_raw10, { { RS_STREAM_COLOR, RS_FORMAT_RAW10 } } } } }
const native_pixel_format pf_rw16 = { 'RW16', 1, 2,{ { false, &copy_pixels<2>, { { RS_STREAM_COLOR, RS_FORMAT_RAW16 } } } } }
const native_pixel_format pf_sr300_invi
const native_pixel_format pf_sr300_inzi
const native_pixel_format pf_y12i = { 'Y12I', 1, 3,{ { true, &unpack_y16_y16_from_y12i_10, { { RS_STREAM_INFRARED, RS_FORMAT_Y16 },{ RS_STREAM_INFRARED2, RS_FORMAT_Y16 } } } } }
const native_pixel_format pf_y16 = { 'Y16 ', 1, 2,{ { true, &unpack_y16_from_y16_10, { { RS_STREAM_INFRARED, RS_FORMAT_Y16 } } } } }
const native_pixel_format pf_y8 = { 'GREY', 1, 1,{ { false, &copy_pixels<1>, { { RS_STREAM_INFRARED, RS_FORMAT_Y8 } } } } }
const native_pixel_format pf_y8i = { 'Y8I ', 1, 2,{ { true, &unpack_y8_y8_from_y8i, { { RS_STREAM_INFRARED, RS_FORMAT_Y8 },{ RS_STREAM_INFRARED2, RS_FORMAT_Y8 } } } } }
const native_pixel_format pf_yuy2
const native_pixel_format pf_z16
static const cam_mode sr300_color_modes []
static const cam_mode sr300_depth_modes []
static const cam_mode sr300_ir_only_modes []

Typedef Documentation

typedef uint8_t rsimpl::byte

Definition at line 42 of file types.h.

Definition at line 327 of file types.h.

Definition at line 330 of file types.h.

Definition at line 426 of file types.h.

Definition at line 328 of file types.h.

Definition at line 427 of file types.h.

Definition at line 329 of file types.h.

Definition at line 428 of file types.h.


Enumeration Type Documentation

Enumerator:
static_auto_exposure 
auto_exposure_anti_flicker 
auto_exposure_hybrid 

Definition at line 177 of file zr300.h.


Function Documentation

void rsimpl::align_disparity_to_other ( byte *  disparity_aligned_to_other,
const uint16_t *  disparity_pixels,
float  disparity_scale,
const rs_intrinsics disparity_intrin,
const rs_extrinsics disparity_to_other,
const rs_intrinsics other_intrin 
)

Definition at line 560 of file image.cpp.

template<class GET_DEPTH , class TRANSFER_PIXEL >
void rsimpl::align_images ( const rs_intrinsics depth_intrin,
const rs_extrinsics depth_to_other,
const rs_intrinsics other_intrin,
GET_DEPTH  get_depth,
TRANSFER_PIXEL  transfer_pixel 
)

Definition at line 515 of file image.cpp.

template<class GET_DEPTH >
void rsimpl::align_other_to_depth ( byte *  other_aligned_to_depth,
GET_DEPTH  get_depth,
const rs_intrinsics depth_intrin,
const rs_extrinsics depth_to_other,
const rs_intrinsics other_intrin,
const byte *  other_pixels,
rs_format  other_format 
)

Definition at line 577 of file image.cpp.

template<int N, class GET_DEPTH >
void rsimpl::align_other_to_depth_bytes ( byte *  other_aligned_to_depth,
GET_DEPTH  get_depth,
const rs_intrinsics depth_intrin,
const rs_extrinsics depth_to_other,
const rs_intrinsics other_intrin,
const byte *  other_pixels 
)

Definition at line 569 of file image.cpp.

void rsimpl::align_other_to_disparity ( byte *  other_aligned_to_disparity,
const uint16_t *  disparity_pixels,
float  disparity_scale,
const rs_intrinsics disparity_intrin,
const rs_extrinsics disparity_to_other,
const rs_intrinsics other_intrin,
const byte *  other_pixels,
rs_format  other_format 
)

Definition at line 599 of file image.cpp.

void rsimpl::align_other_to_z ( byte *  other_aligned_to_z,
const uint16_t *  z_pixels,
float  z_scale,
const rs_intrinsics z_intrin,
const rs_extrinsics z_to_other,
const rs_intrinsics other_intrin,
const byte *  other_pixels,
rs_format  other_format 
)

Definition at line 594 of file image.cpp.

void rsimpl::align_z_to_other ( byte *  z_aligned_to_other,
const uint16_t *  z_pixels,
float  z_scale,
const rs_intrinsics z_intrin,
const rs_extrinsics z_to_other,
const rs_intrinsics other_intrin 
)

Definition at line 552 of file image.cpp.

bool rsimpl::check_not_all_zeros ( std::vector< byte >  data) [inline]

Definition at line 643 of file types.h.

std::vector< int > rsimpl::compute_rectification_table ( const rs_intrinsics rect_intrin,
const rs_extrinsics rect_to_unrect,
const rs_intrinsics unrect_intrin 
)

Definition at line 608 of file image.cpp.

template<size_t SIZE>
void rsimpl::copy_pixels ( byte *const  dest[],
const byte *  source,
int  count 
)

Definition at line 53 of file image.cpp.

void rsimpl::copy_raw10 ( byte *const  dest[],
const byte *  source,
int  count 
)

Definition at line 58 of file image.cpp.

Definition at line 72 of file ds-device.cpp.

template<class MAP_DEPTH >
void rsimpl::deproject_depth ( float *  points,
const rs_intrinsics intrin,
const uint16_t *  depth,
MAP_DEPTH  map_depth 
)

Definition at line 488 of file image.cpp.

void rsimpl::deproject_disparity ( float *  points,
const rs_intrinsics disparity_intrin,
const uint16_t *  disparity_pixels,
float  disparity_scale 
)

Definition at line 506 of file image.cpp.

void rsimpl::deproject_z ( float *  points,
const rs_intrinsics z_intrin,
const uint16_t *  z_pixels,
float  z_scale 
)

Definition at line 501 of file image.cpp.

const ds::dinghy& rsimpl::get_dinghy ( const subdevice_mode mode,
const void frame 
)

Definition at line 670 of file ds-device.cpp.

static static_device_info rsimpl::get_f200_info ( std::shared_ptr< uvc::device >  ,
const ivcam::camera_calib_params &  c 
) [static]

Definition at line 43 of file f200.cpp.

Definition at line 29 of file image.cpp.

size_t rsimpl::get_image_size ( int  width,
int  height,
rs_format  format 
)

Definition at line 22 of file image.cpp.

Definition at line 91 of file log.cpp.

static static_device_info rsimpl::get_sr300_info ( std::shared_ptr< uvc::device >  ,
const ivcam::camera_calib_params &  c 
) [static]

Definition at line 39 of file sr300.cpp.

const char* rsimpl::get_string ( rs_stream  value)

Definition at line 19 of file types.cpp.

const char* rsimpl::get_string ( rs_format  value)

Definition at line 41 of file types.cpp.

const char* rsimpl::get_string ( rs_preset  value)

Definition at line 65 of file types.cpp.

const char* rsimpl::get_string ( rs_distortion  value)

Definition at line 78 of file types.cpp.

const char* rsimpl::get_string ( rs_option  value)

Definition at line 92 of file types.cpp.

const char* rsimpl::get_string ( rs_source  value)

Definition at line 170 of file types.cpp.

const char* rsimpl::get_string ( rs_capabilities  value)

Definition at line 183 of file types.cpp.

const char* rsimpl::get_string ( rs_event_source  value)

Definition at line 202 of file types.cpp.

const char* rsimpl::get_string ( rs_blob_type  value)

Definition at line 219 of file types.cpp.

const char* rsimpl::get_string ( rs_camera_info  value)

Definition at line 230 of file types.cpp.

const char* rsimpl::get_string ( rs_frame_metadata  value)

Definition at line 263 of file types.cpp.

const char* rsimpl::get_string ( rs_timestamp_domain  value)

Definition at line 275 of file types.cpp.

Definition at line 717 of file types.cpp.

pose rsimpl::inverse ( const pose &  a) [inline]

Definition at line 123 of file types.h.

Definition at line 33 of file zr300.cpp.

Definition at line 38 of file zr300.cpp.

void rsimpl::log ( rs_log_severity  severity,
const std::string message 
)

Definition at line 96 of file log.cpp.

void rsimpl::log_to_callback ( rs_log_severity  min_severity,
rs_log_callback callback 
)

Definition at line 111 of file log.cpp.

void rsimpl::log_to_callback ( rs_log_severity  min_severity,
void(*)(rs_log_severity min_severity, const char *message, void *user)  on_log,
void user 
)

Definition at line 116 of file log.cpp.

Definition at line 101 of file log.cpp.

void rsimpl::log_to_file ( rs_log_severity  min_severity,
const char *  file_path 
)

Definition at line 106 of file log.cpp.

std::shared_ptr< rs_device > rsimpl::make_f200_device ( std::shared_ptr< uvc::device >  device)

Definition at line 265 of file f200.cpp.

std::shared_ptr< rs_device > rsimpl::make_lr200_device ( std::shared_ptr< uvc::device >  device)

Definition at line 43 of file r200.cpp.

std::shared_ptr< rs_device > rsimpl::make_r200_device ( std::shared_ptr< uvc::device >  device)

Definition at line 27 of file r200.cpp.

std::shared_ptr< rs_device > rsimpl::make_sr300_device ( std::shared_ptr< uvc::device >  device)

Definition at line 250 of file sr300.cpp.

template<class T , class R , class W >
struct_interface<T, R, W> rsimpl::make_struct_interface ( r,
w 
)

Definition at line 33 of file device.h.

std::shared_ptr< rs_device > rsimpl::make_zr300_device ( std::shared_ptr< uvc::device >  device)

Definition at line 425 of file zr300.cpp.

rs_intrinsics rsimpl::MakeColorIntrinsics ( const ivcam::camera_calib_params &  c,
const int2 dims 
)

Definition at line 22 of file ivcam-device.cpp.

rs_intrinsics rsimpl::MakeDepthIntrinsics ( const ivcam::camera_calib_params &  c,
const int2 dims 
)

Definition at line 16 of file ivcam-device.cpp.

float3 rsimpl::operator* ( const float3 &  a,
float  b 
) [inline]

Definition at line 115 of file types.h.

float3 rsimpl::operator* ( const float3x3 &  a,
const float3 &  b 
) [inline]

Definition at line 117 of file types.h.

float3x3 rsimpl::operator* ( const float3x3 &  a,
const float3x3 &  b 
) [inline]

Definition at line 118 of file types.h.

float3 rsimpl::operator* ( const pose &  a,
const float3 &  b 
) [inline]

Definition at line 121 of file types.h.

pose rsimpl::operator* ( const pose &  a,
const pose &  b 
) [inline]

Definition at line 122 of file types.h.

float3 rsimpl::operator+ ( const float3 &  a,
const float3 &  b 
) [inline]

Definition at line 114 of file types.h.

bool rsimpl::operator== ( const float3 &  a,
const float3 &  b 
) [inline]

Definition at line 113 of file types.h.

bool rsimpl::operator== ( const float3x3 &  a,
const float3x3 &  b 
) [inline]

Definition at line 116 of file types.h.

bool rsimpl::operator== ( const pose &  a,
const pose &  b 
) [inline]

Definition at line 120 of file types.h.

bool rsimpl::operator== ( const rs_intrinsics a,
const rs_intrinsics b 
) [inline]

Definition at line 488 of file types.h.

uint32_t rsimpl::pack ( uint8_t  c0,
uint8_t  c1,
uint8_t  c2,
uint8_t  c3 
) [inline]

Definition at line 490 of file types.h.

rs_intrinsics rsimpl::pad_crop_intrinsics ( const rs_intrinsics i,
int  pad_crop 
) [inline]

Definition at line 477 of file types.h.

calibration rsimpl::read_calibration ( uvc::device &  device,
std::timed_mutex &  mutex 
)

Definition at line 405 of file zr300.cpp.

motion_module_calibration rsimpl::read_fisheye_intrinsic ( uvc::device &  device,
std::timed_mutex &  mutex 
)

Definition at line 415 of file zr300.cpp.

serial_number rsimpl::read_serial_number ( uvc::device &  device,
std::timed_mutex &  mutex 
)

Definition at line 395 of file zr300.cpp.

void rsimpl::rectify_image ( uint8_t *  rect_pixels,
const std::vector< int > &  rectification_table,
const uint8_t *  unrect_pixels,
rs_format  format 
)

Definition at line 622 of file image.cpp.

template<class T >
void rsimpl::rectify_image_pixels ( T *  rect_pixels,
const std::vector< int > &  rectification_table,
const T *  unrect_pixels 
)

Definition at line 617 of file image.cpp.

rs_intrinsics rsimpl::scale_intrinsics ( const rs_intrinsics i,
int  width,
int  height 
) [inline]

Definition at line 482 of file types.h.

template<class SOURCE , class SPLIT_A , class SPLIT_B >
void rsimpl::split_frame ( byte *const  dest[],
int  count,
const SOURCE *  source,
SPLIT_A  split_a,
SPLIT_B  split_b 
)

Definition at line 393 of file image.cpp.

template<typename T >
T rsimpl::sqr ( const T &  x) [inline]

Definition at line 1088 of file zr300.cpp.

template<class T >
void rsimpl::stream_args ( std::ostream &  out,
const char *  names,
const T &  last 
)

Definition at line 26 of file rs.cpp.

template<class T , class... U>
void rsimpl::stream_args ( std::ostream &  out,
const char *  names,
const T &  first,
const U &...  rest 
)

Definition at line 27 of file rs.cpp.

static void rsimpl::translate_exception ( const char *  name,
std::string  args,
rs_error **  error 
) [static]

Definition at line 35 of file rs.cpp.

float3x3 rsimpl::transpose ( const float3x3 &  a) [inline]

Definition at line 119 of file types.h.

template<class SOURCE , class UNPACK >
void rsimpl::unpack_pixels ( byte *const  dest[],
int  count,
const SOURCE *  source,
UNPACK  unpack 
)

Definition at line 63 of file image.cpp.

void rsimpl::unpack_rw10_from_rw8 ( byte *const  d[],
const byte *  s,
int  n 
)

Definition at line 72 of file image.cpp.

void rsimpl::unpack_y16_from_y16_10 ( byte *const  d[],
const byte *  s,
int  n 
)

Definition at line 70 of file image.cpp.

void rsimpl::unpack_y16_from_y8 ( byte *const  d[],
const byte *  s,
int  n 
)

Definition at line 69 of file image.cpp.

void rsimpl::unpack_y16_y16_from_y12i_10 ( byte *const  dest[],
const byte *  source,
int  count 
)

Definition at line 413 of file image.cpp.

void rsimpl::unpack_y8_from_y16_10 ( byte *const  d[],
const byte *  s,
int  n 
)

Definition at line 71 of file image.cpp.

void rsimpl::unpack_y8_y8_from_y8i ( byte *const  dest[],
const byte *  source,
int  count 
)

Definition at line 405 of file image.cpp.

template<rs_format FORMAT>
void rsimpl::unpack_yuy2 ( byte *const  d[],
const byte *  s,
int  n 
)

Definition at line 109 of file image.cpp.

void rsimpl::unpack_z16_y16_from_f200_inzi ( byte *const  dest[],
const byte *  source,
int  count 
)

Definition at line 428 of file image.cpp.

void rsimpl::unpack_z16_y16_from_sr300_inzi ( byte *const  dest[],
const byte *  source,
int  count 
)

Definition at line 443 of file image.cpp.

void rsimpl::unpack_z16_y8_from_f200_inzi ( byte *const  dest[],
const byte *  source,
int  count 
)

Definition at line 421 of file image.cpp.

void rsimpl::unpack_z16_y8_from_sr300_inzi ( byte *const  dest[],
const byte *  source,
int  count 
)

Definition at line 435 of file image.cpp.

void rsimpl::update_supported_options ( uvc::device &  dev,
const uvc::extension_unit  depth_xu,
const std::vector< std::pair< rs_option, char >>  options,
std::vector< supported_option > &  supported_options 
)

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


Variable Documentation

const std::vector<std::pair<rs_option, char> > rsimpl::eu_F200_depth_controls
const std::vector<std::pair<rs_option, char> > rsimpl::eu_SR300_depth_controls
Initial value:
 {
        {{1920, 1080}, {2,5,15,30}},
        {{1280,  720}, {2,5,15,30}},
        {{ 960,  540}, {2,5,15,30,60}},
        {{ 848,  480}, {2,5,15,30,60}},
        {{ 640,  480}, {2,5,15,30,60}},
        {{ 640,  360}, {2,5,15,30,60}},
        {{ 424,  240}, {2,5,15,30,60}},
        {{ 320,  240}, {2,5,15,30,60}},
        {{ 320,  180}, {2,5,15,30,60}}
    }

Definition at line 23 of file f200.cpp.

Initial value:
 {
        {{640, 480}, {2,5,15,30,60}}, 
        {{640, 240}, {2,5,15,30,60}}    
    }

Definition at line 34 of file f200.cpp.

Initial value:
 {
        {{640, 480}, {30,60,120,240,300}}, 
        {{640, 240}, {30,60,120,240,300}}        
    }

Definition at line 38 of file f200.cpp.

Definition at line 88 of file log.cpp.

Initial value:
 { 'Y10 ', 1, 1, { { false, &copy_pixels<1>,                   { { RS_STREAM_INFRARED, RS_FORMAT_Y8 } } },
                                                                { true,  &unpack_y16_from_y8,               { { RS_STREAM_INFRARED, RS_FORMAT_Y16 } } } } }

Definition at line 474 of file image.cpp.

Initial value:

Definition at line 476 of file image.cpp.

const native_pixel_format rsimpl::pf_invz = { 'Z16 ', 1, 2, { { false, &copy_pixels<2>, { { RS_STREAM_DEPTH, RS_FORMAT_Z16 } } } } }

Definition at line 473 of file image.cpp.

const native_pixel_format rsimpl::pf_raw8 = { 'RAW8', 1, 1,{ { false, &copy_pixels<1>, { { RS_STREAM_FISHEYE, RS_FORMAT_RAW8 } } } } }

Definition at line 459 of file image.cpp.

const native_pixel_format rsimpl::pf_rw10 = { 'pRAA', 1, 1,{ { false, &copy_raw10, { { RS_STREAM_COLOR, RS_FORMAT_RAW10 } } } } }

Definition at line 461 of file image.cpp.

const native_pixel_format rsimpl::pf_rw16 = { 'RW16', 1, 2,{ { false, &copy_pixels<2>, { { RS_STREAM_COLOR, RS_FORMAT_RAW16 } } } } }

Definition at line 460 of file image.cpp.

Initial value:
 { 'Y10 ', 1, 2,{  { true,  &unpack_y8_from_y16_10,            { { RS_STREAM_INFRARED, RS_FORMAT_Y8 } } },
                                                                { true,  &unpack_y16_from_y16_10,           { { RS_STREAM_INFRARED, RS_FORMAT_Y16 } } } } }

Definition at line 478 of file image.cpp.

Initial value:

Definition at line 480 of file image.cpp.

Definition at line 470 of file image.cpp.

Definition at line 468 of file image.cpp.

const native_pixel_format rsimpl::pf_y8 = { 'GREY', 1, 1,{ { false, &copy_pixels<1>, { { RS_STREAM_INFRARED, RS_FORMAT_Y8 } } } } }

Definition at line 467 of file image.cpp.

Definition at line 469 of file image.cpp.

Initial value:
 { 'YUY2', 1, 2,{  { true,  &unpack_yuy2<RS_FORMAT_RGB8 >,     { { RS_STREAM_COLOR,    RS_FORMAT_RGB8 } } },
                                                                { false, &copy_pixels<2>,                   { { RS_STREAM_COLOR,    RS_FORMAT_YUYV } } },
                                                                { true,  &unpack_yuy2<RS_FORMAT_RGBA8>,     { { RS_STREAM_COLOR,    RS_FORMAT_RGBA8 } } },
                                                                { true,  &unpack_yuy2<RS_FORMAT_BGR8 >,     { { RS_STREAM_COLOR,    RS_FORMAT_BGR8 } } },
                                                                { true,  &unpack_yuy2<RS_FORMAT_BGRA8>,     { { RS_STREAM_COLOR,    RS_FORMAT_BGRA8 } } } } }

Definition at line 462 of file image.cpp.

Initial value:
 { 'Z16 ', 1, 2,{  { false, &copy_pixels<2>,                   { { RS_STREAM_DEPTH,    RS_FORMAT_Z16 } } },
                                                                { false, &copy_pixels<2>,                   { { RS_STREAM_DEPTH,    RS_FORMAT_DISPARITY16 } } } } }

Definition at line 471 of file image.cpp.

Initial value:
 {
        {{1920, 1080}, { 10,30 } },
        {{1280,  720}, { 10,30,60 } },
        {{ 960,  540}, { 10,30,60 } },
        {{ 848,  480}, { 10,30,60 } },
        {{ 640,  480}, { 10,30,60 } },
        {{ 640,  360}, { 10,30,60 } },
        {{ 424,  240}, { 10,30,60 } },
        {{ 320,  240}, { 10,30,60 } },
        {{ 320,  180}, { 10,30,60 } },
    }

Definition at line 18 of file sr300.cpp.

Initial value:
 {
        {{640, 480}, {10,30,60}},
        {{640, 240}, {10,30,60,110}}
    }

Definition at line 30 of file sr300.cpp.

Initial value:
 {
        {{640, 480}, {30,60,120,200}}
    }

Definition at line 35 of file sr300.cpp.



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