Intel® RealSense™ Cross Platform API
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;
18  _description = rs2_get_notification_description(notification, &e);
19  error::handle(e);
20  _timestamp = rs2_get_notification_timestamp(notification, &e);
21  error::handle(e);
22  _severity = rs2_get_notification_severity(notification, &e);
23  error::handle(e);
24  _category = rs2_get_notification_category(notification, &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  protected:
216  explicit options(rs2_options* o = nullptr) : _options(o) {}
217 
218  template<class T>
219  options& operator=(const T& dev)
220  {
221  _options = (rs2_options*)(dev.get());
222  return *this;
223  }
224 
225  options(const options& other) : _options(other._options) {}
226 
227  private:
228  rs2_options* _options;
229  };
230 
231  class sensor : public options
232  {
233  public:
234 
235  using options::supports;
240  void open(const stream_profile& profile) const
241  {
242  rs2_error* e = nullptr;
243  rs2_open(_sensor.get(),
244  profile.get(),
245  &e);
246  error::handle(e);
247  }
248 
254  bool supports(rs2_camera_info info) const
255  {
256  rs2_error* e = nullptr;
257  auto is_supported = rs2_supports_sensor_info(_sensor.get(), info, &e);
258  error::handle(e);
259  return is_supported > 0;
260  }
261 
267  const char* get_info(rs2_camera_info info) const
268  {
269  rs2_error* e = nullptr;
270  auto result = rs2_get_sensor_info(_sensor.get(), info, &e);
271  error::handle(e);
272  return result;
273  }
274 
280  void open(const std::vector<stream_profile>& profiles) const
281  {
282  rs2_error* e = nullptr;
283 
284  std::vector<const rs2_stream_profile*> profs;
285  profs.reserve(profiles.size());
286  for (auto& p : profiles)
287  {
288  profs.push_back(p.get());
289  }
290 
291  rs2_open_multiple(_sensor.get(),
292  profs.data(),
293  static_cast<int>(profiles.size()),
294  &e);
295  error::handle(e);
296  }
297 
302  void close() const
303  {
304  rs2_error* e = nullptr;
305  rs2_close(_sensor.get(), &e);
306  error::handle(e);
307  }
308 
313  template<class T>
314  void start(T callback) const
315  {
316  rs2_error* e = nullptr;
317  rs2_start_cpp(_sensor.get(), new frame_callback<T>(std::move(callback)), &e);
318  error::handle(e);
319  }
320 
324  void stop() const
325  {
326  rs2_error* e = nullptr;
327  rs2_stop(_sensor.get(), &e);
328  error::handle(e);
329  }
330 
335  template<class T>
336  void set_notifications_callback(T callback) const
337  {
338  rs2_error* e = nullptr;
340  new notifications_callback<T>(std::move(callback)), &e);
341  error::handle(e);
342  }
343 
344 
349  std::vector<stream_profile> get_stream_profiles() const
350  {
351  std::vector<stream_profile> results;
352 
353  rs2_error* e = nullptr;
354  std::shared_ptr<rs2_stream_profile_list> list(
355  rs2_get_stream_profiles(_sensor.get(), &e),
357  error::handle(e);
358 
359  auto size = rs2_get_stream_profiles_count(list.get(), &e);
360  error::handle(e);
361 
362  for (auto i = 0; i < size; i++)
363  {
364  stream_profile profile(rs2_get_stream_profile(list.get(), i, &e));
365  error::handle(e);
366  results.push_back(profile);
367  }
368 
369  return results;
370  }
371 
372  sensor& operator=(const std::shared_ptr<rs2_sensor> other)
373  {
374  options::operator=(other);
375  _sensor.reset();
376  _sensor = other;
377  return *this;
378  }
379 
380  sensor& operator=(const sensor& other)
381  {
382  *this = nullptr;
384  _sensor = other._sensor;
385  return *this;
386  }
387  sensor() : _sensor(nullptr) {}
388 
389  operator bool() const
390  {
391  return _sensor != nullptr;
392  }
393 
394  const std::shared_ptr<rs2_sensor>& get() const
395  {
396  return _sensor;
397  }
398 
399  template<class T>
400  bool is() const
401  {
402  T extension(*this);
403  return extension;
404  }
405 
406  template<class T>
407  T as() const
408  {
409  T extension(*this);
410  return extension;
411  }
412 
413  protected:
414  friend context;
415  friend device_list;
416  friend device;
417  friend device_base;
418  friend roi_sensor;
419 
420  std::shared_ptr<rs2_sensor> _sensor;
421 
422  explicit sensor(std::shared_ptr<rs2_sensor> dev)
423  :options((rs2_options*)dev.get()), _sensor(dev)
424  {
425  }
426  };
427 
428  inline bool operator==(const sensor& lhs, const sensor& rhs)
429  {
432  return false;
433 
434  return std::string(lhs.get_info(RS2_CAMERA_INFO_NAME)) == rhs.get_info(RS2_CAMERA_INFO_NAME)
436  }
437 
438  class roi_sensor : public sensor
439  {
440  public:
442  : sensor(s.get())
443  {
444  rs2_error* e = nullptr;
445  if(rs2_is_sensor_extendable_to(_sensor.get(), RS2_EXTENSION_ROI, &e) == 0 && !e)
446  {
447  _sensor = nullptr;
448  }
449  error::handle(e);
450  }
451 
453  {
454  rs2_error* e = nullptr;
455  rs2_set_region_of_interest(_sensor.get(), roi.min_x, roi.min_y, roi.max_x, roi.max_y, &e);
456  error::handle(e);
457  }
458 
460  {
461  region_of_interest roi {};
462  rs2_error* e = nullptr;
463  rs2_get_region_of_interest(_sensor.get(), &roi.min_x, &roi.min_y, &roi.max_x, &roi.max_y, &e);
464  error::handle(e);
465  return roi;
466  }
467 
468  operator bool() const { return _sensor.get() != nullptr; }
469  };
470 
471  class depth_sensor : public sensor
472  {
473  public:
475  : sensor(s.get())
476  {
477  rs2_error* e = nullptr;
478  if (rs2_is_sensor_extendable_to(_sensor.get(), RS2_EXTENSION_DEPTH_SENSOR, &e) == 0 && !e)
479  {
480  _sensor = nullptr;
481  }
482  error::handle(e);
483  }
484 
488  float get_depth_scale() const
489  {
490  rs2_error* e = nullptr;
491  auto res = rs2_get_depth_scale(_sensor.get(), &e);
492  error::handle(e);
493  return res;
494  }
495 
496  operator bool() const { return _sensor.get() != nullptr; }
497  };
498 
500  {
501  public:
503  {
504  rs2_error* e = nullptr;
505  if (_sensor && rs2_is_sensor_extendable_to(_sensor.get(), RS2_EXTENSION_DEPTH_STEREO_SENSOR, &e) == 0 && !e)
506  {
507  _sensor = nullptr;
508  }
509  error::handle(e);
510  }
511 
515  float get_stereo_baseline() const
516  {
517  rs2_error* e = nullptr;
518  auto res = rs2_get_depth_scale(_sensor.get(), &e);
519  error::handle(e);
520  return res;
521  }
522 
523  operator bool() const { return _sensor.get() != nullptr; }
524  };
525 }
526 #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:27
Definition: rs_sensor.hpp:231
bool operator==(const sensor &lhs, const sensor &rhs)
Definition: rs_sensor.hpp:428
float rs2_get_option(const rs2_options *options, rs2_option option, rs2_error **error)
Definition: rs_frame.hpp:202
Definition: rs_types.hpp:163
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:416
void stop() const
Definition: rs_sensor.hpp:324
Definition: backend.h:378
std::vector< stream_profile > get_stream_profiles() const
Definition: rs_sensor.hpp:349
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:459
void on_notification(rs2_notification *_notification) override
Definition: rs_sensor.hpp:91
Definition: rs_types.hpp:41
Definition: rs_sensor.hpp:471
void start(T callback) const
Definition: rs_sensor.hpp:314
int min_x
Definition: rs_types.hpp:165
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:474
std::function< void(frame_interface *)> on_frame
Definition: streaming.h:103
friend context
Definition: rs_sensor.hpp:414
float min
Definition: rs_types.hpp:157
void rs2_stop(const rs2_sensor *sensor, rs2_error **error)
Definition: api.h:18
options & operator=(const T &dev)
Definition: rs_sensor.hpp:219
depth_stereo_sensor(sensor s)
Definition: rs_sensor.hpp:502
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:254
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:102
const char * get_option_description(rs2_option option) const
Definition: rs_sensor.hpp:135
int max_y
Definition: rs_types.hpp:168
sensor(std::shared_ptr< rs2_sensor > dev)
Definition: rs_sensor.hpp:422
friend roi_sensor
Definition: rs_sensor.hpp:418
void set_region_of_interest(const region_of_interest &roi)
Definition: rs_sensor.hpp:452
int max_x
Definition: rs_types.hpp:167
options(const options &other)
Definition: rs_sensor.hpp:225
rs2_notification_category get_category() const
Definition: rs_sensor.hpp:36
float max
Definition: rs_types.hpp:158
float step
Definition: rs_types.hpp:160
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:240
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:336
std::shared_ptr< rs2_sensor > _sensor
Definition: rs_sensor.hpp:420
Definition: rs_types.h:101
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:417
Definition: rs_types.h:112
Definition: rs_types.hpp:155
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:387
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:407
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:170
Definition: rs_sensor.hpp:85
static void handle(rs2_error *e)
Definition: rs_types.hpp:123
std::string get_serialized_data() const
Definition: rs_sensor.hpp:71
bool is() const
Definition: rs_sensor.hpp:400
void close() const
Definition: rs_sensor.hpp:302
options(rs2_options *o=nullptr)
Definition: rs_sensor.hpp:216
const rs2_stream_profile * get() const
Definition: rs_frame.hpp:79
Definition: rs_types.h:88
void open(const std::vector< stream_profile > &profiles) const
Definition: rs_sensor.hpp:280
float get_stereo_baseline() const
Definition: rs_sensor.hpp:515
Definition: rs_types.h:23
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
Definition: backend.h:375
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:159
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:438
friend device_list
Definition: rs_sensor.hpp:415
rs2_notification_category rs2_get_notification_category(rs2_notification *notification, rs2_error **error)
Definition: api.h:26
std::string get_description() const
Definition: rs_sensor.hpp:44
float get_depth_scale() const
Definition: rs_sensor.hpp:488
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:380
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)
void rs2_set_option(const rs2_options *options, rs2_option option, float value, rs2_error **error)
rs2_log_severity
Severity of the librealsense logger.
Definition: rs_types.h:81
Definition: rs_sensor.hpp:499
sensor & operator=(const std::shared_ptr< rs2_sensor > other)
Definition: rs_sensor.hpp:372
const char * get_info(rs2_camera_info info) const
Definition: rs_sensor.hpp:267
int min_y
Definition: rs_types.hpp:166
struct rs2_frame rs2_frame
Definition: rs_types.h:150
roi_sensor(sensor s)
Definition: rs_sensor.hpp:441