|
enum | rs::blob_type { rs::blob_type::motion_module_firmware_update
} |
| Proprietary formats for direct communication with device firmware. More...
|
|
enum | rs::camera_info {
rs::camera_info::device_name,
rs::camera_info::serial_number,
rs::camera_info::camera_firmware_version,
rs::camera_info::adapter_board_firmware_version,
rs::camera_info::motion_module_firmware_version,
rs::camera_info::camera_type,
rs::camera_info::oem_id,
rs::camera_info::isp_fw_version,
rs::camera_info::content_version,
rs::camera_info::module_version,
rs::camera_info::imager_model_number,
rs::camera_info::build_date,
rs::camera_info::calibration_date,
rs::camera_info::program_date,
rs::camera_info::focus_alignment_date,
rs::camera_info::emitter_type,
rs::camera_info::focus_value,
rs::camera_info::lens_type,
rs::camera_info::third_lens_type,
rs::camera_info::lens_coating_type,
rs::camera_info::third_lens_coating_type,
rs::camera_info::lens_nominal_baseline,
rs::camera_info::third_lens_nominal_baseline
} |
| Read-only strings that can be queried from the device. More...
|
|
enum | rs::capabilities : int32_t {
rs::capabilities::depth,
rs::capabilities::color,
rs::capabilities::infrared,
rs::capabilities::infrared2,
rs::capabilities::fish_eye,
rs::capabilities::motion_events,
rs::capabilities::motion_module_fw_update,
rs::capabilities::adapter_board,
rs::capabilities::enumeration
} |
| Specifies various capabilities of a RealSense device. More...
|
|
enum | rs::distortion : int32_t { rs::distortion::none,
rs::distortion::modified_brown_conrady,
rs::distortion::inverse_brown_conrady,
rs::distortion::distortion_ftheta
} |
| Distortion model: defines how pixel coordinates should be mapped to sensor coordinates. More...
|
|
enum | rs::event : uint8_t {
rs::event::event_imu_accel,
rs::event::event_imu_gyro,
rs::event::event_imu_depth_cam,
rs::event::event_imu_motion_cam,
rs::event::event_imu_g0_sync,
rs::event::event_imu_g1_sync,
rs::event::event_imu_g2_sync
} |
| Source device that triggered specific timestamp event from the motion module. More...
|
|
enum | rs::format : int32_t {
rs::format::any,
rs::format::z16,
rs::format::disparity16,
rs::format::xyz32f,
rs::format::yuyv,
rs::format::rgb8,
rs::format::bgr8,
rs::format::rgba8,
rs::format::bgra8,
rs::format::y8,
rs::format::y16,
rs::format::raw10,
rs::format::raw16,
rs::format::raw8
} |
| Formats: defines how each stream can be encoded. rs_format specifies how a frame is represented in memory (similar to the V4L pixel format). More...
|
|
enum | rs::frame_metadata { rs::frame_metadata::actual_exposure,
rs::frame_metadata::actual_fps
} |
| Types of value provided from the device with each frame. More...
|
|
enum | rs::log_severity : int32_t {
rs::log_severity::debug = 0,
rs::log_severity::info = 1,
rs::log_severity::warn = 2,
rs::log_severity::error = 3,
rs::log_severity::fatal = 4,
rs::log_severity::none = 5
} |
| Severity of the librealsense logger. More...
|
|
enum | rs::option : int32_t {
rs::option::color_backlight_compensation,
rs::option::color_brightness,
rs::option::color_contrast,
rs::option::color_exposure,
rs::option::color_gain,
rs::option::color_gamma,
rs::option::color_hue,
rs::option::color_saturation,
rs::option::color_sharpness,
rs::option::color_white_balance,
rs::option::color_enable_auto_exposure,
rs::option::color_enable_auto_white_balance,
rs::option::f200_laser_power,
rs::option::f200_accuracy,
rs::option::f200_motion_range,
rs::option::f200_filter_option,
rs::option::f200_confidence_threshold,
rs::option::f200_dynamic_fps,
rs::option::sr300_auto_range_enable_motion_versus_range,
rs::option::sr300_auto_range_enable_laser,
rs::option::sr300_auto_range_min_motion_versus_range,
rs::option::sr300_auto_range_max_motion_versus_range,
rs::option::sr300_auto_range_start_motion_versus_range,
rs::option::sr300_auto_range_min_laser,
rs::option::sr300_auto_range_max_laser,
rs::option::sr300_auto_range_start_laser,
rs::option::sr300_auto_range_upper_threshold,
rs::option::sr300_auto_range_lower_threshold,
rs::option::r200_lr_auto_exposure_enabled,
rs::option::r200_lr_gain,
rs::option::r200_lr_exposure,
rs::option::r200_emitter_enabled,
rs::option::r200_depth_units,
rs::option::r200_depth_clamp_min,
rs::option::r200_depth_clamp_max,
rs::option::r200_disparity_multiplier,
rs::option::r200_disparity_shift,
rs::option::r200_auto_exposure_mean_intensity_set_point,
rs::option::r200_auto_exposure_bright_ratio_set_point,
rs::option::r200_auto_exposure_kp_gain,
rs::option::r200_auto_exposure_kp_exposure,
rs::option::r200_auto_exposure_kp_dark_threshold,
rs::option::r200_auto_exposure_top_edge,
rs::option::r200_auto_exposure_bottom_edge,
rs::option::r200_auto_exposure_left_edge,
rs::option::r200_auto_exposure_right_edge,
rs::option::r200_depth_control_estimate_median_decrement,
rs::option::r200_depth_control_estimate_median_increment,
rs::option::r200_depth_control_median_threshold,
rs::option::r200_depth_control_score_minimum_threshold,
rs::option::r200_depth_control_score_maximum_threshold,
rs::option::r200_depth_control_texture_count_threshold,
rs::option::r200_depth_control_texture_difference_threshold,
rs::option::r200_depth_control_second_peak_threshold,
rs::option::r200_depth_control_neighbor_threshold,
rs::option::r200_depth_control_lr_threshold,
rs::option::fisheye_exposure,
rs::option::fisheye_gain,
rs::option::fisheye_strobe,
rs::option::fisheye_external_trigger,
rs::option::fisheye_color_auto_exposure,
rs::option::fisheye_color_auto_exposure_mode,
rs::option::fisheye_color_auto_exposure_rate,
rs::option::fisheye_color_auto_exposure_sample_rate,
rs::option::fisheye_color_auto_exposure_skip_frames,
rs::option::frames_queue_size,
rs::option::hardware_logger_enabled,
rs::option::total_frame_drops
} |
| Defines general configuration controls. More...
|
|
enum | rs::output_buffer_format : int32_t { rs::output_buffer_format::continous,
rs::output_buffer_format::native
} |
| Output buffer format: sets how librealsense works with frame memory. More...
|
|
enum | rs::preset : int32_t { rs::preset::best_quality,
rs::preset::largest_image,
rs::preset::highest_framerate
} |
| Presets: general preferences that are translated by librealsense into concrete resolution and FPS. More...
|
|
enum | rs::source : uint8_t { rs::source::video,
rs::source::motion_data,
rs::source::all_sources
} |
| Allows the user to choose between available hardware subdevices. More...
|
|
enum | rs::stream : int32_t {
rs::stream::depth,
rs::stream::color,
rs::stream::infrared,
rs::stream::infrared2,
rs::stream::fisheye,
rs::stream::points,
rs::stream::rectified_color,
rs::stream::color_aligned_to_depth,
rs::stream::infrared2_aligned_to_depth,
rs::stream::depth_aligned_to_color,
rs::stream::depth_aligned_to_rectified_color,
rs::stream::depth_aligned_to_infrared2
} |
| Streams are different types of data provided by RealSense devices. More...
|
|
enum | rs::timestamp_domain { rs::timestamp_domain::camera,
rs::timestamp_domain::microcontroller
} |
| Specifies the clock in relation to which the frame timestamp was measured. More...
|
|
|
void | rs::apply_depth_control_preset (device *device, int preset) |
|
void | rs::apply_ivcam_preset (device *device, rs_ivcam_preset preset) |
|
void | rs::apply_ivcam_preset (device *device, int preset) |
|
void | rs::log_to_callback (log_severity min_severity, std::function< void(log_severity, const char *)> callback) |
|
void | rs::log_to_console (log_severity min_severity) |
|
void | rs::log_to_file (log_severity min_severity, const char *file_path) |
|
std::ostream & | rs::operator<< (std::ostream &o, stream stream) |
|
std::ostream & | rs::operator<< (std::ostream &o, format format) |
|
std::ostream & | rs::operator<< (std::ostream &o, preset preset) |
|
std::ostream & | rs::operator<< (std::ostream &o, distortion distortion) |
|
std::ostream & | rs::operator<< (std::ostream &o, option option) |
|
std::ostream & | rs::operator<< (std::ostream &o, capabilities capability) |
|
std::ostream & | rs::operator<< (std::ostream &o, source src) |
|
std::ostream & | rs::operator<< (std::ostream &o, event evt) |
|
Exposes librealsense functionality for C++ compilers.
Definition in file rs.hpp.