Classes | Enumerations | Functions
rs Namespace Reference

Classes

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

Enumerations

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

Functions

void apply_depth_control_preset (device *device, int preset)
 
void apply_ivcam_preset (device *device, rs_ivcam_preset preset)
 
void apply_ivcam_preset (device *device, int preset)
 
void log_to_callback (log_severity min_severity, std::function< void(log_severity, const char *)> callback)
 
void log_to_console (log_severity min_severity)
 
void log_to_file (log_severity min_severity, const char *file_path)
 
std::ostream & operator<< (std::ostream &o, stream stream)
 
std::ostream & operator<< (std::ostream &o, format format)
 
std::ostream & operator<< (std::ostream &o, preset preset)
 
std::ostream & operator<< (std::ostream &o, distortion distortion)
 
std::ostream & operator<< (std::ostream &o, option option)
 
std::ostream & operator<< (std::ostream &o, capabilities capability)
 
std::ostream & operator<< (std::ostream &o, source src)
 
std::ostream & operator<< (std::ostream &o, event evt)
 

Enumeration Type Documentation

enum rs::blob_type
strong

Proprietary formats for direct communication with device firmware.

Enumerator
motion_module_firmware_update 

By using this option, new firmware can be uploaded to the ZR300 motion-module

Definition at line 183 of file rs.hpp.

enum rs::camera_info
strong

Read-only strings that can be queried from the device.

Not all information fields are available on all camera types. This information is mainly available for camera debug and troubleshooting and should not be used in applications.

Enumerator
device_name 

Device friendly name

serial_number 

Device serial number

camera_firmware_version 

Primary firmware version

adapter_board_firmware_version 

MIPI-to-USB adapter board firmware version if such board is present

motion_module_firmware_version 

Motion module firmware version if motion module is present

camera_type 

R200/LR200/ZR300 camera type

oem_id 

OEM ID

isp_fw_version 

ISP firmware version when available

content_version 

R200/LR200/ZR300 content version

module_version 

R200/LR200/ZR300 module version

imager_model_number 

Primary imager model number

build_date 

Device build date

calibration_date 

Primary calibration date

program_date 

R200/LR200/ZR300 program date

focus_alignment_date 

Focus calibration date

emitter_type 

R200/LR200/ZR300 emitter date

focus_value 

Result of the focus calibration

lens_type 

Primary lens type

third_lens_type 

Color imager lens type

lens_coating_type 

Lens coating type

third_lens_coating_type 

Color coating type

lens_nominal_baseline 

Nominal baseline

third_lens_nominal_baseline 

Color nominal baseline

Definition at line 192 of file rs.hpp.

enum rs::capabilities : int32_t
strong

Specifies various capabilities of a RealSense device.

To check if a certain capability is supported by a particular device, at runtime call dev->supports(capability).

Enumerator
depth 

Provides depth stream

color 

Provides color stream

infrared 

Provides infrared stream

infrared2 

Provides second infrared stream

fish_eye 

Provides wide field of view (fish-eye) stream

motion_events 

Provides gyroscope and accelorometer events

motion_module_fw_update 

Provides method for upgrading motion module firmware

adapter_board 

Internally includes MIPI-to-USB adapter

enumeration 

Provides enough basic functionality to be considered supported. This is to catch various outdated engineering samples at runtime.

Definition at line 169 of file rs.hpp.

enum rs::distortion : int32_t
strong

Distortion model: defines how pixel coordinates should be mapped to sensor coordinates.

Enumerator
none 

Rectilinear images. No distortion compensation required.

modified_brown_conrady 

Equivalent to Brown-Conrady distortion, except that tangential distortion is applied to radially distorted points

inverse_brown_conrady 

Equivalent to Brown-Conrady distortion, except undistorts image instead of distorting it

distortion_ftheta 

Distortion model of the fish-eye camera

Definition at line 76 of file rs.hpp.

enum rs::event : uint8_t
strong

Source device that triggered specific timestamp event from the motion module.

Enumerator
event_imu_accel 

Event from accelerometer

event_imu_gyro 

Event from the gyroscope

event_imu_depth_cam 

Event from depth camera (depth/IR frame)

event_imu_motion_cam 

Event from the fish-eye camera

event_imu_g0_sync 

Event from external GPIO 0

event_imu_g1_sync 

Event from external GPIO 1

event_imu_g2_sync 

Event from external GPIO 2

Definition at line 227 of file rs.hpp.

enum rs::format : int32_t
strong

Formats: defines how each stream can be encoded. rs_format specifies how a frame is represented in memory (similar to the V4L pixel format).

Enumerator
any 

When passed to enable stream, librealsense will try to provide best suited format

z16 

