rs_sensor.h
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 
10 #ifndef LIBREALSENSE_RS2_SENSOR_H
11 #define LIBREALSENSE_RS2_SENSOR_H
12 
13 #ifdef __cplusplus
14 extern "C" {
15 #endif
16 
17 #include "rs_types.h"
18 
22 typedef enum rs2_camera_info {
39 const char* rs2_camera_info_to_string(rs2_camera_info info);
40 
42 typedef enum rs2_stream
43 {
55 } rs2_stream;
56 const char* rs2_stream_to_string(rs2_stream stream);
57 
59 typedef enum rs2_format
60 {
92 } rs2_format;
93 const char* rs2_format_to_string(rs2_format format);
94 
96 typedef struct rs2_extrinsics
97 {
98  float rotation[9];
99  float translation[3];
101 
106 void rs2_delete_sensor_list(rs2_sensor_list* info_list);
107 
114 int rs2_get_sensors_count(const rs2_sensor_list* info_list, rs2_error** error);
115 
121 
129 
137 
145 const char* rs2_get_sensor_info(const rs2_sensor* sensor, rs2_camera_info info, rs2_error** error);
146 
153 int rs2_supports_sensor_info(const rs2_sensor* sensor, rs2_camera_info info, rs2_error** error);
154 
163 
170 
177 
184 
194 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);
195 
205 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);
206 
214 
224 
230 void rs2_close(const rs2_sensor* sensor, rs2_error** error);
231 
240 
248 
256 
262 void rs2_stop(const rs2_sensor* sensor, rs2_error** error);
263 
271 
279 
287 
295 
303 
311 
319 
327 
335 
343 
351 
362 void rs2_get_stream_profile_data(const rs2_stream_profile* mode, rs2_stream* stream, rs2_format* format, int* index, int* unique_id, int* framerate, rs2_error** error);
363 
373 
384 
398 
399 
406 
415 
424 
432 
441 
449 
455 
462 void rs2_get_extrinsics(const rs2_stream_profile* from,
463  const rs2_stream_profile* to,
464  rs2_extrinsics* extrin, rs2_error** error);
465 
473  const rs2_stream_profile* to,
474  rs2_extrinsics extrin, rs2_error** error);
475 
486 
494 
503 
512 
520 
526 
535 int rs2_import_localization_map(const rs2_sensor* sensor, const unsigned char* lmap_blob, unsigned int blob_size, rs2_error** error);
536 
544 //void rs2_export_localization_map(const rs2_sensor* sensor, const char* lmap_fname, rs2_error** error);
546 
556 int rs2_set_static_node(const rs2_sensor* sensor, const char* guid, const rs2_vector pos, const rs2_quaternion orient, rs2_error** error);
557 
567 int rs2_get_static_node(const rs2_sensor* sensor, const char* guid, rs2_vector *pos, rs2_quaternion *orient, rs2_error** error);
568 
576 int rs2_remove_static_node(const rs2_sensor* sensor, const char* guid, rs2_error** error);
577 
582 int rs2_load_wheel_odometry_config(const rs2_sensor* sensor, const unsigned char* odometry_config_buf, unsigned int blob_size, rs2_error** error);
583 
590 int rs2_send_wheel_odometry(const rs2_sensor* sensor, char wo_sensor_id, unsigned int frame_num,
591  const rs2_vector translational_velocity, rs2_error** error);
592 
601 
612 
622 void rs2_set_extrinsics(const rs2_sensor* from_sensor, const rs2_stream_profile* from_profile, rs2_sensor* to_sensor, const rs2_stream_profile* to_profile, const rs2_extrinsics* extrinsics, rs2_error** error);
623 
630 void rs2_get_dsm_params( rs2_sensor const * sensor, rs2_dsm_params * p_params_out, rs2_error** error );
631 
640 void rs2_override_dsm_params( rs2_sensor const * sensor, rs2_dsm_params const * p_params, rs2_error** error );
641 
649 
658 
665 
666 #ifdef __cplusplus
667 }
668 #endif
669 #endif // LIBREALSENSE_RS2_SENSOR_H
void rs2_register_extrinsics(const rs2_stream_profile *from, const rs2_stream_profile *to, rs2_extrinsics extrin, rs2_error **error)
Definition: rs.cpp:1125
int rs2_get_sensors_count(const rs2_sensor_list *info_list, rs2_error **error)
Definition: rs.cpp:267
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
const char * rs2_format_to_string(rs2_format format)
Definition: rs.cpp:1263
float rs2_get_depth_scale(rs2_sensor *sensor, rs2_error **error)
Definition: rs.cpp:2312
::realsense_legacy_msgs::extrinsics_< std::allocator< void > > extrinsics
Definition: extrinsics.h:59
void rs2_get_video_stream_resolution(const rs2_stream_profile *mode, int *width, int *height, rs2_error **error)
Definition: rs.cpp:466
void rs2_set_intrinsics(const rs2_sensor *sensor, const rs2_stream_profile *profile, const rs2_intrinsics *intrinsics, rs2_error **error)
Definition: rs.cpp:2677
rs2_sensor * rs2_create_sensor(const rs2_sensor_list *list, int index, rs2_error **error)
Definition: rs.cpp:308
int rs2_get_static_node(const rs2_sensor *sensor, const char *guid, rs2_vector *pos, rs2_quaternion *orient, rs2_error **error)
Definition: rs.cpp:2852
float translation[3]
Definition: rs_sensor.h:99
float rs2_get_max_usable_depth_range(rs2_sensor const *sensor, rs2_error **error)
Definition: rs.cpp:2320
void rs2_get_extrinsics(const rs2_stream_profile *from, const rs2_stream_profile *to, rs2_extrinsics *extrin, rs2_error **error)
Definition: rs.cpp:1110
rs2_device * rs2_create_device_from_sensor(const rs2_sensor *sensor, rs2_error **error)
Definition: rs.cpp:2338
Video DSM (Digital Sync Module) parameters for calibration (same layout as in FW ac_depth_params) Thi...
Definition: rs_types.h:74
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
Definition: rs.cpp:1224
std::function< void(frame_interface *)> on_frame
Definition: streaming.h:164
int rs2_import_localization_map(const rs2_sensor *sensor, const unsigned char *lmap_blob, unsigned int blob_size, rs2_error **error)
Definition: rs.cpp:2815
void rs2_stop(const rs2_sensor *sensor, rs2_error **error)
Definition: rs.cpp:831
void rs2_start_queue(const rs2_sensor *sensor, rs2_frame_queue *queue, rs2_error **error)
Definition: rs.cpp:754
int rs2_stream_profile_is(const rs2_stream_profile *mode, rs2_extension type, rs2_error **error)
Definition: rs.cpp:1504
const char * rs2_get_notification_serialized_data(rs2_notification *notification, rs2_error **error)
Definition: rs.cpp:882
rs2_log_severity rs2_get_notification_severity(rs2_notification *notification, rs2_error **error)
Definition: rs.cpp:868
GLuint GLuint stream
Definition: glext.h:1790
rs2_stream_profile * rs2_clone_stream_profile(const rs2_stream_profile *mode, rs2_stream stream, int index, rs2_format format, rs2_error **error)
Definition: rs.cpp:519
rs2_stream_profile_list * rs2_get_active_streams(rs2_sensor *sensor, rs2_error **error)
Definition: rs.cpp:344
float rotation[9]
Definition: rs_sensor.h:98
GLuint index
rs2_stream_profile_list * rs2_get_stream_profiles(rs2_sensor *sensor, rs2_error **error)
Definition: rs.cpp:327
void rs2_open(rs2_sensor *device, const rs2_stream_profile *profile, rs2_error **error)
Definition: rs.cpp:588
void rs2_set_stream_profile_data(rs2_stream_profile *mode, rs2_stream stream, int index, rs2_format format, rs2_error **error)
Definition: rs.cpp:500
def info(name, value, persistent=False)
Definition: test.py:301
Quaternion used to represent rotation.
Definition: rs_types.h:135
rs2_stream_profile_list * rs2_get_debug_stream_profiles(rs2_sensor *sensor, rs2_error **error)
Definition: rs.cpp:334
GLenum mode
void rs2_get_stream_profile_data(const rs2_stream_profile *mode, rs2_stream *stream, rs2_format *format, int *index, int *unique_id, int *framerate, rs2_error **error)
Definition: rs.cpp:484
void rs2_override_dsm_params(rs2_sensor const *sensor, rs2_dsm_params const *p_params, rs2_error **error)
Definition: rs.cpp:1156
int rs2_is_stream_profile_default(const rs2_stream_profile *mode, rs2_error **error)
Definition: rs.cpp:477
Exposes RealSense structs.
void rs2_start(const rs2_sensor *sensor, rs2_frame_callback_ptr on_frame, void *user, rs2_error **error)
Definition: rs.cpp:744
void rs2_set_notifications_callback(const rs2_sensor *sensor, rs2_notification_callback_ptr on_notification, void *user, rs2_error **error)
Definition: rs.cpp:764
float rs2_get_stereo_baseline(rs2_sensor *sensor, rs2_error **error)
Definition: rs.cpp:2330
int rs2_get_recommended_processing_blocks_count(const rs2_processing_block_list *list, rs2_error **error)
Definition: rs.cpp:2781
void rs2_delete_sensor(rs2_sensor *sensor)
Definition: rs.cpp:320
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
Definition: rs.cpp:1238
rs2_time_t rs2_get_notification_timestamp(rs2_notification *notification, rs2_error **error)
Definition: rs.cpp:861
void rs2_set_extrinsics(const rs2_sensor *from_sensor, const rs2_stream_profile *from_profile, rs2_sensor *to_sensor, const rs2_stream_profile *to_profile, const rs2_extrinsics *extrinsics, rs2_error **error)
Definition: rs.cpp:2698
int rs2_remove_static_node(const rs2_sensor *sensor, const char *guid, rs2_error **error)
Definition: rs.cpp:2879
void rs2_delete_stream_profile(rs2_stream_profile *mode)
Definition: rs.cpp:512
GLint GLsizei GLsizei height
GLint GLint GLsizei GLint GLenum format
const rs2_stream_profile * rs2_get_stream_profile(const rs2_stream_profile_list *list, int index, rs2_error **error)
Definition: rs.cpp:351
void rs2_set_notifications_callback_cpp(const rs2_sensor *sensor, rs2_notifications_callback *callback, rs2_error **error)
Definition: rs.cpp:806
void rs2_reset_sensor_calibration(rs2_sensor const *sensor, rs2_error **error)
Definition: rs.cpp:1166
Definition: api.h:28
def callback(frame)
Definition: t265_stereo.py:91
rs2_format
A stream&#39;s format identifies how binary data is encoded within a frame.
Definition: rs_sensor.h:59
int rs2_supports_sensor_info(const rs2_sensor *sensor, rs2_camera_info info, rs2_error **error)
Definition: rs.cpp:736
void rs2_delete_recommended_processing_blocks(rs2_processing_block_list *list)
Definition: rs.cpp:2788
dictionary intrinsics
Definition: t265_stereo.py:142
rs2_stream
Streams are different types of data provided by RealSense devices.
Definition: rs_sensor.h:42
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.
Definition: rs.cpp:1136
void rs2_set_motion_device_intrinsics(const rs2_sensor *sensor, const rs2_stream_profile *profile, const rs2_motion_device_intrinsic *intrinsics, rs2_error **error)
Definition: rs.cpp:2722
void rs2_get_video_stream_intrinsics(const rs2_stream_profile *mode, rs2_intrinsics *intrinsics, rs2_error **error)
Definition: rs.cpp:374
Cross-stream extrinsics: encodes the topology describing how the different devices are oriented...
Definition: rs_sensor.h:96
void rs2_get_dsm_params(rs2_sensor const *sensor, rs2_dsm_params *p_params_out, rs2_error **error)
Definition: rs.cpp:1146
const char * rs2_camera_info_to_string(rs2_camera_info info)
Definition: rs.cpp:1266
int rs2_is_sensor_extendable_to(const rs2_sensor *sensor, rs2_extension extension, rs2_error **error)
Definition: rs.cpp:1394
3D vector in Euclidean coordinate space
Definition: rs_types.h:129
const char * rs2_stream_to_string(rs2_stream stream)
Definition: rs.cpp:1262
rs2_extension
Specifies advanced interfaces (capabilities) objects may implement.
Definition: rs_types.h:166
rs2_notification_category
Category of the librealsense notification.
Definition: rs_types.h:17
void(* rs2_notification_callback_ptr)(rs2_notification *, void *)
Definition: rs_types.h:293
stream_profile to_profile(const stream_profile_interface *sp)
Definition: src/stream.h:185
GLenum type
void rs2_delete_stream_profiles_list(rs2_stream_profile_list *list)
Definition: rs.cpp:367
void rs2_close(const rs2_sensor *sensor, rs2_error **error)
Definition: rs.cpp:614
GLint GLsizei count
Video stream intrinsics.
Definition: rs_types.h:58
rs2_stream_profile * rs2_clone_video_stream_profile(const rs2_stream_profile *mode, rs2_stream stream, int index, rs2_format format, int width, int height, const rs2_intrinsics *intr, rs2_error **error)
Definition: rs.cpp:533
void rs2_open_multiple(rs2_sensor *device, const rs2_stream_profile **profiles, int count, rs2_error **error)
Definition: rs.cpp:599
void rs2_start_cpp(const rs2_sensor *sensor, rs2_frame_callback *callback, rs2_error **error)
Definition: rs.cpp:798
float rs2_vector::* pos
rs2_notification_category rs2_get_notification_category(rs2_notification *notification, rs2_error **error)
Definition: rs.cpp:875
rs2_processing_block * rs2_get_processing_block(const rs2_processing_block_list *list, int index, rs2_error **error)
Definition: rs.cpp:2772
Motion device intrinsics: scale, bias, and variances.
Definition: rs_types.h:103
struct rs2_extrinsics rs2_extrinsics
Cross-stream extrinsics: encodes the topology describing how the different devices are oriented...
void rs2_delete_sensor_list(rs2_sensor_list *info_list)
Definition: rs.cpp:282
int rs2_set_static_node(const rs2_sensor *sensor, const char *guid, const rs2_vector pos, const rs2_quaternion orient, rs2_error **error)
Definition: rs.cpp:2840
void(* rs2_frame_callback_ptr)(rs2_frame *, void *)
Definition: rs_types.h:296
const rs2_raw_data_buffer * rs2_export_localization_map(const rs2_sensor *sensor, rs2_error **error)
Definition: rs.cpp:2828
float rs2_depth_stereo_frame_get_baseline(const rs2_frame *frame_ref, rs2_error **error)
Definition: rs.cpp:2364
const char * rs2_get_sensor_info(const rs2_sensor *sensor, rs2_camera_info info, rs2_error **error)
Definition: rs.cpp:724
const char * rs2_get_notification_description(rs2_notification *notification, rs2_error **error)
Definition: rs.cpp:854
int rs2_get_stream_profiles_count(const rs2_stream_profile_list *list, rs2_error **error)
Definition: rs.cpp:360
double rs2_time_t
Definition: rs_types.h:300
int rs2_load_wheel_odometry_config(const rs2_sensor *sensor, const unsigned char *odometry_config_buf, unsigned int blob_size, rs2_error **error)
Definition: rs.cpp:2891
rs2_log_severity
Severity of the librealsense logger.
Definition: rs_types.h:153
rs2_processing_block_list * rs2_get_recommended_processing_blocks(rs2_sensor *sensor, rs2_error **error)
Definition: rs.cpp:2765
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)
Definition: rs.cpp:2907
void rs2_get_motion_intrinsics(const rs2_stream_profile *mode, rs2_motion_device_intrinsic *intrinsics, rs2_error **error)
Definition: rs.cpp:455
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.
Definition: rs.cpp:2688
auto device
Definition: pyrs_net.cpp:17
struct rs2_frame rs2_frame
Definition: rs_types.h:261
GLint GLsizei width


librealsense2
Author(s): Sergey Dorodnicov , Doron Hirshberg , Mark Horn , Reagan Lopez , Itay Carpis
autogenerated on Mon May 3 2021 02:47:41