|
enum | auto_calib_speed {
speed_very_fast = 0,
speed_fast = 1,
speed_medium = 2,
speed_slow = 3,
speed_white_wall = 4
} |
|
enum | auto_calib_sub_cmd : uint8_t {
py_rx_calib_begin = 0x08,
py_rx_calib_check_status = 0x03,
tare_calib_begin = 0x0b,
tare_calib_check_status = 0x0c,
get_calibration_result = 0x0d,
focal_length_calib_begin = 0x11,
get_focal_legth_calib_result = 0x12,
py_rx_plus_fl_calib_begin = 0x13,
get_py_rx_plus_fl_calib_result = 0x14,
set_coefficients = 0x19
} |
|
enum | auto_exposure_modes { auto_exposure_modes::static_auto_exposure = 0,
auto_exposure_modes::auto_exposure_anti_flicker,
auto_exposure_modes::auto_exposure_hybrid
} |
|
enum | backend_type { backend_type::standard,
backend_type::record,
backend_type::playback
} |
|
enum | cam_data_source : uint32_t { cam_data_source::TakeFromRO = 0,
cam_data_source::TakeFromRW = 1,
cam_data_source::TakeFromRAM = 2
} |
|
enum | data_sampling { polling = 0,
interrupt = 1
} |
|
enum | frame_metadata_internal {
RS2_FRAME_METADATA_HW_TYPE = RS2_FRAME_METADATA_COUNT +1,
RS2_FRAME_METADATA_SKU_ID,
RS2_FRAME_METADATA_FORMAT,
RS2_FRAME_METADATA_WIDTH,
RS2_FRAME_METADATA_HEIGHT,
RS2_FRAME_METADATA_COUNT
} |
| Metadata fields that are utilized internally by librealsense Provides extention to the r2_frame_metadata list of attributes. More...
|
|
enum | holes_filling_types : uint8_t { hf_fill_from_left,
hf_farest_from_around,
hf_nearest_from_around,
hf_max_value
} |
|
enum | hwmon_response : int32_t {
hwm_Success = 0,
hwm_WrongCommand = -1,
hwm_StartNGEndAddr = -2,
hwm_AddressSpaceNotAligned = -3,
hwm_AddressSpaceTooSmall = -4,
hwm_ReadOnly = -5,
hwm_WrongParameter = -6,
hwm_HWNotReady = -7,
hwm_I2CAccessFailed = -8,
hwm_NoExpectedUserAction = -9,
hwm_IntegrityError = -10,
hwm_NullOrZeroSizeString = -11,
hwm_GPIOPinNumberInvalid = -12,
hwm_GPIOPinDirectionInvalid = -13,
hwm_IllegalAddress = -14,
hwm_IllegalSize = -15,
hwm_ParamsTableNotValid = -16,
hwm_ParamsTableIdNotValid = -17,
hwm_ParamsTableWrongExistingSize = -18,
hwm_WrongCRC = -19,
hwm_NotAuthorisedFlashWrite = -20,
hwm_NoDataToReturn = -21,
hwm_SpiReadFailed = -22,
hwm_SpiWriteFailed = -23,
hwm_SpiEraseSectorFailed = -24,
hwm_TableIsEmpty = -25,
hwm_I2cSeqDelay = -26,
hwm_CommandIsLocked = -27,
hwm_CalibrationWrongTableId = -28,
hwm_ValueOutOfRange = -29,
hwm_InvalidDepthFormat = -30,
hwm_DepthFlowError = -31,
hwm_Timeout = -32,
hwm_NotSafeCheckFailed = -33,
hwm_FlashRegionIsLocked = -34,
hwm_SummingEventTimeout = -35,
hwm_SDSCorrupted = -36,
hwm_SDSVerifyFailed = -37,
hwm_IllegalHwState = -38,
hwm_RealtekNotLoaded = -39,
hwm_WakeUpDeviceNotSupported = -40,
hwm_ResourceBusy = -41,
hwm_MaxErrorValue = -42,
hwm_PwmNotSupported = -43,
hwm_PwmStereoModuleNotConnected = -44,
hwm_UvcStreamInvalidStreamRequest = -45,
hwm_UvcControlManualExposureInvalid = -46,
hwm_UvcControlManualGainInvalid = -47,
hwm_EyesafetyPayloadFailure = -48,
hwm_ProjectorTestFailed = -49,
hwm_ThreadModifyFailed = -50,
hwm_HotLaserPwrReduce = -51,
hwm_HotLaserDisable = -52,
hwm_FlagBLaserDisable = -53,
hwm_NoStateChange = -54,
hwm_EEPROMIsLocked = -55,
hwm_OEMIdWrong = -56,
hwm_RealtekNotUpdated = -57,
hwm_FunctionNotSupported = -58,
hwm_IspNotImplemented = -59,
hwm_IspNotSupported = -60,
hwm_IspNotPermited = -61,
hwm_IspNotExists = -62,
hwm_IspFail = -63,
hwm_Unknown = -64,
hwm_LastError = hwm_Unknown - 1
} |
|
enum | IMU_OUTPUT_DATA_RATES : uint16_t {
IMU_OUTPUT_DATA_RATES::IMU_FPS_63 = 63,
IMU_OUTPUT_DATA_RATES::IMU_FPS_100 = 100,
IMU_OUTPUT_DATA_RATES::IMU_FPS_200 = 200,
IMU_OUTPUT_DATA_RATES::IMU_FPS_250 = 250,
IMU_OUTPUT_DATA_RATES::IMU_FPS_400 = 400
} |
|
enum | l500_command {
get_current = 0,
get_min = 1,
get_max = 2,
get_step = 3,
get_default = 4
} |
|
enum | l500_control {
confidence = 0,
post_processing_sharpness = 1,
pre_processing_sharpness = 2,
noise_filtering = 3,
apd = 4,
laser_gain = 5,
min_distance = 6,
invalidation_bypass = 7,
alternate_ir = 8
} |
|
enum | md_capture_stat_attributes : uint32_t {
md_capture_stat_attributes::exposure_time_attribute = (1u << 0),
md_capture_stat_attributes::exposure_compensation_attribute = (1u << 1),
md_capture_stat_attributes::iso_speed_attribute = (1u << 2),
md_capture_stat_attributes::focus_state_attribute = (1u << 3),
md_capture_stat_attributes::lens_posiiton_attribute = (1u << 4),
md_capture_stat_attributes::white_balance_attribute = (1u << 5),
md_capture_stat_attributes::flash_attribute = (1u << 6),
md_capture_stat_attributes::flash_power_attribute = (1u << 7),
md_capture_stat_attributes::zoom_factor_attribute = (1u << 8),
md_capture_stat_attributes::scene_mode_attribute = (1u << 9),
md_capture_stat_attributes::sensor_framerate_attribute = (1u << 10)
} |
| md_capture_stat_attributes - bit mask to find enabled attributes in md_capture_stats More...
|
|
enum | md_capture_timing_attributes : uint32_t {
md_capture_timing_attributes::frame_counter_attribute = (1u << 0),
md_capture_timing_attributes::sensor_timestamp_attribute = (1u << 1),
md_capture_timing_attributes::readout_time_attribute = (1u << 2),
md_capture_timing_attributes::exposure_attribute = (1u << 3),
md_capture_timing_attributes::frame_interval_attribute = (1u << 4),
md_capture_timing_attributes::pipe_latency_attribute = (1u << 5)
} |
| md_capture_timing_attributes - enumerate the bit offset to check a specific attribute of md_capture_timing struct for validity. The enumeration includes up to 32 attributes, according to the size of flags parameter in all the defined structs More...
|
|
enum | md_configuration_attributes : uint32_t {
md_configuration_attributes::hw_type_attribute = (1u << 0),
md_configuration_attributes::sku_id_attribute = (1u << 1),
md_configuration_attributes::cookie_attribute = (1u << 2),
md_configuration_attributes::format_attribute = (1u << 3),
md_configuration_attributes::width_attribute = (1u << 4),
md_configuration_attributes::height_attribute = (1u << 5),
md_configuration_attributes::fps_attribute = (1u << 6),
md_configuration_attributes::trigger_attribute = (1u << 7),
md_configuration_attributes::calibration_count_attribute = (1u << 8),
md_configuration_attributes::gpio_input_data_attribute = (1u << 9),
md_configuration_attributes::sub_preset_info_attribute = (1u << 10)
} |
| md_configuration_attributes - bit mask to find active attributes, md_configuration struct More...
|
|
enum | md_depth_control_attributes : uint32_t {
md_depth_control_attributes::gain_attribute = (1u << 0),
md_depth_control_attributes::exposure_attribute = (1u << 1),
md_depth_control_attributes::laser_pwr_attribute = (1u << 2),
md_depth_control_attributes::ae_mode_attribute = (1u << 3),
md_depth_control_attributes::exposure_priority_attribute = (1u << 4),
md_depth_control_attributes::roi_attribute = (1u << 5),
md_depth_control_attributes::preset_attribute = (1u << 6),
md_depth_control_attributes::emitter_mode_attribute = (1u << 7),
md_depth_control_attributes::led_power_attribute = (1u << 8)
} |
| md_depth_control_attributes - bit mask to find active attributes, md_depth_control struct More...
|
|
enum | md_fisheye_control_attributes : uint32_t { md_fisheye_control_attributes::gain_attribute = (1u << 0),
md_fisheye_control_attributes::exposure_attribute = (1u << 1)
} |
| md_fisheye_control_attributes - bit mask to find active attributes, md_fisheye_control struct More...
|
|
enum | md_hid_custom_temp_attributes : uint8_t { md_hid_custom_temp_attributes::source_id_attirbute = (1u << 0),
md_hid_custom_temp_attributes::custom_timestamp_attirbute = (1u << 1),
md_hid_custom_temp_attributes::imu_counter_attribute = (1u << 2),
md_hid_custom_temp_attributes::usb_counter_attribute = (1u << 3)
} |
| md_hid_imu_attributes - bit mask to designate the enabled attributed, md_imu_report struct More...
|
|
enum | md_hid_imu_attributes : uint8_t { md_hid_imu_attributes::custom_timestamp_attirbute = (1u << 0),
md_hid_imu_attributes::imu_counter_attribute = (1u << 1),
md_hid_imu_attributes::usb_counter_attribute = (1u << 2)
} |
| md_hid_imu_attributes - bit mask to designate the enabled attributed, md_imu_report struct More...
|
|
enum | md_hid_report_type : uint8_t { hid_report_unknown,
hid_report_imu,
hid_report_custom_temperature,
hid_report_max
} |
| md_hid_imu_attributes - bit mask to designate the enabled attributed, md_imu_report struct More...
|
|
enum | md_l500_depth_control_attributes : uint32_t { md_l500_depth_control_attributes::laser_power = (1u << 0),
md_l500_depth_control_attributes::preset_id = (1u << 1),
md_l500_depth_control_attributes::laser_power_mode = (1u << 2)
} |
| md_depth_control_attributes - bit mask to find active attributes, md_depth_control struct More...
|
|
enum | md_rgb_control_attributes : uint32_t {
md_rgb_control_attributes::brightness_attribute = (1u << 0),
md_rgb_control_attributes::contrast_attribute = (1u << 1),
md_rgb_control_attributes::saturation_attribute = (1u << 2),
md_rgb_control_attributes::sharpness_attribute = (1u << 3),
md_rgb_control_attributes::ae_mode_attribute = (1u << 4),
md_rgb_control_attributes::awb_temp_attribute = (1u << 5),
md_rgb_control_attributes::gain_attribute = (1u << 6),
md_rgb_control_attributes::backlight_comp_attribute = (1u << 7),
md_rgb_control_attributes::gamma_attribute = (1u << 8),
md_rgb_control_attributes::hue_attribute = (1u << 9),
md_rgb_control_attributes::manual_exp_attribute = (1u << 10),
md_rgb_control_attributes::manual_wb_attribute = (1u << 11),
md_rgb_control_attributes::power_line_frequency_attribute = (1u << 12),
md_rgb_control_attributes::low_light_comp_attribute = (1u << 13)
} |
| md_rgb_control_attributes - bit mask to find active attributes, md_rgb_control struct More...
|
|
enum | md_stat_attributes : uint32_t {
md_stat_attributes::left_sum_attribute = (1u << 0),
md_stat_attributes::left_dark_count_attribute = (1u << 1),
md_stat_attributes::left_bright_count_attribute = (1u << 2),
md_stat_attributes::right_sum_attribute = (1u << 3),
md_stat_attributes::right_dark_count_attribute = (1u << 4),
md_stat_attributes::right_bright_count_attribute = (1u << 5),
md_stat_attributes::red_frame_count_attribute = (1u << 6),
md_stat_attributes::left_red_sum_attribute = (1u << 7),
md_stat_attributes::left_greeen1_attribute = (1u << 8),
md_stat_attributes::left_greeen2_attribute = (1u << 9),
md_stat_attributes::left_blue_sum_attribute = (1u << 10),
md_stat_attributes::right_red_sum_attribute = (1u << 11),
md_stat_attributes::right_greeen1_attribute = (1u << 12),
md_stat_attributes::right_greeen2_attribute = (1u << 13),
md_stat_attributes::right_blue_sum_attribute = (1u << 14)
} |
| md_stat_attributes - bit mask to find active attributes, md_stat struct More...
|
|
enum | md_type : uint32_t {
md_type::META_DATA_INTEL_DEPTH_CONTROL_ID = 0x80000000,
md_type::META_DATA_INTEL_CAPTURE_TIMING_ID = 0x80000001,
md_type::META_DATA_INTEL_CONFIGURATION_ID = 0x80000002,
md_type::META_DATA_INTEL_STAT_ID = 0x80000003,
md_type::META_DATA_INTEL_FISH_EYE_CONTROL_ID = 0x80000004,
md_type::META_DATA_INTEL_RGB_CONTROL_ID = 0x80000005,
md_type::META_DATA_INTEl_FE_FOV_MODEL_ID = 0x80000006,
md_type::META_DATA_INTEl_FE_CAMERA_EXTRINSICS_ID = 0x80000007,
md_type::META_DATA_CAPTURE_STATS_ID = 0x00000003,
md_type::META_DATA_CAMERA_EXTRINSICS_ID = 0x00000004,
md_type::META_DATA_CAMERA_INTRINSICS_ID = 0x00000005,
md_type::META_DATA_INTEL_L500_CAPTURE_TIMING_ID = 0x80000010,
md_type::META_DATA_INTEL_L500_DEPTH_CONTROL_ID = 0x80000012,
md_type::META_DATA_CAMERA_DEBUG_ID = 0x800000FF,
md_type::META_DATA_HID_IMU_REPORT_ID = 0x80001001,
md_type::META_DATA_HID_CUSTOM_TEMP_REPORT_ID = 0x80001002
} |
| md_mode - enumerates the types of metadata modes(structs) supported More...
|
|
enum | occlusion_rect_type : uint8_t { occlusion_min,
occlusion_none,
occlusion_monotonic_scan,
occlusion_max
} |
|
enum | occlusion_scanning_type : uint8_t { horizontal,
vertical
} |
|
enum | profile_tag { PROFILE_TAG_SUPERSET = 1,
PROFILE_TAG_DEFAULT = 2,
PROFILE_TAG_ANY = 4,
PROFILE_TAG_DEBUG = 8
} |
|
enum | rs2_dfu_command {
RS2_DFU_DETACH = 0,
RS2_DFU_DOWNLOAD = 1,
RS2_DFU_UPLOAD = 2,
RS2_DFU_GET_STATUS = 3,
RS2_DFU_CLEAR_STATUS = 4,
RS2_DFU_GET_STATE = 5,
RS2_DFU_ABORT = 6
} |
|
enum | rs2_dfu_state {
RS2_DFU_STATE_APP_IDLE = 0,
RS2_DFU_STATE_APP_DETACH = 1,
RS2_DFU_STATE_DFU_IDLE = 2,
RS2_DFU_STATE_DFU_DOWNLOAD_SYNC = 3,
RS2_DFU_STATE_DFU_DOWNLOAD_BUSY = 4,
RS2_DFU_STATE_DFU_DOWNLOAD_IDLE = 5,
RS2_DFU_STATE_DFU_MANIFEST_SYNC = 6,
RS2_DFU_STATE_DFU_MANIFEST = 7,
RS2_DFU_STATE_DFU_MANIFEST_WAIT_RESET = 8,
RS2_DFU_STATE_DFU_UPLOAD_IDLE = 9,
RS2_DFU_STATE_DFU_ERROR = 10
} |
|
enum | rs2_dfu_status {
RS2_DFU_STATUS_OK = 0x00,
RS2_DFU_STATUS_TARGET = 0x01,
RS2_DFU_STATUS_FILE = 0x02,
RS2_DFU_STATUS_WRITE = 0x03,
RS2_DFU_STATUS_ERASE = 0x04,
RS2_DFU_STATUS_CHECK_ERASED = 0x05,
RS2_DFU_STATUS_PROG = 0x06,
RS2_DFU_STATUS_VERIFY = 0x07,
RS2_DFU_STATUS_ADDRESS = 0x08,
RS2_DFU_STATUS_NOTDONE = 0x09,
RS2_DFU_STATUS_FIRMWARE = 0x0A,
RS2_DFU_STATUS_VENDOR = 0x0B,
RS2_DFU_STATUS_USBR = 0x0C,
RS2_DFU_STATUS_POR = 0x0D,
RS2_DFU_STATUS_UNKNOWN = 0x0E,
RS2_DFU_STATUS_STALLEDPKT = 0x0F
} |
|
enum | rs2_dsc_status : uint16_t {
RS2_DSC_STATUS_SUCCESS = 0,
RS2_DSC_STATUS_RESULT_NOT_READY = 1,
RS2_DSC_STATUS_FILL_FACTOR_TOO_LOW = 2,
RS2_DSC_STATUS_EDGE_TOO_CLOSE = 3,
RS2_DSC_STATUS_NOT_CONVERGE = 4,
RS2_DSC_STATUS_BURN_SUCCESS = 5,
RS2_DSC_STATUS_BURN_ERROR = 6,
RS2_DSC_STATUS_NO_DEPTH_AVERAGE = 7
} |
|
enum | scan_parameter { py_scan = 0,
rx_scan = 1
} |
|
enum | spatial_holes_filling_types : uint8_t {
sp_hf_disabled,
sp_hf_2_pixel_radius,
sp_hf_4_pixel_radius,
sp_hf_8_pixel_radius,
sp_hf_16_pixel_radius,
sp_hf_unlimited_radius,
sp_hf_max_value
} |
|
enum | subpixel_accuracy { very_high = 0,
high = 1,
medium = 2,
low = 3
} |
|
enum | temperature_type { TEMPERATURE_TYPE_ASIC,
TEMPERATURE_TYPE_MOTION
} |
|
enum | zero_order_invalidation_options {
RS2_OPTION_FILTER_ZO_IR_THRESHOLD = static_cast<rs2_option>(RS2_OPTION_COUNT + 0),
RS2_OPTION_FILTER_ZO_RTD_HIGH_THRESHOLD = static_cast<rs2_option>(RS2_OPTION_COUNT + 1),
RS2_OPTION_FILTER_ZO_RTD_LOW_THRESHOLD = static_cast<rs2_option>(RS2_OPTION_COUNT + 2),
RS2_OPTION_FILTER_ZO_BASELINE = static_cast<rs2_option>(RS2_OPTION_COUNT + 3),
RS2_OPTION_FILTER_ZO_PATCH_SIZE = static_cast<rs2_option>(RS2_OPTION_COUNT + 4),
RS2_OPTION_FILTER_ZO_MAX_VALUE = static_cast<rs2_option>(RS2_OPTION_COUNT + 5),
RS2_OPTION_FILTER_ZO_IR_MIN_VALUE = static_cast<rs2_option>(RS2_OPTION_COUNT + 6),
RS2_OPTION_FILTER_ZO_THRESHOLD_OFFSET = static_cast<rs2_option>(RS2_OPTION_COUNT + 7),
RS2_OPTION_FILTER_ZO_THRESHOLD_SCALE = static_cast<rs2_option>(RS2_OPTION_COUNT + 8)
} |
|
|
template<class GET_DEPTH , class TRANSFER_PIXEL > |
void | align_images (const rs2_intrinsics &depth_intrin, const rs2_extrinsics &depth_to_other, const rs2_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 rs2_intrinsics &depth_intrin, const rs2_extrinsics &depth_to_other, const rs2_intrinsics &other_intrin, const byte *other_pixels, rs2_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 rs2_intrinsics &depth_intrin, const rs2_extrinsics &depth_to_other, const rs2_intrinsics &other_intrin, const byte *other_pixels) |
|
template<typename T > |
constexpr size_t | arr_size (T const &) |
|
template<typename T , size_t sz> |
constexpr size_t | arr_size (T(&arr)[sz]) |
|
template<typename T , size_t sz> |
constexpr size_t | arr_size_bytes (T(&arr)[sz]) |
|
template<typename T > |
std::string | array2str (T &data) |
|
template<typename T , typename P > |
std::shared_ptr< T > | As (std::shared_ptr< P > ptr) |
|
template<typename T , typename P > |
T * | As (P *ptr) |
|
std::string | async_op_to_string (tm2_sensor::async_op_state val) |
|
uint32_t | calc_crc32 (const uint8_t *buf, size_t bufsize) |
| Calculate CRC code for arbitrary characters buffer. More...
|
|
float3x3 | calc_rotation_from_rodrigues_angles (const std::vector< double > rot) |
|
bool | check_not_all_zeros (std::vector< byte > data) |
|
template<typename T > |
T | clamp_val (T val, const T &min, const T &max) |
|
void | convert (rs2_format source, std::string &target) |
|
template<typename T > |
bool | convert (const std::string &source, T &target) |
|
template<> |
bool | convert (const std::string &source, rs2_format &target) |
|
template<> |
bool | convert (const std::string &source, double &target) |
|
template<> |
bool | convert (const std::string &source, long long &target) |
|
bool | convert (const geometry_msgs::Transform &source, rs2_extrinsics &target) |
|
bool | convert (const rs2_extrinsics &source, geometry_msgs::Transform &target) |
|
void | copy (void *dst, void const *src, size_t size) |
|
template<const bool force_narrowing = false, typename T , typename S , size_t tgt_m, size_t tgt_n, size_t src_m, size_t src_n> |
size_t | copy_2darray (T(&dst)[tgt_m][tgt_n], const S(&src)[src_m][src_n]) |
|
template<const bool force_narrowing = false, typename T , typename S , size_t size_tgt, size_t size_src> |
size_t | copy_array (T(&dst)[size_tgt], const S(&src)[size_src]) |
|
void | copy_frames (frame_holder from, frame_interface **&target) |
|
template<rs2_format FORMAT> |
void | copy_hid_axes (byte *const dest[], const byte *source, double factor) |
|
void | copy_raw10 (byte *const dest[], const byte *source, int width, int height, int actual_size) |
|
std::shared_ptr< librealsense::align > | create_align (rs2_stream align_to) |
|
template<class callback > |
calibration_change_callback_ptr | create_calibration_change_callback_ptr (callback &&cb) |
|
std::shared_ptr< matcher > | create_composite_matcher (std::vector< std::shared_ptr< matcher >> matchers) |
|
std::string | create_composite_name (const std::vector< std::shared_ptr< matcher >> &matchers, const std::string &name) |
|
static rs2_stream | custom_gpio_to_stream_type (uint32_t custom_gpio) |
|
void | d415_remove_ir (preset &p) |
|
void | d460_remove_ir (preset &p) |
|
std::string | datetime_string () |
|
void | default_400 (preset &p) |
|
void | default_405 (preset &p) |
|
void | default_410 (preset &p) |
|
void | default_420 (preset &p) |
|
void | default_430 (preset &p) |
|
rs2_intrinsics | denormalize (const rs2_intrinsics &intr, const uint32_t &width, const uint32_t &height) |
|
template<class MAP_DEPTH > |
void | deproject_depth (float *points, const rs2_intrinsics &intrin, const uint16_t *depth, MAP_DEPTH map_depth) |
|
template<class T > |
void | detect_zero_order (const double *rtd, const uint16_t *depth_data_in, const uint8_t *ir_data, T zero_pixel, const rs2_intrinsics &intrinsics, const zero_order_options &options, double zo_value, uint8_t iro_value) |
|
void | enable_rolling_log_file (unsigned max_size) |
|
std::pair< double, double > | extract_timestamps (frame_holder &a, frame_holder &b) |
|
bool | file_exists (const char *filename) |
|
std::vector< platform::uvc_device_info > | filter_by_mi (const std::vector< platform::uvc_device_info > &devices, uint32_t mi) |
|
std::vector< platform::uvc_device_info > | filter_by_product (const std::vector< platform::uvc_device_info > &devices, const std::set< uint16_t > &pid_list) |
|
std::vector< platform::usb_device_info > | filter_by_product (const std::vector< platform::usb_device_info > &devices, const std::set< uint16_t > &pid_list) |
|
std::vector< std::shared_ptr< device_info > > | filter_by_vid (std::vector< std::shared_ptr< device_info >> devices, int vid) |
|
stream_interface * | find_profile (rs2_stream stream, int index, std::vector< stream_interface * > profiles) |
|
std::string | frame_holder_to_string (const frame_holder &f) |
|
std::string | frame_to_string (const frame_interface &f) |
|
rs2_extrinsics | from_pose (pose a) |
|
rs2_extrinsics | from_raw_extrinsics (rs2_extrinsics extr) |
|
int | gcd (int a, int b) |
|
std::vector< uint8_t > | generate_json (const preset &in_preset) |
|
processing_blocks | get_color_recommended_proccesing_blocks () |
|
processing_blocks | get_depth_recommended_proccesing_blocks () |
|
constexpr uint32_t | get_device_index () |
|
processing_blocks | get_ds5_depth_recommended_proccesing_blocks () |
|
int | get_embeded_frames_size (frame_interface *f) |
|
constexpr uint32_t | get_file_version () |
|
std::string | get_formatted_fw_version (uint32_t fw_last_version) |
|
int | get_image_bpp (rs2_format format) |
|
size_t | get_image_size (int width, int height, rs2_format format) |
|
platform::uvc_device_info | get_mi (const std::vector< platform::uvc_device_info > &devices, uint32_t mi) |
|
constexpr uint32_t | get_minimum_supported_file_version () |
|
double | get_pixel_rtd (const rs2::vertex &v, int baseline) |
|
int | get_product_line (const platform::usb_device_info &usb_info) |
|
constexpr device_serializer::nanoseconds | get_static_file_info_timestamp () |
|
const char * | get_string (rs2_rs400_visual_preset value) |
|
const char * | get_string (rs2_gl_extension value) |
|
const char * | get_string (rs2_gl_matrix_type value) |
|
const char * | get_string (rs2_exception_type value) |
|
const char * | get_string (rs2_stream value) |
|
const char * | get_string (rs2_sr300_visual_preset value) |
|
const char * | get_string (rs2_sensor_mode value) |
|
const char * | get_string (rs2_calibration_type type) |
|
const char * | get_string (rs2_calibration_status value) |
|
const char * | get_string (rs2_ambient_light value) |
|
const char * | get_string (rs2_digital_gain value) |
|
const char * | get_string (rs2_cah_trigger value) |
|
const char * | get_string (rs2_host_perf_mode value) |
|
const char * | get_string (rs2_extension value) |
|
const char * | get_string (rs2_playback_status value) |
|
const char * | get_string (rs2_log_severity value) |
|
const char * | get_string (rs2_option value) |
|
const char * | get_string (rs2_format value) |
|
const char * | get_string (rs2_distortion value) |
|
const char * | get_string (rs2_camera_info value) |
|
const char * | get_string (rs2_frame_metadata_value value) |
|
const char * | get_string (rs2_timestamp_domain value) |
|
const char * | get_string (rs2_calib_target_type value) |
|
const char * | get_string (rs2_notification_category value) |
|
const char * | get_string (rs2_matchers value) |
|
const char * | get_string (rs2_l500_visual_preset value) |
|
std::tuple< uint8_t, uint8_t, uint8_t > | get_texcolor (const frame_holder &texture, float u, float v) |
|
template<typename T > |
T | get_zo_point_value (std::vector< T > &values) |
|
template<typename T > |
std::vector< T > | get_zo_point_values (const T *frame_data_in, const rs2_intrinsics &intrinsics, int zo_point_x, int zo_point_y, int patch_r) |
|
std::vector< std::pair< std::vector< platform::uvc_device_info >, std::vector< platform::hid_device_info > > > | group_devices_and_hids_by_unique_id (const std::vector< std::vector< platform::uvc_device_info >> &devices, const std::vector< platform::hid_device_info > &hids) |
|
std::vector< std::vector< platform::uvc_device_info > > | group_devices_by_unique_id (const std::vector< platform::uvc_device_info > &devices) |
|
void | hand_gesture (preset &p) |
|
template<class T > |
std::string | hexify (const T &val) |
|
void | high_res_high_accuracy (preset &p) |
|
void | high_res_high_density (preset &p) |
|
void | high_res_mid_density (preset &p) |
|
std::string | hwmon_error2str (hwmon_response e) |
|
std::string | hwmon_error_string (command const &cmd, hwmon_response e) |
|
rs2_extrinsics | identity_matrix () |
|
parsers_map | initialize_field_parsers (preset_param_group &p) |
|
template<class T , typename S > |
void | insert_control_to_map (parsers_map &map, bool was_set, const std::string &name, param_group< T > &control, S field) |
|
template<class T , typename S > |
void | insert_string_control_to_map (parsers_map &map, bool was_set, const std::string &name, param_group< T > &control, S field, const std::map< std::string, float > &values) |
|
pose | inverse (const pose &a) |
|
rs2_extrinsics | inverse (const rs2_extrinsics &a) |
|
template<typename T , typename P > |
bool | Is (std::shared_ptr< P > ptr) |
|
template<typename T , typename P > |
bool | Is (P *ptr) |
|
bool | is_l500_recovery (platform::rs_usb_device usb, bool &is_l500_device) |
|
bool | is_z_or_disparity (rs2_format format) |
|
resolution | l500_confidence_resolution (resolution res) |
|
template<class T > |
bool | list_changed (const std::vector< T > &list1, const std::vector< T > &list2, std::function< bool(T, T)> equal=[](T first, T second){return first==second;}) |
|
static void | log_FW_response_first_byte (hw_monitor &hwm, const std::string &command_name, const command &cmd, size_t expected_size) |
|
void | log_to_callback (rs2_log_severity min_severity, log_callback_ptr callback) |
|
void | log_to_console (rs2_log_severity min_severity) |
|
void | log_to_file (rs2_log_severity min_severity, const char *file_path) |
|
void | low_res_high_accuracy (preset &p) |
|
void | low_res_high_density (preset &p) |
|
void | low_res_mid_density (preset &p) |
|
template<class St , class Attribute > |
std::shared_ptr< md_attribute_parser_base > | make_additional_data_parser (Attribute St::*attribute) |
| A utility function to create additional_data parser. More...
|
|
std::shared_ptr< archive_interface > | make_archive (rs2_extension type, std::atomic< uint32_t > *in_max_frame_queue_size, std::shared_ptr< platform::time_service > ts, std::shared_ptr< metadata_parser_map > parsers) |
|
template<class S , class Attribute , typename Flag > |
std::shared_ptr< md_attribute_parser_base > | make_attribute_parser (Attribute S::*attribute, Flag flag, unsigned long long offset, attrib_modifyer mod=nullptr) |
| A helper function to create a specialized attribute parser. Return it as a pointer to a base-class. More...
|
|
template<class T > |
frame_callback_ptr | make_callback (T callback) |
|
template<class T , class S > |
std::shared_ptr< json_field > | make_field (T &strct, S T::group_type::*field, float scale=1.0f, bool is_duplicated_field=false) |
|
template<class T , class R , class W , class U > |
std::shared_ptr< struct_field_option< T, R, W, U > > | make_field_option (std::shared_ptr< struct_interface< T, R, W >> struct_interface, U T::*field, const option_range &range) |
|
template<class T > |
frame_callback_ptr | make_frame_callback (T callback) |
|
template<class St , class Attribute > |
std::shared_ptr< md_attribute_parser_base > | make_hid_header_parser (Attribute St::*attribute, attrib_modifyer mod=nullptr) |
| A utility function to create HID metadata header parser. More...
|
|
std::shared_ptr< json_field > | make_ignored_field () |
|
template<class T , class S > |
std::shared_ptr< json_field > | make_invert_field (T &strct, S T::group_type::*field, bool is_duplicated_field=false) |
|
std::string | make_less_screamy (const char *str) |
|
std::shared_ptr< md_attribute_parser_base > | make_rs400_sensor_ts_parser (std::shared_ptr< md_attribute_parser_base > frame_ts_parser, std::shared_ptr< md_attribute_parser_base > sensor_ts_parser) |
| A helper function to create a specialized parser for RS4xx sensor timestamp. More...
|
|
template<class S , class Attribute > |
std::shared_ptr< md_attribute_parser_base > | make_sr300_attribute_parser (Attribute S::*attribute, unsigned long long offset, attrib_modifyer mod=nullptr) |
| A helper function to create a specialized attribute parser. Return it as a pointer to a base-class. More...
|
|
template<class T , class S > |
std::shared_ptr< json_field > | make_string_field (T &strct, S T::group_type::*field, const std::map< std::string, float > &values, bool is_duplicated_field=false) |
|
template<class T , class R , class W > |
std::shared_ptr< struct_interface< T, R, W > > | make_struct_interface (R r, W w) |
|
template<class St , class Attribute > |
std::shared_ptr< md_attribute_parser_base > | make_uvc_header_parser (Attribute St::*attribute, attrib_modifyer mod=nullptr) |
| A utility function to create UVC metadata header parser. More...
|
|
| MAP_ADVANCED_MODE (STDepthControlGroup, etDepthControl) |
|
| MAP_ADVANCED_MODE (STRsm, etRsm) |
|
| MAP_ADVANCED_MODE (STRauSupportVectorControl, etRauSupportVectorControl) |
|
| MAP_ADVANCED_MODE (STColorControl, etColorControl) |
|
| MAP_ADVANCED_MODE (STRauColorThresholdsControl, etRauColorThresholdsControl) |
|
| MAP_ADVANCED_MODE (STSloColorThresholdsControl, etSloColorThresholdsControl) |
|
| MAP_ADVANCED_MODE (STSloPenaltyControl, etSloPenaltyControl) |
|
| MAP_ADVANCED_MODE (STHdad, etHdad) |
|
| MAP_ADVANCED_MODE (STColorCorrection, etColorCorrection) |
|
| MAP_ADVANCED_MODE (STDepthTableControl, etDepthTableControl) |
|
| MAP_ADVANCED_MODE (STAEControl, etAEControl) |
|
| MAP_ADVANCED_MODE (STCensusRadius, etCencusRadius9) |
|
| MAP_ADVANCED_MODE (STAFactor, etAFactor) |
|
| MAP_EXTENSION (RS2_EXTENSION_DEBUG_STREAM_SENSOR, debug_stream_sensor) |
|
| MAP_EXTENSION (RS2_EXTENSION_MAX_USABLE_RANGE_SENSOR, max_usable_range_sensor) |
|
| MAP_EXTENSION (RS2_EXTENSION_SERIALIZABLE, serializable_interface) |
|
| MAP_EXTENSION (RS2_EXTENSION_DEBUG, librealsense::debug_interface) |
|
| MAP_EXTENSION (RS2_EXTENSION_MOTION_PROFILE, librealsense::motion_stream_profile_interface) |
|
| MAP_EXTENSION (RS2_EXTENSION_CALIBRATION_CHANGE_DEVICE, calibration_change_device) |
|
| MAP_EXTENSION (RS2_EXTENSION_INFO, librealsense::info_interface) |
|
| MAP_EXTENSION (RS2_EXTENSION_DEPTH_HUFFMAN_DECODER, librealsense::depth_decompression_huffman) |
|
| MAP_EXTENSION (RS2_EXTENSION_AUTO_CALIBRATED_DEVICE, auto_calibrated_interface) |
|
| MAP_EXTENSION (RS2_EXTENSION_CALIBRATED_SENSOR, calibrated_sensor) |
|
| MAP_EXTENSION (RS2_EXTENSION_POSE_PROFILE, librealsense::pose_stream_profile_interface) |
|
| MAP_EXTENSION (RS2_EXTENSION_FW_LOGGER, librealsense::firmware_logger_extensions) |
|
| MAP_EXTENSION (RS2_EXTENSION_DEVICE_CALIBRATION, device_calibration) |
|
| MAP_EXTENSION (RS2_EXTENSION_SEQUENCE_ID_FILTER, librealsense::sequence_id_filter) |
|
| MAP_EXTENSION (RS2_EXTENSION_VIDEO, librealsense::video_sensor_interface) |
|
| MAP_EXTENSION (RS2_EXTENSION_UPDATE_DEVICE, update_device_interface) |
|
| MAP_EXTENSION (RS2_EXTENSION_THRESHOLD_FILTER, librealsense::threshold) |
|
| MAP_EXTENSION (RS2_EXTENSION_UPDATABLE, updatable) |
|
| MAP_EXTENSION (RS2_EXTENSION_VIDEO_PROFILE, librealsense::video_stream_profile_interface) |
|
| MAP_EXTENSION (RS2_EXTENSION_POSE_SENSOR, librealsense::pose_sensor_interface) |
|
| MAP_EXTENSION (RS2_EXTENSION_DECIMATION_FILTER, librealsense::decimation_filter) |
|
| MAP_EXTENSION (RS2_EXTENSION_WHEEL_ODOMETER, librealsense::wheel_odometry_interface) |
|
| MAP_EXTENSION (RS2_EXTENSION_OPTIONS, librealsense::options_interface) |
|
| MAP_EXTENSION (RS2_EXTENSION_L500_DEPTH_SENSOR, librealsense::l500_depth_sensor_interface) |
|
| MAP_EXTENSION (RS2_EXTENSION_HDR_MERGE, librealsense::hdr_merge) |
|
| MAP_EXTENSION (RS2_EXTENSION_ROI, librealsense::roi_sensor_interface) |
|
| MAP_EXTENSION (RS2_EXTENSION_TM2, librealsense::tm2_extensions) |
|
| MAP_EXTENSION (RS2_EXTENSION_DISPARITY_FILTER, librealsense::disparity_transform) |
|
| MAP_EXTENSION (RS2_EXTENSION_TM2_SENSOR, librealsense::tm2_sensor_interface) |
|
| MAP_EXTENSION (RS2_EXTENSION_ZERO_ORDER_FILTER, librealsense::zero_order) |
|
| MAP_EXTENSION (RS2_EXTENSION_RECORD, record_device) |
|
| MAP_EXTENSION (RS2_EXTENSION_PLAYBACK, playback_device) |
|
| MAP_EXTENSION (RS2_EXTENSION_ADVANCED_MODE, librealsense::ds5_advanced_mode_interface) |
|
| MAP_EXTENSION (RS2_EXTENSION_TEMPORAL_FILTER, librealsense::temporal_filter) |
|
| MAP_EXTENSION (RS2_EXTENSION_GLOBAL_TIMER, librealsense::global_time_interface) |
|
| MAP_EXTENSION (RS2_EXTENSION_MOTION_SENSOR, librealsense::motion_sensor) |
|
| MAP_EXTENSION (RS2_EXTENSION_SOFTWARE_SENSOR, software_sensor) |
|
| MAP_EXTENSION (RS2_EXTENSION_SOFTWARE_DEVICE, software_device) |
|
| MAP_EXTENSION (RS2_EXTENSION_FISHEYE_SENSOR, librealsense::fisheye_sensor) |
|
| MAP_EXTENSION (RS2_EXTENSION_HOLE_FILLING_FILTER, librealsense::hole_filling_filter) |
|
| MAP_EXTENSION (RS2_EXTENSION_RECOMMENDED_FILTERS, librealsense::recommended_proccesing_blocks_interface) |
|
| MAP_EXTENSION (RS2_EXTENSION_POINTS, librealsense::points) |
|
| MAP_EXTENSION (RS2_EXTENSION_COMPOSITE_FRAME, librealsense::composite_frame) |
|
| MAP_EXTENSION (RS2_EXTENSION_SPATIAL_FILTER, librealsense::spatial_filter) |
|
| MAP_EXTENSION (RS2_EXTENSION_VIDEO_FRAME, librealsense::video_frame) |
|
| MAP_EXTENSION (RS2_EXTENSION_COLOR_SENSOR, librealsense::color_sensor) |
|
| MAP_EXTENSION (RS2_EXTENSION_DEPTH_SENSOR, librealsense::depth_sensor) |
|
| MAP_EXTENSION (RS2_EXTENSION_DEPTH_STEREO_SENSOR, librealsense::depth_stereo_sensor) |
|
| MAP_EXTENSION (RS2_EXTENSION_DEPTH_FRAME, librealsense::depth_frame) |
|
| MAP_EXTENSION (RS2_EXTENSION_DISPARITY_FRAME, librealsense::disparity_frame) |
|
| MAP_EXTENSION (RS2_EXTENSION_MOTION_FRAME, librealsense::motion_frame) |
|
| MAP_EXTENSION (RS2_EXTENSION_POSE_FRAME, librealsense::pose_frame) |
|
int | maxDivisorRange (int a, int b, int lo, int hi) |
|
std::vector< uint8_t > | merge_images (flash_info from, flash_info to, const std::vector< uint8_t > image) |
|
bool | mi_present (const std::vector< platform::uvc_device_info > &devices, uint32_t mi) |
|
void | mid_res_high_accuracy (preset &p) |
|
void | mid_res_high_density (preset &p) |
|
void | mid_res_mid_density (preset &p) |
|
double | monotonic_to_realtime (double monotonic) |
|
rs2_intrinsics | normalize (const rs2_intrinsics &intr) |
|
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) |
|
float4 | operator+ (const float4 &a, const float4 &b) |
|
float3 | operator- (const float3 &a, const float3 &b) |
|
float4 | operator- (const float4 &a, const float4 &b) |
|
bool | operator< (const stream_profile &lhs, const stream_profile &rhs) |
|
std::ostream & | operator<< (std::ostream &os, const stream_profiles &profiles) |
|
std::ostream & | operator<< (std::ostream &out, const frame_interface &f) |
|
std::ostream & | operator<< (std::ostream &stream, const float3 &elem) |
|
std::ostream & | operator<< (std::ostream &stream, const float4 &elem) |
|
std::ostream & | operator<< (std::ostream &stream, const float3x3 &elem) |
|
std::ostream & | operator<< (std::ostream &stream, const pose &elem) |
|
bool | operator== (const hdr_params &first, const hdr_params &second) |
|
bool | operator== (const float3 &a, const float3 &b) |
|
bool | operator== (const float4 &a, const float4 &b) |
|
bool | operator== (const float3x3 &a, const float3x3 &b) |
|
bool | operator== (const pose &a, const pose &b) |
|
bool | operator== (const stream_profile &a, const stream_profile &b) |
|
bool | operator== (const rs2_intrinsics &a, const rs2_intrinsics &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 hid_device_info &a, const hid_device_info &b) |
|
md_hid_imu_attributes | operator| (md_hid_imu_attributes l, md_hid_imu_attributes r) |
|
md_hid_imu_attributes | operator|= (md_hid_imu_attributes l, md_hid_imu_attributes r) |
|
template<class pixelvalue > |
pixelvalue | opt_med3 (pixelvalue *p) |
|
template<class pixelvalue > |
pixelvalue | opt_med4 (pixelvalue *p) |
|
template<class pixelvalue > |
pixelvalue | opt_med5 (pixelvalue *p) |
|
template<class pixelvalue > |
pixelvalue | opt_med6 (pixelvalue *p) |
|
template<class pixelvalue > |
pixelvalue | opt_med7 (pixelvalue *p) |
|
template<class pixelvalue > |
pixelvalue | opt_med8 (pixelvalue *p) |
|
template<class pixelvalue > |
pixelvalue | opt_med9 (pixelvalue *p) |
|
uint32_t | pack (uint8_t c0, uint8_t c1, uint8_t c2, uint8_t c3) |
|
rs2_intrinsics | pad_crop_intrinsics (const rs2_intrinsics &i, int pad_crop) |
|
flash_section | parse_flash_section (const std::vector< uint8_t > &flash_buffer, flash_table toc, flash_structure s) |
|
std::vector< flash_payload_header > | parse_payloads (const std::vector< uint8_t > &flash_buffer, size_t number_of_payloads) |
|
flash_table | parse_table_of_contents (const std::vector< uint8_t > &flash_buffer, uint32_t toc_offset) |
|
std::vector< flash_table > | parse_tables (const std::vector< uint8_t > &flash_buffer, flash_table toc, flash_structure structure) |
|
float2 | pixel_to_texcoord (const rs2_intrinsics *intrin, const float2 &pixel) |
|
float2 | project (const rs2_intrinsics *intrin, const float3 &point) |
|
float2 | project_to_texcoord (const rs2_intrinsics *intrin, const float3 &point) |
|
void | quat2rot (const geometry_msgs::Transform::_rotation_type &q, float(&r)[9]) |
|
rs2_sensor_mode | query_sensor_mode (option &resolution) |
|
void | reset_logger () |
|
void | rot2quat (const float(&r)[9], geometry_msgs::Transform::_rotation_type &q) |
|
void | rotate_confidence (byte *const dest[], const byte *source, int width, int height, int actual_size) |
|
template<size_t SIZE> |
void | rotate_image (byte *const dest[], const byte *source, int width, int height, int actual_size) |
|
template<size_t SIZE> |
void | rotate_image_optimized (byte *const dest[], const byte *source, int width, int height, int actual_size) |
|
template<size_t SIZE> |
void | rotate_image_optimized (byte *dest[], const byte *source, int width, int height) |
|
resolution | rotate_resolution (resolution res) |
|
rs2_intrinsics | scale_intrinsics (const rs2_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<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) |
|
bool | stream_profiles_correspond (stream_profile_interface *l, stream_profile_interface *r) |
|
device_serializer::nanoseconds | to_nanoseconds (const rs2rosinternal::Time &t) |
|
pose | to_pose (const rs2_extrinsics &a) |
|
stream_profile | to_profile (const stream_profile_interface *sp) |
|
std::vector< stream_profile > | to_profiles (const std::vector< std::shared_ptr< stream_profile_interface >> &vec) |
|
rs2_extrinsics | to_raw_extrinsics (rs2_extrinsics extr) |
|
rs2rosinternal::Time | to_rostime (const device_serializer::nanoseconds &t) |
|
float3 | transform (const rs2_extrinsics *extrin, const float3 &point) |
|
static void | translate_exception (const char *name, std::string args, rs2_error **error) |
|
float3x3 | transpose (const float3x3 &a) |
|
void | trim_device_list (std::vector< platform::usb_device_info > &devices, const std::vector< platform::usb_device_info > &chosen) |
|
void | trim_device_list (std::vector< platform::uvc_device_info > &devices, const std::vector< platform::uvc_device_info > &chosen) |
|
template<typename To > |
bool | try_extend (std::shared_ptr< extension_snapshot > from, void **ext) |
|
void | try_fetch (std::map< std::string, int > jsn, std::string key, int *value) |
|
bool | try_get_zo_rtd_ir_point_values (const double *rtd, const uint16_t *depth_data_in, const uint8_t *ir_data, const rs2_intrinsics &intrinsics, const zero_order_options &options, int zo_point_x, int zo_point_y, double *rtd_zo_value, uint8_t *ir_zo_data) |
|
template<rs2_format FORMAT> |
void | unpack_accel_axes (byte *const dest[], const byte *source, int width, int height, int output_size) |
|
template<rs2_format FORMAT> |
void | unpack_gyro_axes (byte *const dest[], const byte *source, int width, int height, int output_size) |
|
void | unpack_invi (rs2_format dst_format, byte *const d[], const byte *s, int width, int height, int actual_size) |
|
void | unpack_inzi (rs2_format dst_ir_format, byte *const d[], const byte *s, int width, int height, int actual_size) |
|
void | unpack_mjpeg (byte *const dest[], const byte *source, int width, int height, int actual_size, int input_size) |
|
template<class SOURCE , class UNPACK > |
void | unpack_pixels (byte *const dest[], int count, const SOURCE *source, UNPACK unpack, int actual_size) |
|
void | unpack_rgb_from_bgr (byte *const dest[], const byte *source, int width, int height, int actual_size) |
|
template<rs2_format FORMAT> |
void | unpack_uyvy (byte *const d[], const byte *s, int width, int height, int actual_size) |
|
void | unpack_uyvyc (rs2_format dst_format, rs2_stream dst_stream, byte *const d[], const byte *s, int w, int h, int actual_size) |
|
void | unpack_w10 (rs2_format dst_format, byte *const d[], const byte *s, int width, int height, int actual_size) |
|
void | unpack_y10bpack (byte *const dest[], const byte *source, int width, int height, int actual_size) |
|
void | unpack_y16_from_y16_10 (byte *const d[], const byte *s, int width, int height, int actual_size) |
|
void | unpack_y16_y16_from_y12i_10 (byte *const dest[], const byte *source, int width, int height, int actual_size) |
|
void | unpack_y8_from_y16_10 (byte *const d[], const byte *s, int width, int height, int actual_size) |
|
void | unpack_y8_y8_from_y8i (byte *const dest[], const byte *source, int width, int height, int actual_size) |
|
template<rs2_format FORMAT> |
void | unpack_yuy2 (byte *const d[], const byte *s, int width, int height, int actual_size) |
|
void | unpack_yuy2 (rs2_format dst_format, rs2_stream dst_stream, byte *const d[], const byte *s, int w, int h, int actual_size) |
|
void | unpack_z16_y16_from_sr300_inzi (byte *const dest[], const byte *source, int width, int height, int actual_size) |
|
void | unpack_z16_y8_from_sr300_inzi (byte *const dest[], const byte *source, int width, int height, int actual_size) |
|
void | update_flash_internal (std::shared_ptr< hw_monitor > hwm, const std::vector< uint8_t > &image, std::vector< uint8_t > &flash_backup, update_progress_callback_ptr callback, int update_mode) |
|
void | update_flash_section (std::shared_ptr< hw_monitor > hwm, const std::vector< uint8_t > &image, uint32_t offset, uint32_t size, update_progress_callback_ptr callback, float continue_from, float ratio) |
|
template<typename T > |
void | update_preset_camera_control (T &camera_control, const param_group< T > ¶m) |
|
template<typename T > |
void | update_preset_control (T &preset_control, const param_group< T > ¶m) |
|
void | update_section (std::shared_ptr< hw_monitor > hwm, const std::vector< uint8_t > &merged_image, flash_section fs, uint32_t tables_size, update_progress_callback_ptr callback, float continue_from, float ratio) |
|
void | update_structs (const std::string &content, preset &in_preset) |
|
template<typename T > |
bool | val_in_range (const T &val, const std::initializer_list< T > &list) |
|
void | z2rtd (const rs2::vertex *vertices, double *rtd, const rs2_intrinsics &intrinsics, int baseline) |
|
template<class T > |
bool | zero_order_invalidation (const uint16_t *depth_data_in, const uint8_t *ir_data, T zero_pixel, const rs2::vertex *vertices, rs2_intrinsics intrinsics, const zero_order_options &options, int zo_point_x, int zo_point_y) |
|