4 #ifndef LIBREALSENSE_RS2_SENSOR_HPP
5 #define LIBREALSENSE_RS2_SENSOR_HPP
75 return _serialized_data;
79 std::string _description;
80 double _timestamp = -1;
83 std::string _serialized_data;
89 T on_notification_function;
130 return is_supported > 0;
151 void open(
const std::vector<stream_profile>& profiles)
const
155 std::vector<const rs2_stream_profile*> profs;
156 profs.reserve(profiles.size());
157 for (
auto& p : profiles)
159 profs.push_back(p.get());
164 static_cast<int>(profiles.size()),
221 std::vector<stream_profile> results{};
224 std::shared_ptr<rs2_stream_profile_list> list(
232 for (
auto i = 0; i < size; i++)
236 results.push_back(profile);
248 std::vector<stream_profile> results{};
251 std::shared_ptr<rs2_stream_profile_list> list(
259 for (
auto i = 0; i < size; i++)
263 results.push_back(profile);
275 std::vector<filter> results{};
278 std::shared_ptr<rs2_processing_block_list> list(
286 for (
auto i = 0; i < size; i++)
288 auto f = std::shared_ptr<rs2_processing_block>(
292 results.push_back(f);
315 operator bool()
const
320 const std::shared_ptr<rs2_sensor>&
get()
const
339 explicit sensor(std::shared_ptr<rs2_sensor> dev)
343 explicit operator std::shared_ptr<rs2_sensor>() {
return _sensor; }
360 return std::make_shared<sensor>(psens);
386 operator bool()
const {
return _sensor.get() !=
nullptr; }
402 operator bool()
const {
return _sensor.get() !=
nullptr; }
418 operator bool()
const {
return _sensor.get() !=
nullptr; }
451 operator bool()
const {
return _sensor.get() !=
nullptr; }
479 operator bool()
const {
return _sensor.get() !=
nullptr; }
507 operator bool()
const {
return _sensor.get() !=
nullptr; }
549 std::vector<uint8_t> results;
563 results = std::vector<uint8_t>(
start,
start + size);
618 operator bool()
const {
return _sensor.get() !=
nullptr; }
662 operator bool()
const {
return _sensor.get() !=
nullptr; }
680 operator bool()
const {
return _sensor.get() !=
nullptr; }
742 operator bool()
const {
return _sensor.get() !=
nullptr; }
Definition: rs_sensor.hpp:667
void override_dsm_params(rs2_dsm_params const ¶ms)
Definition: rs_sensor.hpp:711
calibrated_sensor(sensor s)
Definition: rs_sensor.hpp:669
rs2_dsm_params get_dsm_params() const
Definition: rs_sensor.hpp:699
void override_extrinsics(rs2_extrinsics const &extr)
Definition: rs_sensor.hpp:691
void override_intrinsics(rs2_intrinsics const &intr)
Definition: rs_sensor.hpp:683
void reset_calibration()
Definition: rs_sensor.hpp:720
Definition: rs_sensor.hpp:374
color_sensor(sensor s)
Definition: rs_sensor.hpp:376
Definition: rs_sensor.hpp:455
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
Definition: rs_sensor.hpp:484
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:144
Definition: rs_sensor.hpp:406
fisheye_sensor(sensor s)
Definition: rs_sensor.hpp:408
Definition: rs_frame.hpp:1136
Definition: rs_frame.hpp:337
rs2_sensor * get_sensor()
Definition: rs_frame.hpp:438
Definition: rs_sensor.hpp:729
float get_max_usable_depth_range() const
Definition: rs_sensor.hpp:747
max_usable_range_sensor(sensor s)
Definition: rs_sensor.hpp:731
Definition: rs_sensor.hpp:390
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
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
Definition: rs_options.hpp:12
options & operator=(const options &other)
Definition: rs_options.hpp:134
bool supports(rs2_option option) const
Definition: rs_options.hpp:19
Definition: rs_sensor.hpp:512
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
Definition: rs_sensor.hpp:422
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
sensor & operator=(const std::shared_ptr< rs2_sensor > other)
Definition: rs_sensor.hpp:298
friend device_base
Definition: rs_sensor.hpp:349
std::vector< filter > get_recommended_filters() const
Definition: rs_sensor.hpp:273
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
friend context
Definition: rs_sensor.hpp:346
bool is() const
Definition: rs_sensor.hpp:326
friend roi_sensor
Definition: rs_sensor.hpp:350
const std::shared_ptr< rs2_sensor > & get() const
Definition: rs_sensor.hpp:320
sensor(std::shared_ptr< rs2_sensor > dev)
Definition: rs_sensor.hpp:339
T as() const
Definition: rs_sensor.hpp:333
sensor & operator=(const sensor &other)
Definition: rs_sensor.hpp:306
bool supports(rs2_camera_info info) const
Definition: rs_sensor.hpp:125
void stop() const
Definition: rs_sensor.hpp:195
const char * get_info(rs2_camera_info info) const
Definition: rs_sensor.hpp:138
std::vector< stream_profile > get_stream_profiles() const
Definition: rs_sensor.hpp:219
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
friend device
Definition: rs_sensor.hpp:348
std::vector< stream_profile > get_active_streams() const
Definition: rs_sensor.hpp:246
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
Definition: rs_sensor.hpp:623
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_context.hpp:12
bool operator==(const sensor &lhs, const sensor &rhs)
Definition: rs_sensor.hpp:363
std::shared_ptr< sensor > sensor_from_frame(frame f)
Definition: rs_sensor.hpp:357
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)
void rs2_override_extrinsics(const rs2_sensor *sensor, const rs2_extrinsics *extrinsics, rs2_error **error)
Override extrinsics of a given sensor that supports calibrated_sensor.
int rs2_get_recommended_processing_blocks_count(const rs2_processing_block_list *list, rs2_error **error)
void rs2_override_intrinsics(const rs2_sensor *sensor, const rs2_intrinsics *intrinsics, rs2_error **error)
Override intrinsics of a given sensor that supports calibrated_sensor.
float rs2_get_depth_scale(rs2_sensor *sensor, rs2_error **error)
const char * rs2_get_notification_serialized_data(rs2_notification *notification, 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_processing_block_list * rs2_get_recommended_processing_blocks(rs2_sensor *sensor, rs2_error **error)
rs2_time_t rs2_get_notification_timestamp(rs2_notification *notification, rs2_error **error)
const rs2_stream_profile * rs2_get_stream_profile(const rs2_stream_profile_list *list, int index, 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_get_dsm_params(rs2_sensor const *sensor, rs2_dsm_params *p_params_out, 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_notification_description(rs2_notification *notification, 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)
int rs2_load_wheel_odometry_config(const rs2_sensor *sensor, const unsigned char *odometry_config_buf, unsigned int blob_size, rs2_error **error)
void rs2_reset_sensor_calibration(rs2_sensor const *sensor, rs2_error **error)
rs2_processing_block * rs2_get_processing_block(const rs2_processing_block_list *list, int index, 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)
rs2_log_severity rs2_get_notification_severity(rs2_notification *notification, rs2_error **error)
const rs2_raw_data_buffer * rs2_export_localization_map(const rs2_sensor *sensor, rs2_error **error)
const char * rs2_get_sensor_info(const rs2_sensor *sensor, rs2_camera_info info, 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)
void rs2_set_notifications_callback_cpp(const rs2_sensor *sensor, rs2_notifications_callback *callback, 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
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)
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)
rs2_stream_profile_list * rs2_get_active_streams(rs2_sensor *sensor, rs2_error **error)
rs2_stream_profile_list * rs2_get_stream_profiles(rs2_sensor *sensor, rs2_error **error)
void rs2_override_dsm_params(rs2_sensor const *sensor, rs2_dsm_params const *p_params, 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:147
@ RS2_LOG_SEVERITY_COUNT
Definition: rs_types.h:154
rs2_notification_category
Category of the librealsense notification.
Definition: rs_types.h:17
@ RS2_NOTIFICATION_CATEGORY_COUNT
Definition: rs_types.h:25
@ RS2_EXTENSION_FISHEYE_SENSOR
Definition: rs_types.h:206
@ RS2_EXTENSION_POSE_SENSOR
Definition: rs_types.h:196
@ RS2_EXTENSION_DEPTH_SENSOR
Definition: rs_types.h:169
@ RS2_EXTENSION_ROI
Definition: rs_types.h:168
@ RS2_EXTENSION_WHEEL_ODOMETER
Definition: rs_types.h:197
@ RS2_EXTENSION_COLOR_SENSOR
Definition: rs_types.h:204
@ RS2_EXTENSION_MAX_USABLE_RANGE_SENSOR
Definition: rs_types.h:215
@ RS2_EXTENSION_CALIBRATED_SENSOR
Definition: rs_types.h:212
@ RS2_EXTENSION_DEPTH_STEREO_SENSOR
Definition: rs_types.h:179
@ RS2_EXTENSION_MOTION_SENSOR
Definition: rs_types.h:205
struct rs2_notification rs2_notification
Definition: rs_types.h:278
struct rs2_error rs2_error
Definition: rs_types.h:250
struct rs2_raw_data_buffer rs2_raw_data_buffer
Definition: rs_types.h:252
struct rs2_options rs2_options
Definition: rs_types.h:275
Definition: rs_types.hpp:185
int min_x
Definition: rs_types.hpp:186
int max_y
Definition: rs_types.hpp:189
int max_x
Definition: rs_types.hpp:188
int min_y
Definition: rs_types.hpp:187
Video DSM (Digital Sync Module) parameters for calibration (same layout as in FW ac_depth_params) Thi...
Definition: rs_types.h:74
Cross-stream extrinsics: encodes the topology describing how the different devices are oriented.
Definition: rs_sensor.h:96
Video stream intrinsics.
Definition: rs_types.h:59
Definition: rs_types.hpp:40
Quaternion used to represent rotation
Definition: rs_types.h:130
3D vector in Euclidean coordinate space
Definition: rs_types.h:124