Classes | Namespaces | Enumerations | Functions
rs.hpp File Reference

Exposes librealsense functionality for C++ compilers. More...

#include "rsutil.h"
#include "rscore.hpp"
#include <cmath>
#include <cstdint>
#include <cstring>
#include <sstream>
#include <stdexcept>
#include <functional>
#include <vector>
Include dependency graph for rs.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  rs::context
 Context. More...
class  rs::device
 Provides convenience methods relating to devices. More...
class  rs::error
struct  rs::extrinsics
 Cross-stream extrinsics: encode the topology describing how the different devices are connected. More...
struct  rs::float2
struct  rs::float3
class  rs::frame
 Frame. More...
class  rs::frame_callback
struct  rs::intrinsics
 Video stream intrinsics. More...
class  rs::log_callback
class  rs::motion_callback
struct  rs::motion_data
 Motion data from gyroscope and accelerometer from the microcontroller. More...
struct  rs::motion_intrinsics
 Motion device intrinsics: scale, bias, and variances. More...
class  rs::timestamp_callback
struct  rs::timestamp_data
 Timestamp data from the motion microcontroller. More...

Namespaces

namespace  rs

Enumerations

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

Functions

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)

Detailed Description

Exposes librealsense functionality for C++ compilers.

Definition in file rs.hpp.



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