Intel® RealSense™ Cross Platform API  2.13.0
Intel Realsense Cross-platform API
rs_sensor.hpp
Go to the documentation of this file.
1 // License: Apache 2.0. See LICENSE file in root directory.
2 // Copyright(c) 2017 Intel Corporation. All Rights Reserved.
3 
4 #ifndef LIBREALSENSE_RS2_SENSOR_HPP
5 #define LIBREALSENSE_RS2_SENSOR_HPP
6 
7 #include "rs_types.hpp"
8 #include "rs_frame.hpp"
9 
10 namespace rs2
11 {
13  {
14  public:
16  {
17  rs2_error* e = nullptr;
19  error::handle(e);
21  error::handle(e);
23  error::handle(e);
25  error::handle(e);
26  _serialized_data = rs2_get_notification_serialized_data(notification, &e);
27  error::handle(e);
28  }
29 
30  notification() = default;
31 
37  {
38  return _category;
39  }
44  std::string get_description() const
45  {
46  return _description;
47  }
48 
53  double get_timestamp() const
54  {
55  return _timestamp;
56  }
57 
63  {
64  return _severity;
65  }
66 
71  std::string get_serialized_data() const
72  {
73  return _serialized_data;
74  }
75 
76  private:
77  std::string _description;
78  double _timestamp = -1;
81  std::string _serialized_data;
82  };
83 
84  template<class T>
86  {
87  T on_notification_function;
88  public:
89  explicit notifications_callback(T on_notification) : on_notification_function(on_notification) {}
90 
91  void on_notification(rs2_notification* _notification) override
92  {
93  on_notification_function(notification{ _notification });
94  }
95 
96  void release() override { delete this; }
97  };
98 
99  template<class T>
101  {
102  T on_frame_function;
103  public:
104  explicit frame_callback(T on_frame) : on_frame_function(on_frame) {}
105 
106  void on_frame(rs2_frame* fref) override
107  {
108  on_frame_function(frame{ fref });
109  }
110 
111  void release() override { delete this; }
112  };
113 
114  class options
115  {
116  public:
122  bool supports(rs2_option option) const
123  {
124  rs2_error* e = nullptr;
125  auto res = rs2_supports_option(_options, option, &e);
126  error::handle(e);
127  return res > 0;
128  }
129 
135  const char* get_option_description(rs2_option option) const
136  {
137  rs2_error* e = nullptr;
138  auto res = rs2_get_option_description(_options, option, &e);
139  error::handle(e);
140  return res;
141  }
142 
149  const char* get_option_value_description(rs2_option option, float val) const
150  {
151  rs2_error* e = nullptr;
152  auto res = rs2_get_option_value_description(_options, option, val, &e);
153  error::handle(e);
154  return res;
155  }
156 
162  float get_option(rs2_option option) const
163  {
164  rs2_error* e = nullptr;
165  auto res = rs2_get_option(_options, option, &e);
166  error::handle(e);
167  return res;
168  }
169 
175  {
176  option_range result;
177  rs2_error* e = nullptr;
178  rs2_get_option_range(_options, option,
179  &result.min, &result.max, &result.step, &result.def, &e);
180  error::handle(e);
181  return result;
182  }
183 
189  void set_option(rs2_option option, float value) const
190  {
191  rs2_error* e = nullptr;
192  rs2_set_option(_options, option, value, &e);
193  error::handle(e);
194  }
195 
201  bool is_option_read_only(rs2_option option) const
202  {
203  rs2_error* e = nullptr;
204  auto res = rs2_is_option_read_only(_options, option, &e);
205  error::handle(e);
206  return res > 0;
207  }
208 
209  options& operator=(const options& other)
210  {
211  _options = other._options;
212  return *this;
213  }
214 
215  virtual ~options() = default;
216  protected:
217  explicit options(rs2_options* o = nullptr) : _options(o) {}
218 
219  template<class T>
220  options& operator=(const T& dev)
221  {
222  _options = (rs2_options*)(dev.get());
223  return *this;
224  }
225 
226  options(const options& other) : _options(other._options) {}
227 
228  private:
229  rs2_options* _options;
230  };
231 
232  class sensor : public options
233  {
234  public:
235 
236  using options::supports;
241  void open(const stream_profile& profile) const
242  {
243  rs2_error* e = nullptr;
244  rs2_open(_sensor.get(),
245  profile.get(),
246  &e);
247  error::handle(e);
248  }
249 
255  bool supports(rs2_camera_info info) const
256  {
257  rs2_error* e = nullptr;
258  auto is_supported = rs2_supports_sensor_info(_sensor.get(), info, &e);
259  error::handle(e);
260  return is_supported > 0;
261  }
262 
268  const char* get_info(rs2_camera_info info) const
269  {
270  rs2_error* e = nullptr;
271  auto result = rs2_get_sensor_info(_sensor.get(), info, &e);
272  error::handle(e);
273  return result;
274  }
275 
281  void open(const std::vector<stream_profile>& profiles) const
282  {
283  rs2_error* e = nullptr;
284 
285  std::vector<const rs2_stream_profile*> profs;
286  profs.reserve(profiles.size());
287  for (auto& p : profiles)
288  {
289  profs.push_back(p.get());
290  }
291 
293  profs.data(),
294  static_cast<int>(profiles.size()),
295  &e);
296  error::handle(e);
297  }
298 
303  void close() const
304  {
305  rs2_error* e = nullptr;
306  rs2_close(_sensor.get(), &e);
307  error::handle(e);
308  }
309 
314  template<class T>
315  void start(T callback) const
316  {
317  rs2_error* e = nullptr;
318  rs2_start_cpp(_sensor.get(), new frame_callback<T>(std::move(callback)), &e);
319  error::handle(e);
320  }
321 
325  void stop() const
326  {
327  rs2_error* e = nullptr;
328  rs2_stop(_sensor.get(), &e);
329  error::handle(e);
330  }
331 
336  template<class T>
337  void set_notifications_callback(T callback) const
338  {
339  rs2_error* e = nullptr;
341  new notifications_callback<T>(std::move(callback)), &e);
342  error::handle(e);
343  }
344 
345 
350  std::vector<stream_profile> get_stream_profiles() const
351  {
352  std::vector<stream_profile> results;
353 
354  rs2_error* e = nullptr;
355  std::shared_ptr<rs2_stream_profile_list> list(
356  rs2_get_stream_profiles(_sensor.get(), &e),
358  error::handle(e);
359 
360  auto size = rs2_get_stream_profiles_count(list.get(), &e);
361  error::handle(e);
362 
363  for (auto i = 0; i < size; i++)
364  {
365  stream_profile profile(rs2_get_stream_profile(list.get(), i, &e));
366  error::handle(e);
367  results.push_back(profile);
368  }
369 
370  return results;
371  }
372 
373  sensor& operator=(const std::shared_ptr<rs2_sensor> other)
374  {
375  options::operator=(other);
376  _sensor.reset();
377  _sensor = other;
378  return *this;
379  }
380 
381  sensor& operator=(const sensor& other)
382  {
383  *this = nullptr;
385  _sensor = other._sensor;
386  return *this;
387  }
388  sensor() : _sensor(nullptr) {}
389 
390  operator bool() const
391  {
392  return _sensor != nullptr;
393  }
394 
395  const std::shared_ptr<rs2_sensor>& get() const
396  {
397  return _sensor;
398  }
399 
400  template<class T>
401  bool is() const
402  {
403  T extension(*this);
404  return extension;
405  }
406 
407  template<class T>
408  T as() const
409  {
410  T extension(*this);
411  return extension;
412  }
413 
414  protected:
415  friend context;
416  friend device_list;
417  friend device;
418  friend device_base;
419  friend roi_sensor;
420 
421  std::shared_ptr<rs2_sensor> _sensor;
422 
423  explicit sensor(std::shared_ptr<rs2_sensor> dev)
424  :options((rs2_options*)dev.get()), _sensor(dev)
425  {
426  }
427  };
428 
429  inline bool operator==(const sensor& lhs, const sensor& rhs)
430  {
433  return false;
434 
435  return std::string(lhs.get_info(RS2_CAMERA_INFO_NAME)) == rhs.get_info(RS2_CAMERA_INFO_NAME)
437  }
438 
439  class roi_sensor : public sensor
440  {
441  public:
443  : sensor(s.get())
444  {
445  rs2_error* e = nullptr;
446  if(rs2_is_sensor_extendable_to(_sensor.get(), RS2_EXTENSION_ROI, &e) == 0 && !e)
447  {
448  _sensor.reset();
449  }
450  error::handle(e);
451  }
452 
454  {
455  rs2_error* e = nullptr;
456  rs2_set_region_of_interest(_sensor.get(), roi.min_x, roi.min_y, roi.max_x, roi.max_y, &e);
457  error::handle(e);
458  }
459 
461  {
462  region_of_interest roi {};
463  rs2_error* e = nullptr;
464  rs2_get_region_of_interest(_sensor.get(), &roi.min_x, &roi.min_y, &roi.max_x, &roi.max_y, &e);
465  error::handle(e);
466  return roi;
467  }
468 
469  operator bool() const { return _sensor.get() != nullptr; }
470  };
471 
472  class depth_sensor : public sensor
473  {
474  public:
476  : sensor(s.get())
477  {
478  rs2_error* e = nullptr;
480  {
481  _sensor.reset();
482  }
483  error::handle(e);
484  }
485 
489  float get_depth_scale() const
490  {
491  rs2_error* e = nullptr;
492  auto res = rs2_get_depth_scale(_sensor.get(), &e);
493  error::handle(e);
494  return res;
495  }
496 
497  operator bool() const { return _sensor.get() != nullptr; }
498  };
499 
501  {
502  public:
504  {
505  rs2_error* e = nullptr;
507  {
508  _sensor.reset();
509  }
510  error::handle(e);
511  }
512 
516  float get_stereo_baseline() const
517  {
518  rs2_error* e = nullptr;
519  auto res = rs2_get_depth_scale(_sensor.get(), &e);
520  error::handle(e);
521  return res;
522  }
523 
524  operator bool() const { return _sensor.get() != nullptr; }
525  };
526 }
527 #endif // LIBREALSENSE_RS2_SENSOR_HPP
Definition: rs_frame.hpp:21
rs2_camera_info
Read-only strings that can be queried from the device. Not all information attributes are available o...
Definition: rs_sensor.h:22
Definition: rs_types.hpp:25
Definition: rs_sensor.hpp:232
bool operator==(const sensor &lhs, const sensor &rhs)
Definition: rs_sensor.hpp:429
float rs2_get_option(const rs2_options *options, rs2_option option, rs2_error **error)
Definition: rs_frame.hpp:202
Definition: rs_types.hpp:161
float rs2_get_depth_scale(rs2_sensor *sensor, rs2_error **error)
void release() override
Definition: rs_sensor.hpp:111
bool supports(rs2_option option) const
Definition: rs_sensor.hpp:122
friend device
Definition: rs_sensor.hpp:417
void stop() const
Definition: rs_sensor.hpp:325
std::vector< stream_profile > get_stream_profiles() const
Definition: rs_sensor.hpp:350
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls...
Definition: rs_option.h:22
region_of_interest get_region_of_interest() const
Definition: rs_sensor.hpp:460
void on_notification(rs2_notification *_notification) override
Definition: rs_sensor.hpp:91
Definition: rs_types.hpp:39
virtual ~options()=default
Definition: rs_sensor.hpp:472
void start(T callback) const
Definition: rs_sensor.hpp:315
int min_x
Definition: rs_types.hpp:163
Definition: rs_sensor.h:24
void rs2_set_region_of_interest(const rs2_sensor *sensor, int min_x, int min_y, int max_x, int max_y, rs2_error **error)
sets the active region of interest to be used by auto-exposure algorithm
depth_sensor(sensor s)
Definition: rs_sensor.hpp:475
friend context
Definition: rs_sensor.hpp:415
float min
Definition: rs_types.hpp:155
void rs2_stop(const rs2_sensor *sensor, rs2_error **error)
options & operator=(const T &dev)
Definition: rs_sensor.hpp:220
depth_stereo_sensor(sensor s)
Definition: rs_sensor.hpp:503
void release() override
Definition: rs_sensor.hpp:96
const char * rs2_get_notification_serialized_data(rs2_notification *notification, rs2_error **error)
Definition: rs_context.hpp:11
bool supports(rs2_camera_info info) const
Definition: rs_sensor.hpp:255
Definition: rs_sensor.h:23
notification(rs2_notification *notification)
Definition: rs_sensor.hpp:15
rs2_log_severity rs2_get_notification_severity(rs2_notification *notification, rs2_error **error)
notification()=default
Definition: rs_types.h:103
const char * get_option_description(rs2_option option) const
Definition: rs_sensor.hpp:135
int max_y
Definition: rs_types.hpp:166
sensor(std::shared_ptr< rs2_sensor > dev)
Definition: rs_sensor.hpp:423
friend roi_sensor
Definition: rs_sensor.hpp:419
void set_region_of_interest(const region_of_interest &roi)
Definition: rs_sensor.hpp:453
int max_x
Definition: rs_types.hpp:165
options(const options &other)
Definition: rs_sensor.hpp:226
rs2_notification_category get_category() const
Definition: rs_sensor.hpp:36
float max
Definition: rs_types.hpp:156
float step
Definition: rs_types.hpp:158
void rs2_open(rs2_sensor *device, const rs2_stream_profile *profile, rs2_error **error)
notifications_callback(T on_notification)
Definition: rs_sensor.hpp:89
frame_callback(T on_frame)
Definition: rs_sensor.hpp:104
float get_option(rs2_option option) const
Definition: rs_sensor.hpp:162
Definition: rs_sensor.hpp:100
double get_timestamp() const
Definition: rs_sensor.hpp:53
void open(const stream_profile &profile) const
Definition: rs_sensor.hpp:241
int rs2_supports_option(const rs2_options *options, rs2_option option, rs2_error **error)
void set_notifications_callback(T callback) const
Definition: rs_sensor.hpp:337
struct rs2_notification rs2_notification
Definition: rs_types.h:173
std::shared_ptr< rs2_sensor > _sensor
Definition: rs_sensor.hpp:421
Definition: rs_types.h:102
const char * rs2_get_option_value_description(const rs2_options *options, rs2_option option, float value, rs2_error **error)
Definition: rs_sensor.hpp:12
friend device_base
Definition: rs_sensor.hpp:418
Definition: rs_types.h:113
Definition: rs_types.hpp:153
void rs2_get_region_of_interest(const rs2_sensor *sensor, int *min_x, int *min_y, int *max_x, int *max_y, rs2_error **error)
gets the active region of interest to be used by auto-exposure algorithm
rs2_time_t rs2_get_notification_timestamp(rs2_notification *notification, rs2_error **error)
sensor()
Definition: rs_sensor.hpp:388
const rs2_stream_profile * rs2_get_stream_profile(const rs2_stream_profile_list *list, int index, rs2_error **error)
void rs2_set_notifications_callback_cpp(const rs2_sensor *sensor, rs2_notifications_callback *callback, rs2_error **error)
Definition: rs_sensor.hpp:114
const char * get_option_value_description(rs2_option option, float val) const
Definition: rs_sensor.hpp:149
T as() const
Definition: rs_sensor.hpp:408
void rs2_get_option_range(const rs2_options *sensor, rs2_option option, float *min, float *max, float *step, float *def, rs2_error **error)
int rs2_supports_sensor_info(const rs2_sensor *sensor, rs2_camera_info info, rs2_error **error)
struct rs2_options rs2_options
Definition: rs_types.h:171
Definition: rs_sensor.hpp:85
static void handle(rs2_error *e)
Definition: rs_types.hpp:121
std::string get_serialized_data() const
Definition: rs_sensor.hpp:71
bool is() const
Definition: rs_sensor.hpp:401
void close() const
Definition: rs_sensor.hpp:303
options(rs2_options *o=nullptr)
Definition: rs_sensor.hpp:217
const rs2_stream_profile * get() const
Definition: rs_frame.hpp:79
Definition: rs_types.h:89
void open(const std::vector< stream_profile > &profiles) const
Definition: rs_sensor.hpp:281
float get_stereo_baseline() const
Definition: rs_sensor.hpp:516
Definition: rs_types.h:24
int rs2_is_sensor_extendable_to(const rs2_sensor *sensor, rs2_extension extension, rs2_error **error)
rs2_log_severity get_severity() const
Definition: rs_sensor.hpp:62
bool is_option_read_only(rs2_option option) const
Definition: rs_sensor.hpp:201
void on_frame(rs2_frame *fref) override
Definition: rs_sensor.hpp:106
rs2_notification_category
Category of the librealsense notifications.
Definition: rs_types.h:17
option_range get_option_range(rs2_option option) const
Definition: rs_sensor.hpp:174
void set_option(rs2_option option, float value) const
Definition: rs_sensor.hpp:189
void rs2_delete_stream_profiles_list(rs2_stream_profile_list *list)
float def
Definition: rs_types.hpp:157
void rs2_close(const rs2_sensor *sensor, rs2_error **error)
rs2_stream_profile_list * rs2_get_stream_profiles(rs2_sensor *device, rs2_error **error)
const char * rs2_get_option_description(const rs2_options *options, rs2_option option, rs2_error **error)
options & operator=(const options &other)
Definition: rs_sensor.hpp:209
int rs2_is_option_read_only(const rs2_options *options, rs2_option option, rs2_error **error)
void rs2_open_multiple(rs2_sensor *device, const rs2_stream_profile **profiles, int count, rs2_error **error)
void rs2_start_cpp(const rs2_sensor *sensor, rs2_frame_callback *callback, rs2_error **error)
Definition: rs_sensor.hpp:439
friend device_list
Definition: rs_sensor.hpp:416
rs2_notification_category rs2_get_notification_category(rs2_notification *notification, rs2_error **error)
std::string get_description() const
Definition: rs_sensor.hpp:44
float get_depth_scale() const
Definition: rs_sensor.hpp:489
const char * rs2_get_sensor_info(const rs2_sensor *sensor, rs2_camera_info info, rs2_error **error)
sensor & operator=(const sensor &other)
Definition: rs_sensor.hpp:381
const char * rs2_get_notification_description(rs2_notification *notification, rs2_error **error)
int rs2_get_stream_profiles_count(const rs2_stream_profile_list *list, rs2_error **error)
const std::shared_ptr< rs2_sensor > & get() const
Definition: rs_sensor.hpp:395
void rs2_set_option(const rs2_options *options, rs2_option option, float value, rs2_error **error)
struct rs2_error rs2_error
Definition: rs_types.h:149
rs2_log_severity
Severity of the librealsense logger.
Definition: rs_types.h:82
Definition: rs_sensor.hpp:500
sensor & operator=(const std::shared_ptr< rs2_sensor > other)
Definition: rs_sensor.hpp:373
const char * get_info(rs2_camera_info info) const
Definition: rs_sensor.hpp:268
int min_y
Definition: rs_types.hpp:164
struct rs2_frame rs2_frame
Definition: rs_types.h:151
roi_sensor(sensor s)
Definition: rs_sensor.hpp:442