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< int > | compute_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 ¶ms) |
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::dinghy & | get_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_device > | make_f200_device (std::shared_ptr< uvc::device > device) |
std::shared_ptr< rs_device > | make_lr200_device (std::shared_ptr< uvc::device > device) |
std::shared_ptr< rs_device > | make_r200_device (std::shared_ptr< uvc::device > device) |
std::shared_ptr< rs_device > | make_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_device > | make_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 > |
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, ©_pixels<2>, { { RS_STREAM_DEPTH, RS_FORMAT_Z16 } } } } } |
const native_pixel_format | pf_raw8 = { 'RAW8', 1, 1,{ { false, ©_pixels<1>, { { RS_STREAM_FISHEYE, RS_FORMAT_RAW8 } } } } } |
const native_pixel_format | pf_rw10 = { 'pRAA', 1, 1,{ { false, ©_raw10, { { RS_STREAM_COLOR, RS_FORMAT_RAW10 } } } } } |
const native_pixel_format | pf_rw16 = { 'RW16', 1, 2,{ { false, ©_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, ©_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 [] |