16 bit linear depth values. The depth is meters is equal to depth scale * pixel value.

disparity16 

16 bit linear disparity values. The depth in meters is equal to depth scale / pixel value.

xyz32f 

32 bit floating point 3D coordinates.

yuyv 

Standard YUV pixel format as described in https://en.wikipedia.org/wiki/YUV

rgb8 

8-bit red, green, and blue channels

bgr8 

8-bit blue, green, and red channels channels – suitable for OpenCV

rgba8 

8-bit red, green, and blue channels + constant alpha channel equal to FF

bgra8 

8-bit blue, green, and red channels + constant alpha channel equal to FF

y8 

8-bit per-pixel grayscale image

y16 

16-bit per-pixel grayscale image

raw10 

Four 10-bit luminance values encoded into a 5-byte macropixel

raw16 

16-bit raw image

raw8 

8-bit raw image

Definition at line 42 of file rs.hpp.

enum rs::frame_metadata
strong

Types of value provided from the device with each frame.

Enumerator
actual_exposure 

Actual exposure at which the frame was captured

actual_fps 

Actual FPS at the time of capture

Definition at line 160 of file rs.hpp.

enum rs::log_severity : int32_t
strong

Severity of the librealsense logger.

Enumerator
debug 

Detailed information about ordinary operations

info 

Terse information about ordinary operations

warn 

Indication of possible failure

error 

Indication of definite failure

fatal 

Indication of unrecoverable failure

none 

No logging will occur

Definition at line 1080 of file rs.hpp.

enum rs::option : int32_t
strong

Defines general configuration controls.

These can generally be mapped to camera UVC controls, and unless stated otherwise, can be set/queried at any time.

Enumerator
color_backlight_compensation 

Enable/disable color backlight compensation

color_brightness 

Color image brightness

color_contrast 

Color image contrast

color_exposure 

Controls exposure time of color camera. Setting any value will disable auto exposure.

color_gain 

Color image gain

color_gamma 

Color image gamma setting

color_hue 

Color image hue

color_saturation 

Color image saturation setting

color_sharpness 

Color image sharpness setting

color_white_balance 

Controls white balance of color image. Setting any value will disable auto white balance.

color_enable_auto_exposure 

Enable/disable color image auto-exposure

color_enable_auto_white_balance 

Enable/disable color image auto-white-balance

f200_laser_power 

Power of the F200/SR300 projector, with 0 meaning projector off

f200_accuracy 

Set the number of patterns projected per frame. The higher the accuracy value, the more patterns projected. Increasing the number of patterns helps to achieve better accuracy. Note that this control affects the depth FPS.

f200_motion_range 

Motion vs. range trade-off, with lower values allowing for better motion sensitivity and higher values allowing for better depth range

f200_filter_option 

Set the filter to apply to each depth frame. Each one of the filters is optimized per the application requirements.

f200_confidence_threshold 

Confidence level threshold used by the depth algorithm pipe to set whether a pixel will get a valid range or will be marked with invalid range

f200_dynamic_fps 

(F200-only) Allows to reduce FPS without restarting streaming. Valid values are {2, 5, 15, 30, 60}.

sr300_auto_range_enable_motion_versus_range 

Configures SR300 depth auto-range setting. Should not be used directly but through the rs_apply_ivcam_preset method in rsutil.h.

sr300_auto_range_enable_laser 

Configures SR300 depth auto-range setting. Should not be used directly but through the rs_apply_ivcam_preset method in rsutil.h.

sr300_auto_range_min_motion_versus_range 

Configures SR300 depth auto-range setting. Should not be used directly but through the rs_apply_ivcam_preset method in rsutil.h.

sr300_auto_range_max_motion_versus_range 

Configures SR300 depth auto-range setting. Should not be used directly but through the rs_apply_ivcam_preset method in rsutil.h.

sr300_auto_range_start_motion_versus_range 

Configures SR300 depth auto-range setting. Should not be used directly but through the rs_apply_ivcam_preset method in rsutil.h.

sr300_auto_range_min_laser 

Configures SR300 depth auto-range setting. Should not be used directly but through the rs_apply_ivcam_preset method in rsutil.h.

sr300_auto_range_max_laser 

Configures SR300 depth auto-range setting. Should not be used directly but through the rs_apply_ivcam_preset method in rsutil.h.

sr300_auto_range_start_laser 

Configures SR300 depth auto-range setting. Should not be used directly but through the rs_apply_ivcam_preset method in rsutil.h.

sr300_auto_range_upper_threshold 

Configures SR300 depth auto-range setting. Should not be used directly but through the rs_apply_ivcam_preset method in rsutil.h.

sr300_auto_range_lower_threshold 

