10 #ifndef LIBREALSENSE_RS2_SENSOR_H 11 #define LIBREALSENSE_RS2_SENSOR_H 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)
int rs2_get_sensors_count(const rs2_sensor_list *info_list, rs2_error **error)
rs2_camera_info
Read-only strings that can be queried from the device. Not all information attributes are available o...
const char * rs2_format_to_string(rs2_format format)
float rs2_get_depth_scale(rs2_sensor *sensor, rs2_error **error)
::realsense_legacy_msgs::extrinsics_< std::allocator< void > > extrinsics
void rs2_get_video_stream_resolution(const rs2_stream_profile *mode, int *width, int *height, rs2_error **error)
void rs2_set_intrinsics(const rs2_sensor *sensor, const rs2_stream_profile *profile, const rs2_intrinsics *intrinsics, rs2_error **error)
rs2_sensor * rs2_create_sensor(const rs2_sensor_list *list, int index, rs2_error **error)
int rs2_get_static_node(const rs2_sensor *sensor, const char *guid, rs2_vector *pos, rs2_quaternion *orient, rs2_error **error)
float rs2_get_max_usable_depth_range(rs2_sensor const *sensor, rs2_error **error)
void rs2_get_extrinsics(const rs2_stream_profile *from, const rs2_stream_profile *to, rs2_extrinsics *extrin, rs2_error **error)
rs2_device * rs2_create_device_from_sensor(const rs2_sensor *sensor, rs2_error **error)
Video DSM (Digital Sync Module) parameters for calibration (same layout as in FW ac_depth_params) Thi...
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
std::function< void(frame_interface *)> on_frame
int rs2_import_localization_map(const rs2_sensor *sensor, const unsigned char *lmap_blob, unsigned int blob_size, rs2_error **error)
void rs2_stop(const rs2_sensor *sensor, rs2_error **error)
void rs2_start_queue(const rs2_sensor *sensor, rs2_frame_queue *queue, rs2_error **error)
int rs2_stream_profile_is(const rs2_stream_profile *mode, rs2_extension type, rs2_error **error)
const char * rs2_get_notification_serialized_data(rs2_notification *notification, rs2_error **error)
rs2_log_severity rs2_get_notification_severity(rs2_notification *notification, rs2_error **error)
rs2_stream_profile * rs2_clone_stream_profile(const rs2_stream_profile *mode, rs2_stream stream, int index, rs2_format format, 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_open(rs2_sensor *device, const rs2_stream_profile *profile, rs2_error **error)
void rs2_set_stream_profile_data(rs2_stream_profile *mode, rs2_stream stream, int index, rs2_format format, rs2_error **error)
def info(name, value, persistent=False)
Quaternion used to represent rotation.
rs2_stream_profile_list * rs2_get_debug_stream_profiles(rs2_sensor *sensor, rs2_error **error)
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)
void rs2_override_dsm_params(rs2_sensor const *sensor, rs2_dsm_params const *p_params, rs2_error **error)
int rs2_is_stream_profile_default(const rs2_stream_profile *mode, rs2_error **error)
Exposes RealSense structs.
void rs2_start(const rs2_sensor *sensor, rs2_frame_callback_ptr on_frame, void *user, rs2_error **error)
void rs2_set_notifications_callback(const rs2_sensor *sensor, rs2_notification_callback_ptr on_notification, void *user, rs2_error **error)
float rs2_get_stereo_baseline(rs2_sensor *sensor, rs2_error **error)
int rs2_get_recommended_processing_blocks_count(const rs2_processing_block_list *list, rs2_error **error)
void rs2_delete_sensor(rs2_sensor *sensor)
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)
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)
int rs2_remove_static_node(const rs2_sensor *sensor, const char *guid, rs2_error **error)
void rs2_delete_stream_profile(rs2_stream_profile *mode)
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)
void rs2_set_notifications_callback_cpp(const rs2_sensor *sensor, rs2_notifications_callback *callback, rs2_error **error)
void rs2_reset_sensor_calibration(rs2_sensor const *sensor, rs2_error **error)
rs2_format
A stream's format identifies how binary data is encoded within a frame.
int rs2_supports_sensor_info(const rs2_sensor *sensor, rs2_camera_info info, rs2_error **error)
void rs2_delete_recommended_processing_blocks(rs2_processing_block_list *list)
rs2_stream
Streams are different types of data provided by RealSense devices.
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.
void rs2_set_motion_device_intrinsics(const rs2_sensor *sensor, const rs2_stream_profile *profile, const rs2_motion_device_intrinsic *intrinsics, rs2_error **error)
void rs2_get_video_stream_intrinsics(const rs2_stream_profile *mode, rs2_intrinsics *intrinsics, rs2_error **error)
Cross-stream extrinsics: encodes the topology describing how the different devices are oriented...
void rs2_get_dsm_params(rs2_sensor const *sensor, rs2_dsm_params *p_params_out, rs2_error **error)
const char * rs2_camera_info_to_string(rs2_camera_info info)
int rs2_is_sensor_extendable_to(const rs2_sensor *sensor, rs2_extension extension, rs2_error **error)
3D vector in Euclidean coordinate space
const char * rs2_stream_to_string(rs2_stream stream)
rs2_extension
Specifies advanced interfaces (capabilities) objects may implement.
rs2_notification_category
Category of the librealsense notification.
void(* rs2_notification_callback_ptr)(rs2_notification *, void *)
stream_profile to_profile(const stream_profile_interface *sp)
void rs2_delete_stream_profiles_list(rs2_stream_profile_list *list)
void rs2_close(const rs2_sensor *sensor, rs2_error **error)
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)
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)
rs2_notification_category rs2_get_notification_category(rs2_notification *notification, rs2_error **error)
rs2_processing_block * rs2_get_processing_block(const rs2_processing_block_list *list, int index, rs2_error **error)
Motion device intrinsics: scale, bias, and variances.
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)
int rs2_set_static_node(const rs2_sensor *sensor, const char *guid, const rs2_vector pos, const rs2_quaternion orient, rs2_error **error)
void(* rs2_frame_callback_ptr)(rs2_frame *, void *)
const rs2_raw_data_buffer * rs2_export_localization_map(const rs2_sensor *sensor, rs2_error **error)
float rs2_depth_stereo_frame_get_baseline(const rs2_frame *frame_ref, rs2_error **error)
const char * rs2_get_sensor_info(const rs2_sensor *sensor, rs2_camera_info info, rs2_error **error)
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)
int rs2_load_wheel_odometry_config(const rs2_sensor *sensor, const unsigned char *odometry_config_buf, unsigned int blob_size, rs2_error **error)
rs2_log_severity
Severity of the librealsense logger.
rs2_processing_block_list * rs2_get_recommended_processing_blocks(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)
void rs2_get_motion_intrinsics(const rs2_stream_profile *mode, rs2_motion_device_intrinsic *intrinsics, 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.
struct rs2_frame rs2_frame