00001
00002
00003
00007
00008 #ifndef LIBREALSENSE_RS_HPP
00009 #define LIBREALSENSE_RS_HPP
00010
00011 #include "rsutil.h"
00012 #include "rscore.hpp"
00013 #include <cmath>
00014 #include <cstdint>
00015 #include <cstring>
00016 #include <sstream>
00017 #include <stdexcept>
00018 #include <functional>
00019 #include <vector>
00020
00021 namespace rs
00022 {
00024 enum class stream : int32_t
00025 {
00026 depth ,
00027 color ,
00028 infrared ,
00029 infrared2 ,
00030 fisheye ,
00031 points ,
00032 rectified_color ,
00033 color_aligned_to_depth ,
00034 infrared2_aligned_to_depth ,
00035 depth_aligned_to_color ,
00036 depth_aligned_to_rectified_color,
00037 depth_aligned_to_infrared2
00038 };
00039
00042 enum class format : int32_t
00043 {
00044 any ,
00045 z16 ,
00046 disparity16 ,
00047 xyz32f ,
00048 yuyv ,
00049 rgb8 ,
00050 bgr8 ,
00051 rgba8 ,
00052 bgra8 ,
00053 y8 ,
00054 y16 ,
00055 raw10 ,
00056 raw16 ,
00057 raw8
00058 };
00059
00061 enum class output_buffer_format : int32_t
00062 {
00063 continous ,
00064 native
00065 };
00066
00068 enum class preset : int32_t
00069 {
00070 best_quality ,
00071 largest_image ,
00072 highest_framerate
00073 };
00074
00076 enum class distortion : int32_t
00077 {
00078 none ,
00079 modified_brown_conrady,
00080 inverse_brown_conrady,
00081 distortion_ftheta
00082 };
00083
00087 enum class option : int32_t
00088 {
00089 color_backlight_compensation ,
00090 color_brightness ,
00091 color_contrast ,
00092 color_exposure ,
00093 color_gain ,
00094 color_gamma ,
00095 color_hue ,
00096 color_saturation ,
00097 color_sharpness ,
00098 color_white_balance ,
00099 color_enable_auto_exposure ,
00100 color_enable_auto_white_balance ,
00101 f200_laser_power ,
00102 f200_accuracy ,
00103 f200_motion_range ,
00104 f200_filter_option ,
00105 f200_confidence_threshold ,
00106 f200_dynamic_fps ,
00107 sr300_auto_range_enable_motion_versus_range ,
00108 sr300_auto_range_enable_laser ,
00109 sr300_auto_range_min_motion_versus_range ,
00110 sr300_auto_range_max_motion_versus_range ,
00111 sr300_auto_range_start_motion_versus_range ,
00112 sr300_auto_range_min_laser ,
00113 sr300_auto_range_max_laser ,
00114 sr300_auto_range_start_laser ,
00115 sr300_auto_range_upper_threshold ,
00116 sr300_auto_range_lower_threshold ,
00117 r200_lr_auto_exposure_enabled ,
00118 r200_lr_gain ,
00119 r200_lr_exposure ,
00120 r200_emitter_enabled ,
00121 r200_depth_units ,
00122 r200_depth_clamp_min ,
00123 r200_depth_clamp_max ,
00124 r200_disparity_multiplier ,
00125 r200_disparity_shift ,
00126 r200_auto_exposure_mean_intensity_set_point ,
00127 r200_auto_exposure_bright_ratio_set_point ,
00128 r200_auto_exposure_kp_gain ,
00129 r200_auto_exposure_kp_exposure ,
00130 r200_auto_exposure_kp_dark_threshold ,
00131 r200_auto_exposure_top_edge ,
00132 r200_auto_exposure_bottom_edge ,
00133 r200_auto_exposure_left_edge ,
00134 r200_auto_exposure_right_edge ,
00135 r200_depth_control_estimate_median_decrement ,
00136 r200_depth_control_estimate_median_increment ,
00137 r200_depth_control_median_threshold ,
00138 r200_depth_control_score_minimum_threshold ,
00139 r200_depth_control_score_maximum_threshold ,
00140 r200_depth_control_texture_count_threshold ,
00141 r200_depth_control_texture_difference_threshold ,
00142 r200_depth_control_second_peak_threshold ,
00143 r200_depth_control_neighbor_threshold ,
00144 r200_depth_control_lr_threshold ,
00145 fisheye_exposure ,
00146 fisheye_gain ,
00147 fisheye_strobe ,
00148 fisheye_external_trigger ,
00149 fisheye_color_auto_exposure ,
00150 fisheye_color_auto_exposure_mode ,
00151 fisheye_color_auto_exposure_rate ,
00152 fisheye_color_auto_exposure_sample_rate ,
00153 fisheye_color_auto_exposure_skip_frames ,
00154 frames_queue_size ,
00155 hardware_logger_enabled ,
00156 total_frame_drops ,
00157 };
00158
00160 enum class frame_metadata
00161 {
00162 actual_exposure,
00163 actual_fps
00164 };
00165
00169 enum class capabilities : int32_t
00170 {
00171 depth,
00172 color,
00173 infrared,
00174 infrared2,
00175 fish_eye,
00176 motion_events,
00177 motion_module_fw_update,
00178 adapter_board,
00179 enumeration,
00180 };
00181
00183 enum class blob_type
00184 {
00185 motion_module_firmware_update
00186 };
00187
00192 enum class camera_info {
00193 device_name ,
00194 serial_number ,
00195 camera_firmware_version ,
00196 adapter_board_firmware_version,
00197 motion_module_firmware_version,
00198 camera_type ,
00199 oem_id ,
00200 isp_fw_version ,
00201 content_version ,
00202 module_version ,
00203 imager_model_number ,
00204 build_date ,
00205 calibration_date ,
00206 program_date ,
00207 focus_alignment_date ,
00208 emitter_type ,
00209 focus_value ,
00210 lens_type ,
00211 third_lens_type ,
00212 lens_coating_type ,
00213 third_lens_coating_type ,
00214 lens_nominal_baseline ,
00215 third_lens_nominal_baseline
00216 };
00217
00219 enum class source : uint8_t
00220 {
00221 video ,
00222 motion_data,
00223 all_sources,
00224 };
00225
00227 enum class event : uint8_t
00228 {
00229 event_imu_accel ,
00230 event_imu_gyro ,
00231 event_imu_depth_cam ,
00232 event_imu_motion_cam,
00233 event_imu_g0_sync ,
00234 event_imu_g1_sync ,
00235 event_imu_g2_sync
00236 };
00237
00239
00242 enum class timestamp_domain
00243 {
00244 camera,
00245 microcontroller
00246 };
00247
00248 struct float2 { float x,y; };
00249 struct float3 { float x,y,z; };
00250
00252 struct intrinsics : rs_intrinsics
00253 {
00254 float hfov() const { return (atan2f(ppx + 0.5f, fx) + atan2f(width - (ppx + 0.5f), fx)) * 57.2957795f; }
00255 float vfov() const { return (atan2f(ppy + 0.5f, fy) + atan2f(height - (ppy + 0.5f), fy)) * 57.2957795f; }
00256 distortion model() const { return (distortion)rs_intrinsics::model; }
00257
00258
00259 float2 pixel_to_texcoord(const float2 & pixel) const { return {(pixel.x+0.5f)/width, (pixel.y+0.5f)/height}; }
00260 float2 texcoord_to_pixel(const float2 & coord) const { return {coord.x*width - 0.5f, coord.y*height - 0.5f}; }
00261
00262
00263 float3 deproject(const float2 & pixel, float depth) const { float3 point = {}; rs_deproject_pixel_to_point(&point.x, this, &pixel.x, depth); return point; }
00264 float3 deproject_from_texcoord(const float2 & coord, float depth) const { return deproject(texcoord_to_pixel(coord), depth); }
00265
00266
00267 float2 project(const float3 & point) const { float2 pixel = {}; rs_project_point_to_pixel(&pixel.x, this, &point.x); return pixel; }
00268 float2 project_to_texcoord(const float3 & point) const { return pixel_to_texcoord(project(point)); }
00269
00270 bool operator == (const intrinsics & r) const { return memcmp(this, &r, sizeof(r)) == 0; }
00271
00272 };
00273
00275 struct motion_intrinsics : rs_motion_intrinsics
00276 {
00277 motion_intrinsics(){};
00278 };
00279
00281 struct extrinsics : rs_extrinsics
00282 {
00283 bool is_identity() const { return (rotation[0] == 1) && (rotation[4] == 1) && (translation[0] == 0) && (translation[1] == 0) && (translation[2] == 0); }
00284 float3 transform(const float3 & point) const { float3 p = {}; rs_transform_point_to_point(&p.x, this, &point.x); return p; }
00285 };
00286
00288 struct timestamp_data : rs_timestamp_data
00289 {
00290 timestamp_data(rs_timestamp_data orig) : rs_timestamp_data(orig) {}
00291 timestamp_data() {}
00292 };
00293
00295 struct motion_data : rs_motion_data
00296 {
00297 motion_data(rs_motion_data orig) : rs_motion_data(orig) {}
00298 motion_data() {}
00299 };
00300
00301 class context;
00302 class device;
00303
00304 class error : public std::runtime_error
00305 {
00306 std::string function, args;
00307 public:
00308 error(rs_error * err) : std::runtime_error(rs_get_error_message(err))
00309 {
00310 function = (nullptr != rs_get_failed_function(err)) ? rs_get_failed_function(err) : std::string();
00311 args = (nullptr != rs_get_failed_args(err)) ? rs_get_failed_args(err) : std::string();
00312 rs_free_error(err);
00313 }
00314 const std::string & get_failed_function() const { return function; }
00315 const std::string & get_failed_args() const { return args; }
00316 static void handle(rs_error * e) { if(e) throw error(e); }
00317 };
00319 class context
00320 {
00321 rs_context * handle;
00322 context(const context &) = delete;
00323 context & operator = (const context &) = delete;
00324 public:
00325
00327 context()
00328 {
00329 rs_error * e = nullptr;
00330 handle = rs_create_context(RS_API_VERSION, &e);
00331 error::handle(e);
00332 }
00333
00334 explicit context(rs_context * handle) : handle(handle) {}
00335
00336 ~context()
00337 {
00338 rs_delete_context(handle, nullptr);
00339 }
00340
00343 int get_device_count() const
00344 {
00345 rs_error * e = nullptr;
00346 auto r = rs_get_device_count(handle, &e);
00347 error::handle(e);
00348 return r;
00349 }
00350
00354 device * get_device(int index)
00355 {
00356 rs_error * e = nullptr;
00357 auto r = rs_get_device(handle, index, &e);
00358 error::handle(e);
00359 return (device *)r;
00360 }
00361 };
00362
00363 class motion_callback : public rs_motion_callback
00364 {
00365 std::function<void(motion_data)> on_event_function;
00366 public:
00367 explicit motion_callback(std::function<void(motion_data)> on_event) : on_event_function(on_event) {}
00368
00369 void on_event(rs_motion_data e) override
00370 {
00371 on_event_function(motion_data(e));
00372 }
00373
00374 void release() override { delete this; }
00375 };
00376
00377 class timestamp_callback : public rs_timestamp_callback
00378 {
00379 std::function<void(timestamp_data)> on_event_function;
00380 public:
00381 explicit timestamp_callback(std::function<void(timestamp_data)> on_event) : on_event_function(on_event) {}
00382
00383 void on_event(rs_timestamp_data data) override
00384 {
00385 on_event_function(std::move(data));
00386 }
00387
00388 void release() override { delete this; }
00389 };
00390
00392 class frame
00393 {
00394 rs_device * device;
00395 rs_frame_ref * frame_ref;
00396
00397 frame(const frame &) = delete;
00398
00399 public:
00400 frame() : device(nullptr), frame_ref(nullptr) {}
00401 frame(rs_device * device, rs_frame_ref * frame_ref) : device(device), frame_ref(frame_ref) {}
00402 frame(frame&& other) : device(other.device), frame_ref(other.frame_ref) { other.frame_ref = nullptr; }
00403 frame& operator=(frame other)
00404 {
00405 swap(other);
00406 return *this;
00407 }
00408 void swap(frame& other)
00409 {
00410 std::swap(device, other.device);
00411 std::swap(frame_ref, other.frame_ref);
00412 }
00413
00414 ~frame()
00415 {
00416 if (device && frame_ref)
00417 {
00418 rs_error * e = nullptr;
00419 rs_release_frame(device, frame_ref, &e);
00420 error::handle(e);
00421 }
00422 }
00423
00426 double get_timestamp() const
00427 {
00428 rs_error * e = nullptr;
00429 auto r = rs_get_detached_frame_timestamp(frame_ref, &e);
00430 error::handle(e);
00431 return r;
00432 }
00433
00436 timestamp_domain get_frame_timestamp_domain() const
00437 {
00438 rs_error * e = nullptr;
00439 auto r = rs_get_detached_frame_timestamp_domain(frame_ref, &e);
00440 error::handle(e);
00441 return static_cast<timestamp_domain>(r);
00442 }
00443
00447 double get_frame_metadata(rs_frame_metadata frame_metadata) const
00448 {
00449 rs_error * e = nullptr;
00450 auto r = rs_get_detached_frame_metadata(frame_ref, (rs_frame_metadata)frame_metadata, &e);
00451 error::handle(e);
00452 return r;
00453 }
00454
00458 bool supports_frame_metadata(rs_frame_metadata frame_metadata) const
00459 {
00460 rs_error * e = nullptr;
00461 auto r = rs_supports_frame_metadata(frame_ref, frame_metadata, &e);
00462 error::handle(e);
00463 return r != 0;
00464 }
00465
00468 unsigned long long get_frame_number() const
00469 {
00470 rs_error * e = nullptr;
00471 auto r = rs_get_detached_frame_number(frame_ref, &e);
00472 error::handle(e);
00473 return r;
00474 }
00475
00478 const void * get_data() const
00479 {
00480 rs_error * e = nullptr;
00481 auto r = rs_get_detached_frame_data(frame_ref, &e);
00482 error::handle(e);
00483 return r;
00484 }
00485
00487 int get_width() const
00488 {
00489 rs_error * e = nullptr;
00490 auto r = rs_get_detached_frame_width(frame_ref, &e);
00491 error::handle(e);
00492 return r;
00493 }
00494
00496 int get_height() const
00497 {
00498 rs_error * e = nullptr;
00499 auto r = rs_get_detached_frame_height(frame_ref, &e);
00500 error::handle(e);
00501 return r;
00502 }
00503
00505 int get_framerate() const
00506 {
00507 rs_error * e = nullptr;
00508 auto r = rs_get_detached_framerate(frame_ref, &e);
00509 error::handle(e);
00510 return r;
00511 }
00512
00514 int get_stride() const
00515 {
00516 rs_error * e = nullptr;
00517 auto r = rs_get_detached_frame_stride(frame_ref, &e);
00518 error::handle(e);
00519 return r;
00520 }
00521
00524 int get_bpp() const
00525 {
00526 rs_error * e = nullptr;
00527 auto r = rs_get_detached_frame_bpp(frame_ref, &e);
00528 error::handle(e);
00529 return r;
00530 }
00531
00534 format get_format() const
00535 {
00536 rs_error * e = nullptr;
00537 auto r = rs_get_detached_frame_format(frame_ref, &e);
00538 error::handle(e);
00539 return static_cast<format>(r);
00540 }
00541
00544 stream get_stream_type() const
00545 {
00546 rs_error * e = nullptr;
00547 auto s = rs_get_detached_frame_stream_type(frame_ref, &e);
00548 error::handle(e);
00549 return static_cast<stream>(s);
00550 }
00551 };
00552
00553 class frame_callback : public rs_frame_callback
00554 {
00555 std::function<void(frame)> on_frame_function;
00556 public:
00557 explicit frame_callback(std::function<void(frame)> on_frame) : on_frame_function(on_frame) {}
00558
00559 void on_frame(rs_device * device, rs_frame_ref * fref) override
00560 {
00561 on_frame_function(std::move(frame(device, fref)));
00562 }
00563
00564 void release() override { delete this; }
00565 };
00567 class device
00568 {
00569 device() = delete;
00570 device(const device &) = delete;
00571 device & operator = (const device &) = delete;
00572 ~device() = delete;
00573
00574
00575 public:
00578 const char * get_name() const
00579 {
00580 rs_error * e = nullptr;
00581 auto r = rs_get_device_name((const rs_device *)this, &e);
00582 error::handle(e);
00583 return r;
00584 }
00585
00588 const char * get_serial() const
00589 {
00590 rs_error * e = nullptr;
00591 auto r = rs_get_device_serial((const rs_device *)this, &e);
00592 error::handle(e);
00593 return r;
00594 }
00595
00598 const char * get_usb_port_id() const
00599 {
00600 rs_error * e = nullptr;
00601 auto r = rs_get_device_usb_port_id((const rs_device *)this, &e);
00602 error::handle(e);
00603 return r;
00604 }
00605
00608 const char * get_firmware_version() const
00609 {
00610 rs_error * e = nullptr;
00611 auto r = rs_get_device_firmware_version((const rs_device *)this, &e);
00612 error::handle(e);
00613 return r;
00614 }
00615
00618 const char * get_info(camera_info info) const
00619 {
00620 rs_error * e = nullptr;
00621 auto r = rs_get_device_info((const rs_device *)this, (rs_camera_info)info, &e);
00622 error::handle(e);
00623 return r;
00624 }
00625
00630 extrinsics get_extrinsics(stream from_stream, stream to_stream) const
00631 {
00632 rs_error * e = nullptr;
00633 extrinsics extrin;
00634 rs_get_device_extrinsics((const rs_device *)this, (rs_stream)from_stream, (rs_stream)to_stream, &extrin, &e);
00635 error::handle(e);
00636 return extrin;
00637 }
00638
00642 extrinsics get_motion_extrinsics_from(stream from_stream) const
00643 {
00644 rs_error * e = nullptr;
00645 extrinsics extrin;
00646 rs_get_motion_extrinsics_from((const rs_device *)this, (rs_stream)from_stream, &extrin, &e);
00647 error::handle(e);
00648 return extrin;
00649 }
00650
00653 float get_depth_scale() const
00654 {
00655 rs_error * e = nullptr;
00656 auto r = rs_get_device_depth_scale((const rs_device *)this, &e);
00657 error::handle(e);
00658 return r;
00659 }
00660
00664 bool supports_option(option option) const
00665 {
00666 rs_error * e = nullptr;
00667 auto r = rs_device_supports_option((const rs_device *)this, (rs_option)option, &e);
00668 error::handle(e);
00669 return r != 0;
00670 }
00671
00675 int get_stream_mode_count(stream stream) const
00676 {
00677 rs_error * e = nullptr;
00678 auto r = rs_get_stream_mode_count((const rs_device *)this, (rs_stream)stream, &e);
00679 error::handle(e);
00680 return r;
00681 }
00682
00690 void get_stream_mode(stream stream, int index, int & width, int & height, format & format, int & framerate) const
00691 {
00692 rs_error * e = nullptr;
00693 rs_get_stream_mode((const rs_device *)this, (rs_stream)stream, index, &width, &height, (rs_format *)&format, &framerate, &e);
00694 error::handle(e);
00695 }
00696
00704 void enable_stream(stream stream, int width, int height, format format, int framerate, output_buffer_format output_buffer_type = output_buffer_format::continous)
00705 {
00706 rs_error * e = nullptr;
00707 rs_enable_stream_ex((rs_device *)this, (rs_stream)stream, width, height, (rs_format)format, framerate, (rs_output_buffer_format)output_buffer_type, &e);
00708 error::handle(e);
00709 }
00710
00714 void enable_stream(stream stream, preset preset)
00715 {
00716 rs_error * e = nullptr;
00717 rs_enable_stream_preset((rs_device *)this, (rs_stream)stream, (rs_preset)preset, &e);
00718 error::handle(e);
00719 }
00720
00723 void disable_stream(stream stream)
00724 {
00725 rs_error * e = nullptr;
00726 rs_disable_stream((rs_device *)this, (rs_stream)stream, &e);
00727 error::handle(e);
00728 }
00729
00733 bool is_stream_enabled(stream stream) const
00734 {
00735 rs_error * e = nullptr;
00736 auto r = rs_is_stream_enabled((const rs_device *)this, (rs_stream)stream, &e);
00737 error::handle(e);
00738 return r != 0;
00739 }
00740
00744 int get_stream_width(stream stream) const
00745 {
00746 rs_error * e = nullptr;
00747 auto r = rs_get_stream_width((const rs_device *)this, (rs_stream)stream, &e);
00748 error::handle(e);
00749 return r;
00750 }
00751
00755 int get_stream_height(stream stream) const
00756 {
00757 rs_error * e = nullptr;
00758 auto r = rs_get_stream_height((const rs_device *)this, (rs_stream)stream, &e);
00759 error::handle(e);
00760 return r;
00761 }
00762
00766 format get_stream_format(stream stream) const
00767 {
00768 rs_error * e = nullptr;
00769 auto r = rs_get_stream_format((const rs_device *)this, (rs_stream)stream, &e);
00770 error::handle(e);
00771 return (format)r;
00772 }
00773
00777 int get_stream_framerate(stream stream) const
00778 {
00779 rs_error * e = nullptr;
00780 auto r = rs_get_stream_framerate((const rs_device *)this, (rs_stream)stream, &e);
00781 error::handle(e);
00782 return r;
00783 }
00784
00788 intrinsics get_stream_intrinsics(stream stream) const
00789 {
00790 rs_error * e = nullptr;
00791 intrinsics intrin;
00792 rs_get_stream_intrinsics((const rs_device *)this, (rs_stream)stream, &intrin, &e);
00793 error::handle(e);
00794 return intrin;
00795 }
00796
00799 motion_intrinsics get_motion_intrinsics() const
00800 {
00801 rs_error * e = nullptr;
00802 motion_intrinsics intrinsics;
00803 rs_get_motion_intrinsics((const rs_device *)this, &intrinsics, &e);
00804 error::handle(e);
00805 return intrinsics;
00806 }
00807
00817 void set_frame_callback(rs::stream stream, std::function<void(frame)> frame_handler)
00818 {
00819 rs_error * e = nullptr;
00820 rs_set_frame_callback_cpp((rs_device *)this, (rs_stream)stream, new frame_callback(frame_handler), &e);
00821 error::handle(e);
00822 }
00823
00837
00841 void enable_motion_tracking(std::function<void(motion_data)> motion_handler, std::function<void(timestamp_data)> timestamp_handler)
00842 {
00843 rs_error * e = nullptr;
00844 rs_enable_motion_tracking_cpp((rs_device *)this, new motion_callback(motion_handler), new timestamp_callback(timestamp_handler), &e);
00845 error::handle(e);
00846 }
00847
00853 void enable_motion_tracking(std::function<void(motion_data)> motion_handler)
00854 {
00855 rs_error * e = nullptr;
00856 rs_enable_motion_tracking_cpp((rs_device *)this, new motion_callback(motion_handler), new timestamp_callback([](rs::timestamp_data data) {}), &e);
00857 error::handle(e);
00858 }
00859
00861 void disable_motion_tracking(void)
00862 {
00863 rs_error * e = nullptr;
00864 rs_disable_motion_tracking((rs_device *)this, &e);
00865 error::handle(e);
00866 }
00867
00869 int is_motion_tracking_active()
00870 {
00871 rs_error * e = nullptr;
00872 auto result = rs_is_motion_tracking_active((rs_device *)this,&e);
00873 error::handle(e);
00874 return result;
00875 }
00876
00877
00879 void start(rs::source source = rs::source::video)
00880 {
00881 rs_error * e = nullptr;
00882 rs_start_source((rs_device *)this, (rs_source)source, &e);
00883 error::handle(e);
00884 }
00885
00887 void stop(rs::source source = rs::source::video)
00888 {
00889 rs_error * e = nullptr;
00890 rs_stop_source((rs_device *)this, (rs_source)source, &e);
00891 error::handle(e);
00892 }
00893
00896 bool is_streaming() const
00897 {
00898 rs_error * e = nullptr;
00899 auto r = rs_is_device_streaming((const rs_device *)this, &e);
00900 error::handle(e);
00901 return r != 0;
00902 }
00903
00909 void get_option_range(option option, double & min, double & max, double & step)
00910 {
00911 rs_error * e = nullptr;
00912 rs_get_device_option_range((rs_device *)this, (rs_option)option, &min, &max, &step, &e);
00913 error::handle(e);
00914 }
00915
00922 void get_option_range(option option, double & min, double & max, double & step, double & def)
00923 {
00924 rs_error * e = nullptr;
00925 rs_get_device_option_range_ex((rs_device *)this, (rs_option)option, &min, &max, &step, &def, &e);
00926 error::handle(e);
00927 }
00928
00933 void get_options(const option * options, size_t count, double * values)
00934 {
00935 rs_error * e = nullptr;
00936 rs_get_device_options((rs_device *)this, (const rs_option *)options, (unsigned int)count, values, &e);
00937 error::handle(e);
00938 }
00939
00944 void set_options(const option * options, size_t count, const double * values)
00945 {
00946 rs_error * e = nullptr;
00947 rs_set_device_options((rs_device *)this, (const rs_option *)options, (unsigned int)count, values, &e);
00948 error::handle(e);
00949 }
00950
00954 double get_option(option option)
00955 {
00956 rs_error * e = nullptr;
00957 auto r = rs_get_device_option((rs_device *)this, (rs_option)option, &e);
00958 error::handle(e);
00959 return r;
00960 }
00961
00965 const char * get_option_description(option option)
00966 {
00967 rs_error * e = nullptr;
00968 auto r = rs_get_device_option_description((rs_device *)this, (rs_option)option, &e);
00969 error::handle(e);
00970 return r;
00971 }
00972
00976 void set_option(option option, double value)
00977 {
00978 rs_error * e = nullptr;
00979 rs_set_device_option((rs_device *)this, (rs_option)option, value, &e);
00980 error::handle(e);
00981 }
00982
00985 void wait_for_frames()
00986 {
00987 rs_error * e = nullptr;
00988 rs_wait_for_frames((rs_device *)this, &e);
00989 error::handle(e);
00990 }
00991
00994 bool poll_for_frames()
00995 {
00996 rs_error * e = nullptr;
00997 auto r = rs_poll_for_frames((rs_device *)this, &e);
00998 error::handle(e);
00999 return r != 0;
01000 }
01001
01005 bool supports(capabilities capability) const
01006 {
01007 rs_error * e = nullptr;
01008 auto r = rs_supports((rs_device *)this, (rs_capabilities)capability, &e);
01009 error::handle(e);
01010 return r? true: false;
01011 }
01012
01013
01017 bool supports(camera_info info_param) const
01018 {
01019 rs_error * e = nullptr;
01020 auto r = rs_supports_camera_info((rs_device *)this, (rs_camera_info)info_param, &e);
01021 error::handle(e);
01022 return r ? true : false;
01023 }
01024
01028 double get_frame_timestamp(stream stream) const
01029 {
01030 rs_error * e = nullptr;
01031 auto r = rs_get_frame_timestamp((const rs_device *)this, (rs_stream)stream, &e);
01032 error::handle(e);
01033 return r;
01034 }
01035
01039 unsigned long long get_frame_number(stream stream) const
01040 {
01041 rs_error * e = nullptr;
01042 auto r = rs_get_frame_number((const rs_device *)this, (rs_stream)stream, &e);
01043 error::handle(e);
01044 return r;
01045 }
01046
01050 const void * get_frame_data(stream stream) const
01051 {
01052 rs_error * e = nullptr;
01053 auto r = rs_get_frame_data((const rs_device *)this, (rs_stream)stream, &e);
01054 error::handle(e);
01055 return r;
01056 }
01057
01062 void send_blob_to_device(rs::blob_type type, void * data, int size)
01063 {
01064 rs_error * e = nullptr;
01065 rs_send_blob_to_device((rs_device *)this, (rs_blob_type)type, data, size, &e);
01066 error::handle(e);
01067 }
01068 };
01069
01070 inline std::ostream & operator << (std::ostream & o, stream stream) { return o << rs_stream_to_string((rs_stream)stream); }
01071 inline std::ostream & operator << (std::ostream & o, format format) { return o << rs_format_to_string((rs_format)format); }
01072 inline std::ostream & operator << (std::ostream & o, preset preset) { return o << rs_preset_to_string((rs_preset)preset); }
01073 inline std::ostream & operator << (std::ostream & o, distortion distortion) { return o << rs_distortion_to_string((rs_distortion)distortion); }
01074 inline std::ostream & operator << (std::ostream & o, option option) { return o << rs_option_to_string((rs_option)option); }
01075 inline std::ostream & operator << (std::ostream & o, capabilities capability) { return o << rs_capabilities_to_string((rs_capabilities)capability); }
01076 inline std::ostream & operator << (std::ostream & o, source src) { return o << rs_source_to_string((rs_source)src); }
01077 inline std::ostream & operator << (std::ostream & o, event evt) { return o << rs_event_to_string((rs_event_source)evt); }
01078
01080 enum class log_severity : int32_t
01081 {
01082 debug = 0,
01083 info = 1,
01084 warn = 2,
01085 error = 3,
01086 fatal = 4,
01087 none = 5,
01088 };
01089
01090 class log_callback : public rs_log_callback
01091 {
01092 std::function<void(log_severity, const char *)> on_event_function;
01093 public:
01094 explicit log_callback(std::function<void(log_severity, const char *)> on_event) : on_event_function(on_event) {}
01095
01096 void on_event(rs_log_severity severity, const char * message) override
01097 {
01098 on_event_function((log_severity)severity, message);
01099 }
01100
01101 void release() override { delete this; }
01102 };
01103
01104 inline void log_to_console(log_severity min_severity)
01105 {
01106 rs_error * e = nullptr;
01107 rs_log_to_console((rs_log_severity)min_severity, &e);
01108 error::handle(e);
01109 }
01110
01111 inline void log_to_file(log_severity min_severity, const char * file_path)
01112 {
01113 rs_error * e = nullptr;
01114 rs_log_to_file((rs_log_severity)min_severity, file_path, &e);
01115 error::handle(e);
01116 }
01117
01118 inline void log_to_callback(log_severity min_severity, std::function<void(log_severity, const char *)> callback)
01119 {
01120 rs_error * e = nullptr;
01121 rs_log_to_callback_cpp((rs_log_severity)min_severity, new log_callback(callback), &e);
01122 error::handle(e);
01123 }
01124
01125
01126 inline void apply_depth_control_preset(device * device, int preset) { rs_apply_depth_control_preset((rs_device *)device, preset); }
01127 inline void apply_ivcam_preset(device * device, rs_ivcam_preset preset) { rs_apply_ivcam_preset((rs_device *)device, preset); }
01128 inline void apply_ivcam_preset(device * device, int preset) { rs_apply_ivcam_preset((rs_device *)device, (rs_ivcam_preset)preset); }
01129 }
01130 #endif