Configures SR300 depth auto-range setting. Should not be used directly but through the rs_apply_ivcam_preset method in rsutil.h.

r200_lr_auto_exposure_enabled 

Enable/disable R200 auto-exposure. This will affect both IR and depth images.

r200_lr_gain 

IR image gain

r200_lr_exposure 

This control allows manual adjustment of the exposure time value for the L/R imagers.

r200_emitter_enabled 

Enables/disables R200 emitter

r200_depth_units 

Micrometers per increment in integer depth values. 1000 is default (mm scale). Set before streaming.

r200_depth_clamp_min 

Minimum depth in current depth units that will be output. Any values less than "Min Depth" will be mapped to 0 during the conversion between disparity and depth. Set before streaming.

r200_depth_clamp_max 

Minimum depth in current depth units that will be output. Any values less than "Max Depth" will be mapped to 0 during the conversion between disparity and depth. Set before streaming.

r200_disparity_multiplier 

Disparity scale factor used when in disparity output mode. Can only be set before streaming.

r200_disparity_shift 

{0 - 512}. Can only be set before streaming starts.

r200_auto_exposure_mean_intensity_set_point 

Mean intensity set point. Requires the r200_lr_auto_exposure_enabled option to be set to 1.

r200_auto_exposure_bright_ratio_set_point 

Bright ratio set point. Requires the r200_lr_auto_exposure_enabled option to be set to 1.

r200_auto_exposure_kp_gain 

Kp gain. Requires the r200_lr_auto_exposure_enabled option to be set to 1.

r200_auto_exposure_kp_exposure 

Kp exposure. Requires the r200_lr_auto_exposure_enabled option to be set to 1.

r200_auto_exposure_kp_dark_threshold 

Kp dark threshold. Requires the r200_lr_auto_exposure_enabled option to be set to 1.

r200_auto_exposure_top_edge 

Auto-exposure region-of-interest top edge (in pixels). Requires the r200_lr_auto_exposure_enabled option to be set to 1.

r200_auto_exposure_bottom_edge 

Auto-exposure region-of-interest bottom edge (in pixels). Requires the r200_lr_auto_exposure_enabled option to be set to 1.

r200_auto_exposure_left_edge 

Auto-exposure region-of-interest left edge (in pixels). Requires the r200_lr_auto_exposure_enabled option to be set to 1.

r200_auto_exposure_right_edge 

Auto-exposure region-of-interest right edge (in pixels). Requires the r200_lr_auto_exposure_enabled option to be set to 1.

r200_depth_control_estimate_median_decrement 

Value to subtract when estimating the median of the correlation surface

r200_depth_control_estimate_median_increment 

Value to add when estimating the median of the correlation surface

r200_depth_control_median_threshold 

Threshold: by how much the winning score exceeds the median.

r200_depth_control_score_minimum_threshold 

Minimum correlation score that is considered acceptable

r200_depth_control_score_maximum_threshold 

Maximum correlation score that is considered acceptable

r200_depth_control_texture_count_threshold 

Parameter for determining whether the texture in the region is sufficient to justify a depth result

r200_depth_control_texture_difference_threshold 

Parameter for determining whether the texture in the region is sufficient to justify a depth result

r200_depth_control_second_peak_threshold 

Threshold: how much the minimum correlation score must differ from the next best score.

r200_depth_control_neighbor_threshold 

Neighbor threshold value for depth calculation

r200_depth_control_lr_threshold 

Left-right threshold value for depth calculation

fisheye_exposure 

Fisheye image exposure time in msec

fisheye_gain 

Fisheye image gain

fisheye_strobe 

Enable/disable fisheye strobe. When enabled, aligns timestamps to common clock-domain with the motion events.

fisheye_external_trigger 

Enable/disable fisheye external trigger mode. When enabled, fisheye image will be aquired in-sync with the depth image.

fisheye_color_auto_exposure 

Enable / disable fisheye auto-exposure

fisheye_color_auto_exposure_mode 

0 - static auto-exposure, 1 - anti-flicker auto-exposure, 2 - hybrid

fisheye_color_auto_exposure_rate 

Fisheye auto-exposure anti-flicker rate. Can be 50 or 60 Hz.

fisheye_color_auto_exposure_sample_rate 

In fisheye auto-exposure sample frame, every given number of pixels

fisheye_color_auto_exposure_skip_frames 

In fisheye auto-exposure sample, every given number of frames.

frames_queue_size 

Number of frames the user is allowed to keep per stream. Trying to hold on to more frames will cause frame-drops.

hardware_logger_enabled 

Enable/disable fetching log data from the device

total_frame_drops 

Total number of detected frame drops from all streams

Definition at line 87 of file rs.hpp.

