Intel® RealSense™ Cross Platform API
Intel Realsense Cross-platform API
Loading...
Searching...
No Matches
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#include "rs_processing.hpp"
10#include "rs_options.hpp"
11namespace rs2
12{
13
15 {
16 public:
18 {
19 rs2_error* e = nullptr;
20 _description = rs2_get_notification_description(nt, &e);
22 _timestamp = rs2_get_notification_timestamp(nt, &e);
24 _severity = rs2_get_notification_severity(nt, &e);
26 _category = rs2_get_notification_category(nt, &e);
28 _serialized_data = rs2_get_notification_serialized_data(nt, &e);
30 }
31
32 notification() = default;
33
39 {
40 return _category;
41 }
42
46 std::string get_description() const
47 {
48 return _description;
49 }
50
55 double get_timestamp() const
56 {
57 return _timestamp;
58 }
59
65 {
66 return _severity;
67 }
68
73 std::string get_serialized_data() const
74 {
75 return _serialized_data;
76 }
77
78 private:
79 std::string _description;
80 double _timestamp = -1;
83 std::string _serialized_data;
84 };
85
86 template<class T>
88 {
89 T on_notification_function;
90 public:
91 explicit notifications_callback(T on_notification) : on_notification_function(on_notification) {}
92
93 void on_notification(rs2_notification* _notification) override
94 {
95 on_notification_function(notification{ _notification });
96 }
97
98 void release() override { delete this; }
99 };
100
101
102 class sensor : public options
103 {
104 public:
105
106 using options::supports;
111 void open(const stream_profile& profile) const
112 {
113 rs2_error* e = nullptr;
114 rs2_open(_sensor.get(),
115 profile.get(),
116 &e);
117 error::handle(e);
118 }
119
125 bool supports(rs2_camera_info info) const
126 {
127 rs2_error* e = nullptr;
128 auto is_supported = rs2_supports_sensor_info(_sensor.get(), info, &e);
129 error::handle(e);
130 return is_supported > 0;
131 }
132
138 const char* get_info(rs2_camera_info info) const
139 {
140 rs2_error* e = nullptr;
141 auto result = rs2_get_sensor_info(_sensor.get(), info, &e);
142 error::handle(e);
143 return result;
144 }
145
151 void open(const std::vector<stream_profile>& profiles) const
152 {
153 rs2_error* e = nullptr;
154
155 std::vector<const rs2_stream_profile*> profs;
156 profs.reserve(profiles.size());
157 for (auto& p : profiles)
158 {
159 profs.push_back(p.get());
160 }
161
163 profs.data(),
164 static_cast<int>(profiles.size()),
165 &e);
166 error::handle(e);
167 }
168
173 void close() const
174 {
175 rs2_error* e = nullptr;
176 rs2_close(_sensor.get(), &e);
177 error::handle(e);
178 }
179
184 template<class T>
185 void start(T callback) const
186 {
187 rs2_error* e = nullptr;
188 rs2_start_cpp(_sensor.get(), new frame_callback<T>(std::move(callback)), &e);
189 error::handle(e);
190 }
191
195 void stop() const
196 {
197 rs2_error* e = nullptr;
198 rs2_stop(_sensor.get(), &e);
199 error::handle(e);
200 }
201
206 template<class T>
207 void set_notifications_callback(T callback) const
208 {
209 rs2_error* e = nullptr;
211 new notifications_callback<T>(std::move(callback)), &e);
212 error::handle(e);
213 }
214
219 std::vector<stream_profile> get_stream_profiles() const
220 {
221 std::vector<stream_profile> results;
222
223 rs2_error* e = nullptr;
224 std::shared_ptr<rs2_stream_profile_list> list(
227 error::handle(e);
228
229 auto size = rs2_get_stream_profiles_count(list.get(), &e);
230 error::handle(e);
231
232 for (auto i = 0; i < size; i++)
233 {
234 stream_profile profile(rs2_get_stream_profile(list.get(), i, &e));
235 error::handle(e);
236 results.push_back(profile);
237 }
238
239 return results;
240 }
241
246 std::vector<stream_profile> get_active_streams() const
247 {
248 std::vector<stream_profile> results;
249
250 rs2_error* e = nullptr;
251 std::shared_ptr<rs2_stream_profile_list> list(
254 error::handle(e);
255
256 auto size = rs2_get_stream_profiles_count(list.get(), &e);
257 error::handle(e);
258
259 for (auto i = 0; i < size; i++)
260 {
261 stream_profile profile(rs2_get_stream_profile(list.get(), i, &e));
262 error::handle(e);
263 results.push_back(profile);
264 }
265
266 return results;
267 }
268
273 std::vector<filter> get_recommended_filters() const
274 {
275 std::vector<filter> results;
276
277 rs2_error* e = nullptr;
278 std::shared_ptr<rs2_processing_block_list> list(
281 error::handle(e);
282
283 auto size = rs2_get_recommended_processing_blocks_count(list.get(), &e);
284 error::handle(e);
285
286 for (auto i = 0; i < size; i++)
287 {
288 auto f = std::shared_ptr<rs2_processing_block>(
289 rs2_get_processing_block(list.get(), i, &e),
291 error::handle(e);
292 results.push_back(f);
293 }
294
295 return results;
296 }
297
298 sensor& operator=(const std::shared_ptr<rs2_sensor> other)
299 {
300 options::operator=(other);
301 _sensor.reset();
302 _sensor = other;
303 return *this;
304 }
305
306 sensor& operator=(const sensor& other)
307 {
308 *this = nullptr;
310 _sensor = other._sensor;
311 return *this;
312 }
313 sensor() : _sensor(nullptr) {}
314
315 operator bool() const
316 {
317 return _sensor != nullptr;
318 }
319
320 const std::shared_ptr<rs2_sensor>& get() const
321 {
322 return _sensor;
323 }
324
325 template<class T>
326 bool is() const
327 {
328 T extension(*this);
329 return extension;
330 }
331
332 template<class T>
333 T as() const
334 {
335 T extension(*this);
336 return extension;
337 }
338
339 explicit sensor(std::shared_ptr<rs2_sensor> dev)
340 :options((rs2_options*)dev.get()), _sensor(dev)
341 {
342 }
343 explicit operator std::shared_ptr<rs2_sensor>() { return _sensor; }
344
345 protected:
346 friend context;
348 friend device;
351
352 std::shared_ptr<rs2_sensor> _sensor;
353
354
355 };
356
357 inline std::shared_ptr<sensor> sensor_from_frame(frame f)
358 {
359 std::shared_ptr<rs2_sensor> psens(f.get_sensor(), rs2_delete_sensor);
360 return std::make_shared<sensor>(psens);
361 }
362
363 inline bool operator==(const sensor& lhs, const sensor& rhs)
364 {
367 return false;
368
369 return std::string(lhs.get_info(RS2_CAMERA_INFO_NAME)) == rhs.get_info(RS2_CAMERA_INFO_NAME)
371 }
372
373 class color_sensor : public sensor
374 {
375 public:
377 : sensor(s.get())
378 {
379 rs2_error* e = nullptr;
381 {
382 _sensor.reset();
383 }
384 error::handle(e);
385 }
386 operator bool() const { return _sensor.get() != nullptr; }
387 };
388
389 class motion_sensor : public sensor
390 {
391 public:
393 : sensor(s.get())
394 {
395 rs2_error* e = nullptr;
397 {
398 _sensor.reset();
399 }
400 error::handle(e);
401 }
402 operator bool() const { return _sensor.get() != nullptr; }
403 };
404
405 class fisheye_sensor : public sensor
406 {
407 public:
409 : sensor(s.get())
410 {
411 rs2_error* e = nullptr;
413 {
414 _sensor.reset();
415 }
416 error::handle(e);
417 }
418 operator bool() const { return _sensor.get() != nullptr; }
419 };
420
421 class roi_sensor : public sensor
422 {
423 public:
425 : sensor(s.get())
426 {
427 rs2_error* e = nullptr;
428 if(rs2_is_sensor_extendable_to(_sensor.get(), RS2_EXTENSION_ROI, &e) == 0 && !e)
429 {
430 _sensor.reset();
431 }
432 error::handle(e);
433 }
434
436 {
437 rs2_error* e = nullptr;
438 rs2_set_region_of_interest(_sensor.get(), roi.min_x, roi.min_y, roi.max_x, roi.max_y, &e);
439 error::handle(e);
440 }
441
443 {
444 region_of_interest roi {};
445 rs2_error* e = nullptr;
446 rs2_get_region_of_interest(_sensor.get(), &roi.min_x, &roi.min_y, &roi.max_x, &roi.max_y, &e);
447 error::handle(e);
448 return roi;
449 }
450
451 operator bool() const { return _sensor.get() != nullptr; }
452 };
453
454 class depth_sensor : public sensor
455 {
456 public:
458 : sensor(s.get())
459 {
460 rs2_error* e = nullptr;
462 {
463 _sensor.reset();
464 }
465 error::handle(e);
466 }
467
471 float get_depth_scale() const
472 {
473 rs2_error* e = nullptr;
474 auto res = rs2_get_depth_scale(_sensor.get(), &e);
475 error::handle(e);
476 return res;
477 }
478
479 operator bool() const { return _sensor.get() != nullptr; }
480 explicit depth_sensor(std::shared_ptr<rs2_sensor> dev) : depth_sensor(sensor(dev)) {}
481 };
482
484 {
485 public:
487 {
488 rs2_error* e = nullptr;
490 {
491 _sensor.reset();
492 }
493 error::handle(e);
494 }
495
500 {
501 rs2_error* e = nullptr;
502 auto res = rs2_get_stereo_baseline(_sensor.get(), &e);
503 error::handle(e);
504 return res;
505 }
506
507 operator bool() const { return _sensor.get() != nullptr; }
508 };
509
510
511 class pose_sensor : public sensor
512 {
513 public:
515 : sensor(s.get())
516 {
517 rs2_error* e = nullptr;
519 {
520 _sensor.reset();
521 }
522 error::handle(e);
523 }
524
534 bool import_localization_map(const std::vector<uint8_t>& lmap_buf) const
535 {
536 rs2_error* e = nullptr;
537 auto res = rs2_import_localization_map(_sensor.get(), lmap_buf.data(), uint32_t(lmap_buf.size()), &e);
538 error::handle(e);
539 return !!res;
540 }
541
547 std::vector<uint8_t> export_localization_map() const
548 {
549 std::vector<uint8_t> results;
550 rs2_error* e = nullptr;
552 error::handle(e);
553 std::shared_ptr<const rs2_raw_data_buffer> loc_map(map, rs2_delete_raw_data);
554
555 auto start = rs2_get_raw_data(loc_map.get(), &e);
556 error::handle(e);
557
558 if (start)
559 {
560 auto size = rs2_get_raw_data_size(loc_map.get(), &e);
561 error::handle(e);
562
563 results = std::vector<uint8_t>(start, start + size);
564 }
565 return results;
566 }
567
578 bool set_static_node(const std::string& guid, const rs2_vector& pos, const rs2_quaternion& orient) const
579 {
580 rs2_error* e = nullptr;
581 auto res = rs2_set_static_node(_sensor.get(), guid.c_str(), pos, orient, &e);
582 error::handle(e);
583 return !!res;
584 }
585
586
598 bool get_static_node(const std::string& guid, rs2_vector& pos, rs2_quaternion& orient) const
599 {
600 rs2_error* e = nullptr;
601 auto res = rs2_get_static_node(_sensor.get(), guid.c_str(), &pos, &orient, &e);
602 error::handle(e);
603 return !!res;
604 }
605
610 bool remove_static_node(const std::string& guid) const
611 {
612 rs2_error* e = nullptr;
613 auto res = rs2_remove_static_node(_sensor.get(), guid.c_str(), &e);
614 error::handle(e);
615 return !!res;
616 }
617
618 operator bool() const { return _sensor.get() != nullptr; }
619 explicit pose_sensor(std::shared_ptr<rs2_sensor> dev) : pose_sensor(sensor(dev)) {}
620 };
621
622 class wheel_odometer : public sensor
623 {
624 public:
626 : sensor(s.get())
627 {
628 rs2_error* e = nullptr;
630 {
631 _sensor.reset();
632 }
633 error::handle(e);
634 }
635
640 bool load_wheel_odometery_config(const std::vector<uint8_t>& odometry_config_buf) const
641 {
642 rs2_error* e = nullptr;
643 auto res = rs2_load_wheel_odometry_config(_sensor.get(), odometry_config_buf.data(), uint32_t(odometry_config_buf.size()), &e);
644 error::handle(e);
645 return !!res;
646 }
647
654 bool send_wheel_odometry(uint8_t wo_sensor_id, uint32_t frame_num, const rs2_vector& translational_velocity)
655 {
656 rs2_error* e = nullptr;
657 auto res = rs2_send_wheel_odometry(_sensor.get(), wo_sensor_id, frame_num, translational_velocity, &e);
658 error::handle(e);
659 return !!res;
660 }
661
662 operator bool() const { return _sensor.get() != nullptr; }
663 explicit wheel_odometer(std::shared_ptr<rs2_sensor> dev) : wheel_odometer(sensor(dev)) {}
664 };
665
667 {
668 public:
670 : sensor(s.get())
671 {
672 rs2_error* e = nullptr;
674 {
675 _sensor.reset();
676 }
677 error::handle(e);
678 }
679
680 operator bool() const { return _sensor.get() != nullptr; }
681
686 {
687 rs2_error* e = nullptr;
688 auto res = rs2_get_max_usable_depth_range(_sensor.get(), &e);
689 error::handle(e);
690 return res;
691 }
692 };
693
695 {
696 public:
698 : sensor( s.get() )
699 {
700 rs2_error * e = nullptr;
702 {
703 _sensor.reset();
704 }
705 error::handle( e );
706 }
707
708 operator bool() const { return _sensor.get() != nullptr; }
709
714 std::vector< stream_profile > get_debug_stream_profiles() const
715 {
716 std::vector< stream_profile > results;
717
718 rs2_error * e = nullptr;
719 std::shared_ptr< rs2_stream_profile_list > list(
722 error::handle( e );
723
724 auto size = rs2_get_stream_profiles_count( list.get(), &e );
725 error::handle( e );
726
727 for( auto i = 0; i < size; i++ )
728 {
729 stream_profile profile( rs2_get_stream_profile( list.get(), i, &e ) );
730 error::handle( e );
731 results.push_back( profile );
732 }
733
734 return results;
735 }
736 };
737}
738#endif // LIBREALSENSE_RS2_SENSOR_HPP
color_sensor(sensor s)
Definition rs_sensor.hpp:376
debug_stream_sensor(sensor s)
Definition rs_sensor.hpp:697
std::vector< stream_profile > get_debug_stream_profiles() const
Definition rs_sensor.hpp:714
depth_sensor(std::shared_ptr< rs2_sensor > dev)
Definition rs_sensor.hpp:480
depth_sensor(sensor s)
Definition rs_sensor.hpp:457
float get_depth_scale() const
Definition rs_sensor.hpp:471
float get_stereo_baseline() const
Definition rs_sensor.hpp:499
depth_stereo_sensor(sensor s)
Definition rs_sensor.hpp:486
static void handle(rs2_error *e)
Definition rs_types.hpp:162
fisheye_sensor(sensor s)
Definition rs_sensor.hpp:408
Definition rs_frame.hpp:1181
Definition rs_frame.hpp:346
rs2_sensor * get_sensor()
Definition rs_frame.hpp:447
float get_max_usable_depth_range() const
Definition rs_sensor.hpp:685
max_usable_range_sensor(sensor s)
Definition rs_sensor.hpp:669
motion_sensor(sensor s)
Definition rs_sensor.hpp:392
Definition rs_sensor.hpp:15
std::string get_serialized_data() const
Definition rs_sensor.hpp:73
notification(rs2_notification *nt)
Definition rs_sensor.hpp:17
rs2_notification_category get_category() const
Definition rs_sensor.hpp:38
rs2_log_severity get_severity() const
Definition rs_sensor.hpp:64
double get_timestamp() const
Definition rs_sensor.hpp:55
notification()=default
std::string get_description() const
Definition rs_sensor.hpp:46
Definition rs_sensor.hpp:88
void on_notification(rs2_notification *_notification) override
Definition rs_sensor.hpp:93
notifications_callback(T on_notification)
Definition rs_sensor.hpp:91
void release() override
Definition rs_sensor.hpp:98
options & operator=(const options &other)
Definition rs_options.hpp:323
options(const options &other)
Definition rs_options.hpp:329
bool supports(rs2_option option) const
Definition rs_options.hpp:163
std::vector< uint8_t > export_localization_map() const
Definition rs_sensor.hpp:547
bool import_localization_map(const std::vector< uint8_t > &lmap_buf) const
Definition rs_sensor.hpp:534
bool get_static_node(const std::string &guid, rs2_vector &pos, rs2_quaternion &orient) const
Definition rs_sensor.hpp:598
pose_sensor(std::shared_ptr< rs2_sensor > dev)
Definition rs_sensor.hpp:619
pose_sensor(sensor s)
Definition rs_sensor.hpp:514
bool set_static_node(const std::string &guid, const rs2_vector &pos, const rs2_quaternion &orient) const
Definition rs_sensor.hpp:578
bool remove_static_node(const std::string &guid) const
Definition rs_sensor.hpp:610
void set_region_of_interest(const region_of_interest &roi)
Definition rs_sensor.hpp:435
region_of_interest get_region_of_interest() const
Definition rs_sensor.hpp:442
roi_sensor(sensor s)
Definition rs_sensor.hpp:424
Definition rs_sensor.hpp:103
friend device_base
Definition rs_sensor.hpp:349
void open(const std::vector< stream_profile > &profiles) const
Definition rs_sensor.hpp:151
sensor()
Definition rs_sensor.hpp:313
std::shared_ptr< rs2_sensor > _sensor
Definition rs_sensor.hpp:352
const char * get_info(rs2_camera_info info) const
Definition rs_sensor.hpp:138
friend context
Definition rs_sensor.hpp:346
std::vector< stream_profile > get_stream_profiles() const
Definition rs_sensor.hpp:219
sensor & operator=(const sensor &other)
Definition rs_sensor.hpp:306
bool is() const
Definition rs_sensor.hpp:326
friend roi_sensor
Definition rs_sensor.hpp:350
sensor(std::shared_ptr< rs2_sensor > dev)
Definition rs_sensor.hpp:339
T as() const
Definition rs_sensor.hpp:333
bool supports(rs2_camera_info info) const
Definition rs_sensor.hpp:125
void stop() const
Definition rs_sensor.hpp:195
std::vector< filter > get_recommended_filters() const
Definition rs_sensor.hpp:273
std::vector< stream_profile > get_active_streams() const
Definition rs_sensor.hpp:246
const std::shared_ptr< rs2_sensor > & get() const
Definition rs_sensor.hpp:320
friend device_list
Definition rs_sensor.hpp:347
void start(T callback) const
Definition rs_sensor.hpp:185
void set_notifications_callback(T callback) const
Definition rs_sensor.hpp:207
sensor & operator=(const std::shared_ptr< rs2_sensor > other)
Definition rs_sensor.hpp:298
friend device
Definition rs_sensor.hpp:348
void open(const stream_profile &profile) const
Definition rs_sensor.hpp:111
void close() const
Definition rs_sensor.hpp:173
Definition rs_frame.hpp:23
const rs2_stream_profile * get() const
Definition rs_frame.hpp:137
wheel_odometer(sensor s)
Definition rs_sensor.hpp:625
wheel_odometer(std::shared_ptr< rs2_sensor > dev)
Definition rs_sensor.hpp:663
bool load_wheel_odometery_config(const std::vector< uint8_t > &odometry_config_buf) const
Definition rs_sensor.hpp:640
bool send_wheel_odometry(uint8_t wo_sensor_id, uint32_t frame_num, const rs2_vector &translational_velocity)
Definition rs_sensor.hpp:654
Definition rs_processing_gl.hpp:13
std::shared_ptr< sensor > sensor_from_frame(frame f)
Definition rs_sensor.hpp:357
bool operator==(const sensor &lhs, const sensor &rhs)
Definition rs_sensor.hpp:363
const unsigned char * rs2_get_raw_data(const rs2_raw_data_buffer *buffer, rs2_error **error)
int rs2_get_raw_data_size(const rs2_raw_data_buffer *buffer, rs2_error **error)
void rs2_delete_raw_data(const rs2_raw_data_buffer *buffer)
void rs2_delete_processing_block(rs2_processing_block *block)
rs2_processing_block_list * rs2_get_recommended_processing_blocks(rs2_sensor *sensor, rs2_error **error)
int rs2_get_recommended_processing_blocks_count(const rs2_processing_block_list *list, rs2_error **error)
float rs2_get_depth_scale(rs2_sensor *sensor, rs2_error **error)
int rs2_set_static_node(const rs2_sensor *sensor, const char *guid, const rs2_vector pos, const rs2_quaternion orient, rs2_error **error)
rs2_time_t rs2_get_notification_timestamp(rs2_notification *notification, rs2_error **error)
int rs2_supports_sensor_info(const rs2_sensor *sensor, rs2_camera_info info, rs2_error **error)
rs2_notification_category rs2_get_notification_category(rs2_notification *notification, rs2_error **error)
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
const char * rs2_get_sensor_info(const rs2_sensor *sensor, rs2_camera_info info, rs2_error **error)
void rs2_stop(const rs2_sensor *sensor, rs2_error **error)
void rs2_start_cpp(const rs2_sensor *sensor, rs2_frame_callback *callback, rs2_error **error)
const char * rs2_get_notification_serialized_data(rs2_notification *notification, rs2_error **error)
int rs2_load_wheel_odometry_config(const rs2_sensor *sensor, const unsigned char *odometry_config_buf, unsigned int blob_size, rs2_error **error)
const rs2_raw_data_buffer * rs2_export_localization_map(const rs2_sensor *sensor, rs2_error **error)
int rs2_send_wheel_odometry(const rs2_sensor *sensor, char wo_sensor_id, unsigned int frame_num, const rs2_vector translational_velocity, rs2_error **error)
const rs2_stream_profile * rs2_get_stream_profile(const rs2_stream_profile_list *list, int index, rs2_error **error)
rs2_log_severity rs2_get_notification_severity(rs2_notification *notification, rs2_error **error)
const char * rs2_get_notification_description(rs2_notification *notification, rs2_error **error)
int rs2_is_sensor_extendable_to(const rs2_sensor *sensor, rs2_extension extension, rs2_error **error)
void rs2_delete_sensor(rs2_sensor *sensor)
void rs2_close(const rs2_sensor *sensor, rs2_error **error)
rs2_stream_profile_list * rs2_get_debug_stream_profiles(rs2_sensor *sensor, rs2_error **error)
void rs2_set_notifications_callback_cpp(const rs2_sensor *sensor, rs2_notifications_callback *callback, rs2_error **error)
rs2_stream_profile_list * rs2_get_active_streams(rs2_sensor *sensor, rs2_error **error)
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
@ RS2_CAMERA_INFO_SERIAL_NUMBER
Definition rs_sensor.h:24
@ RS2_CAMERA_INFO_NAME
Definition rs_sensor.h:23
rs2_stream_profile_list * rs2_get_stream_profiles(rs2_sensor *sensor, rs2_error **error)
float rs2_get_max_usable_depth_range(rs2_sensor const *sensor, rs2_error **error)
float rs2_get_stereo_baseline(rs2_sensor *sensor, rs2_error **error)
rs2_processing_block * rs2_get_processing_block(const rs2_processing_block_list *list, int index, rs2_error **error)
void rs2_delete_stream_profiles_list(rs2_stream_profile_list *list)
int rs2_get_stream_profiles_count(const rs2_stream_profile_list *list, rs2_error **error)
int rs2_import_localization_map(const rs2_sensor *sensor, const unsigned char *lmap_blob, unsigned int blob_size, rs2_error **error)
void rs2_open_multiple(rs2_sensor *device, const rs2_stream_profile **profiles, int count, rs2_error **error)
int rs2_remove_static_node(const rs2_sensor *sensor, const char *guid, rs2_error **error)
void rs2_delete_recommended_processing_blocks(rs2_processing_block_list *list)
void rs2_open(rs2_sensor *device, const rs2_stream_profile *profile, rs2_error **error)
int rs2_get_static_node(const rs2_sensor *sensor, const char *guid, rs2_vector *pos, rs2_quaternion *orient, rs2_error **error)
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_log_severity
Severity of the librealsense logger.
Definition rs_types.h:123
@ RS2_LOG_SEVERITY_COUNT
Definition rs_types.h:130
rs2_notification_category
Category of the librealsense notification.
Definition rs_types.h:19
@ RS2_NOTIFICATION_CATEGORY_COUNT
Definition rs_types.h:27
@ RS2_EXTENSION_FISHEYE_SENSOR
Definition rs_types.h:183
@ RS2_EXTENSION_POSE_SENSOR
Definition rs_types.h:173
@ RS2_EXTENSION_DEPTH_SENSOR
Definition rs_types.h:145
@ RS2_EXTENSION_ROI
Definition rs_types.h:144
@ RS2_EXTENSION_DEBUG_STREAM_SENSOR
Definition rs_types.h:193
@ RS2_EXTENSION_WHEEL_ODOMETER
Definition rs_types.h:174
@ RS2_EXTENSION_COLOR_SENSOR
Definition rs_types.h:181
@ RS2_EXTENSION_MAX_USABLE_RANGE_SENSOR
Definition rs_types.h:192
@ RS2_EXTENSION_DEPTH_STEREO_SENSOR
Definition rs_types.h:155
@ RS2_EXTENSION_MOTION_SENSOR
Definition rs_types.h:182
struct rs2_notification rs2_notification
Definition rs_types.h:259
struct rs2_error rs2_error
Definition rs_types.h:230
struct rs2_raw_data_buffer rs2_raw_data_buffer
Definition rs_types.h:232
struct rs2_options rs2_options
Definition rs_types.h:255
Definition rs_types.hpp:203
int min_x
Definition rs_types.hpp:204
int max_y
Definition rs_types.hpp:207
int max_x
Definition rs_types.hpp:206
int min_y
Definition rs_types.hpp:205
Definition rs_types.hpp:43
Quaternion used to represent rotation.
Definition rs_types.h:106
3D vector in Euclidean coordinate space
Definition rs_types.h:100