enum rs::output_buffer_format : int32_t
strong

Output buffer format: sets how librealsense works with frame memory.

Enumerator
continous 

Makes sure that the output frame is exposed as a single continuous buffer

native 

Does not convert buffer to continuous. The user has to handle pitch manually.

Definition at line 61 of file rs.hpp.

enum rs::preset : int32_t
strong

Presets: general preferences that are translated by librealsense into concrete resolution and FPS.

Enumerator
best_quality 

Prefer best overall quality

largest_image 

Prefer largest image size

highest_framerate 

Prefer highest frame rate

Definition at line 68 of file rs.hpp.

enum rs::source : uint8_t
strong

Allows the user to choose between available hardware subdevices.

Enumerator
video 

Video streaming of depth, infrared, color, or fish-eye

motion_data 

Motion tracking from gyroscope and accelerometer

all_sources 

Enable everything together

Definition at line 219 of file rs.hpp.

enum rs::stream : int32_t
strong

Streams are different types of data provided by RealSense devices.

Enumerator
depth 

Native stream of depth data produced by RealSense device

color 

Native stream of color data captured by RealSense device

infrared 

Native stream of infrared data captured by RealSense device

infrared2 

Native stream of infrared data captured from a second viewpoint by RealSense device

fisheye 

Native stream of fish-eye (wide) data captured from the dedicate motion camera

points 

Synthetic stream containing point cloud data generated by deprojecting the depth image

rectified_color 

Synthetic stream containing undistorted color data with no extrinsic rotation from the depth stream

color_aligned_to_depth 

Synthetic stream containing color data but sharing intrinsic of depth stream

infrared2_aligned_to_depth 

Synthetic stream containing second viewpoint infrared data but sharing intrinsic of depth stream

depth_aligned_to_color 

Synthetic stream containing depth data but sharing intrinsic of color stream

depth_aligned_to_rectified_color 

Synthetic stream containing depth data but sharing intrinsic of rectified color stream

depth_aligned_to_infrared2 

Synthetic stream containing depth data but sharing intrinsic of second viewpoint infrared stream

Definition at line 24 of file rs.hpp.

enum rs::timestamp_domain
strong

Specifies the clock in relation to which the frame timestamp was measured.

When working with a motion microcontroller, motion data timestamps are always in the microcontroller timestamp domain. Some frames, however, might not succesfully receive microcontroller timestamp and will be marked as camera domain.

Enumerator
camera 

Frame timestamp was measured in relation to the camera clock

microcontroller 

Frame timestamp was measured in relation to the microcontroller clock

Definition at line 242 of file rs.hpp.

Function Documentation

void rs::apply_depth_control_preset ( device device,
int  preset 
)
inline

Definition at line 1126 of file rs.hpp.

void rs::apply_ivcam_preset ( device device,
rs_ivcam_preset  preset 
)
inline

Definition at line 1127 of file rs.hpp.

void rs::apply_ivcam_preset ( device device,
int  preset 
)
inline

Definition at line 1128 of file rs.hpp.

void rs::log_to_callback ( log_severity  min_severity,
std::function< void(log_severity, const char *)>  callback 
)
inline

Definition at line 1118 of file rs.hpp.

void rs::log_to_console ( log_severity  min_severity)
inline

Definition at line 1104 of file rs.hpp.

void rs::log_to_file ( log_severity  min_severity,
const char *  file_path 
)
inline

Definition at line 1111 of file rs.hpp.

std::ostream& rs::operator<< ( std::ostream &  o,
stream  stream 
)
inline

Definition at line 1070 of file rs.hpp.

std::ostream& rs::operator<< ( std::ostream &  o,
format  format 
)
inline

Definition at line 1071 of file rs.hpp.

std::ostream& rs::operator<< ( std::ostream &  o,
preset  preset 
)
inline

Definition at line 1072 of file rs.hpp.

std::ostream& rs::operator<< ( std::ostream &  o,
distortion  distortion 
)
inline

Definition at line 1073 of file rs.hpp.

std::ostream& rs::operator<< ( std::ostream &  o,
option  option 
)
inline

Definition at line 1074 of file rs.hpp.

std::ostream& rs::operator<< ( std::ostream &  o,
capabilities  capability 
)
inline

Definition at line 1075 of file rs.hpp.

std::ostream& rs::operator<< ( std::ostream &  o,
source  src 
)
inline

Definition at line 1076 of file rs.hpp.

std::ostream& rs::operator<< ( std::ostream &  o,
event  evt 
)
inline

Definition at line 1077 of file rs.hpp.



librealsense
Author(s): Sergey Dorodnicov , Mark Horn , Reagan Lopez
autogenerated on Fri Mar 13 2020 03:16:19