Classes | Typedefs | Enumerations | Functions
rs_sensor.h File Reference

Exposes RealSense sensor functionality for C compilers. More...

#include "rs_types.h"
Include dependency graph for rs_sensor.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  rs2_extrinsics
 Cross-stream extrinsics: encodes the topology describing how the different devices are oriented. More...
 

Typedefs

typedef enum rs2_camera_info rs2_camera_info
 Read-only strings that can be queried from the device. Not all information attributes are available on all camera types. This information is mainly available for camera debug and troubleshooting and should not be used in applications. More...
 
typedef struct rs2_extrinsics rs2_extrinsics
 Cross-stream extrinsics: encodes the topology describing how the different devices are oriented. More...
 
typedef enum rs2_format rs2_format
 A stream's format identifies how binary data is encoded within a frame. More...
 
typedef enum rs2_stream rs2_stream
 Streams are different types of data provided by RealSense devices. More...
 

Enumerations

enum  rs2_camera_info {
  RS2_CAMERA_INFO_NAME, RS2_CAMERA_INFO_SERIAL_NUMBER, RS2_CAMERA_INFO_FIRMWARE_VERSION, RS2_CAMERA_INFO_RECOMMENDED_FIRMWARE_VERSION,
  RS2_CAMERA_INFO_PHYSICAL_PORT, RS2_CAMERA_INFO_DEBUG_OP_CODE, RS2_CAMERA_INFO_ADVANCED_MODE, RS2_CAMERA_INFO_PRODUCT_ID,
  RS2_CAMERA_INFO_CAMERA_LOCKED, RS2_CAMERA_INFO_USB_TYPE_DESCRIPTOR, RS2_CAMERA_INFO_PRODUCT_LINE, RS2_CAMERA_INFO_ASIC_SERIAL_NUMBER,
  RS2_CAMERA_INFO_FIRMWARE_UPDATE_ID, RS2_CAMERA_INFO_IP_ADDRESS, RS2_CAMERA_INFO_COUNT
}
 Read-only strings that can be queried from the device. Not all information attributes are available on all camera types. This information is mainly available for camera debug and troubleshooting and should not be used in applications. More...
 
enum  rs2_format {
  RS2_FORMAT_ANY, RS2_FORMAT_Z16, RS2_FORMAT_DISPARITY16, RS2_FORMAT_XYZ32F,
  RS2_FORMAT_YUYV, RS2_FORMAT_RGB8, RS2_FORMAT_BGR8, RS2_FORMAT_RGBA8,
  RS2_FORMAT_BGRA8, RS2_FORMAT_Y8, RS2_FORMAT_Y16, RS2_FORMAT_RAW10,
  RS2_FORMAT_RAW16, RS2_FORMAT_RAW8, RS2_FORMAT_UYVY, RS2_FORMAT_MOTION_RAW,
  RS2_FORMAT_MOTION_XYZ32F, RS2_FORMAT_GPIO_RAW, RS2_FORMAT_6DOF, RS2_FORMAT_DISPARITY32,
  RS2_FORMAT_Y10BPACK, RS2_FORMAT_DISTANCE, RS2_FORMAT_MJPEG, RS2_FORMAT_Y8I,
  RS2_FORMAT_Y12I, RS2_FORMAT_INZI, RS2_FORMAT_INVI, RS2_FORMAT_W10,
  RS2_FORMAT_Z16H, RS2_FORMAT_FG, RS2_FORMAT_COUNT
}
 A stream's format identifies how binary data is encoded within a frame. More...
 
enum  rs2_stream {
  RS2_STREAM_ANY, RS2_STREAM_DEPTH, RS2_STREAM_COLOR, RS2_STREAM_INFRARED,
  RS2_STREAM_FISHEYE, RS2_STREAM_GYRO, RS2_STREAM_ACCEL, RS2_STREAM_GPIO,
  RS2_STREAM_POSE, RS2_STREAM_CONFIDENCE, RS2_STREAM_COUNT
}
 Streams are different types of data provided by RealSense devices. More...
 

Functions

const char * rs2_camera_info_to_string (rs2_camera_info info)
 
rs2_stream_profilers2_clone_stream_profile (const rs2_stream_profile *mode, rs2_stream stream, int index, rs2_format format, rs2_error **error)
 
rs2_stream_profilers2_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_close (const rs2_sensor *sensor, rs2_error **error)
 
rs2_devicers2_create_device_from_sensor (const rs2_sensor *sensor, rs2_error **error)
 
rs2_sensorrs2_create_sensor (const rs2_sensor_list *list, int index, rs2_error **error)
 
void rs2_delete_recommended_processing_blocks (rs2_processing_block_list *list)
 
void rs2_delete_sensor (rs2_sensor *sensor)
 
void rs2_delete_sensor_list (rs2_sensor_list *info_list)
 
void rs2_delete_stream_profile (rs2_stream_profile *mode)
 
void rs2_delete_stream_profiles_list (rs2_stream_profile_list *list)
 
float rs2_depth_stereo_frame_get_baseline (const rs2_frame *frame_ref, rs2_error **error)
 
const rs2_raw_data_bufferrs2_export_localization_map (const rs2_sensor *sensor, rs2_error **error)
 
const char * rs2_format_to_string (rs2_format format)
 
rs2_stream_profile_listrs2_get_active_streams (rs2_sensor *sensor, rs2_error **error)
 
rs2_stream_profile_listrs2_get_debug_stream_profiles (rs2_sensor *sensor, rs2_error **error)
 
float rs2_get_depth_scale (rs2_sensor *sensor, rs2_error **error)
 
void rs2_get_dsm_params (rs2_sensor const *sensor, rs2_dsm_params *p_params_out, rs2_error **error)
 
void rs2_get_extrinsics (const rs2_stream_profile *from, const rs2_stream_profile *to, rs2_extrinsics *extrin, rs2_error **error)
 
float rs2_get_max_usable_depth_range (rs2_sensor const *sensor, rs2_error **error)
 
void rs2_get_motion_intrinsics (const rs2_stream_profile *mode, rs2_motion_device_intrinsic *intrinsics, rs2_error **error)
 
rs2_notification_category rs2_get_notification_category (rs2_notification *notification, rs2_error **error)
 
const char * rs2_get_notification_description (rs2_notification *notification, 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_time_t rs2_get_notification_timestamp (rs2_notification *notification, rs2_error **error)
 
rs2_processing_blockrs2_get_processing_block (const rs2_processing_block_list *list, int index, rs2_error **error)
 
rs2_processing_block_listrs2_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)
 
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 More...
 
const char * rs2_get_sensor_info (const rs2_sensor *sensor, rs2_camera_info info, rs2_error **error)
 
int rs2_get_sensors_count (const rs2_sensor_list *info_list, 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_stereo_baseline (rs2_sensor *sensor, rs2_error **error)
 
const rs2_stream_profilers2_get_stream_profile (const rs2_stream_profile_list *list, int index, 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)
 
rs2_stream_profile_listrs2_get_stream_profiles (rs2_sensor *sensor, rs2_error **error)
 
int rs2_get_stream_profiles_count (const rs2_stream_profile_list *list, rs2_error **error)
 
void rs2_get_video_stream_intrinsics (const rs2_stream_profile *mode, rs2_intrinsics *intrinsics, rs2_error **error)
 
void rs2_get_video_stream_resolution (const rs2_stream_profile *mode, int *width, int *height, rs2_error **error)
 
int rs2_import_localization_map (const rs2_sensor *sensor, const unsigned char *lmap_blob, unsigned int blob_size, rs2_error **error)
 
int rs2_is_sensor_extendable_to (const rs2_sensor *sensor, rs2_extension extension, rs2_error **error)
 
int rs2_is_stream_profile_default (const rs2_stream_profile *mode, 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_open (rs2_sensor *device, const rs2_stream_profile *profile, rs2_error **error)
 
void rs2_open_multiple (rs2_sensor *device, const rs2_stream_profile **profiles, int count, rs2_error **error)
 
void rs2_override_dsm_params (rs2_sensor const *sensor, rs2_dsm_params const *p_params, rs2_error **error)
 
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. More...
 
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. More...
 
void rs2_register_extrinsics (const rs2_stream_profile *from, const rs2_stream_profile *to, rs2_extrinsics extrin, rs2_error **error)
 
int rs2_remove_static_node (const rs2_sensor *sensor, const char *guid, rs2_error **error)
 
void rs2_reset_sensor_calibration (rs2_sensor const *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_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)
 
void rs2_set_intrinsics (const rs2_sensor *sensor, const rs2_stream_profile *profile, const rs2_intrinsics *intrinsics, rs2_error **error)
 
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_set_notifications_callback (const rs2_sensor *sensor, rs2_notification_callback_ptr on_notification, void *user, rs2_error **error)
 
void rs2_set_notifications_callback_cpp (const rs2_sensor *sensor, rs2_notifications_callback *callback, 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 More...
 
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_set_stream_profile_data (rs2_stream_profile *mode, rs2_stream stream, int index, rs2_format format, rs2_error **error)
 
void rs2_start (const rs2_sensor *sensor, rs2_frame_callback_ptr on_frame, void *user, rs2_error **error)
 
void rs2_start_cpp (const rs2_sensor *sensor, rs2_frame_callback *callback, rs2_error **error)
 
void rs2_start_queue (const rs2_sensor *sensor, rs2_frame_queue *queue, rs2_error **error)
 
void rs2_stop (const rs2_sensor *sensor, rs2_error **error)
 
int rs2_stream_profile_is (const rs2_stream_profile *mode, rs2_extension type, rs2_error **error)
 
const char * rs2_stream_to_string (rs2_stream stream)
 
int rs2_supports_sensor_info (const rs2_sensor *sensor, rs2_camera_info info, rs2_error **error)
 

Detailed Description

Exposes RealSense sensor functionality for C compilers.

Definition in file rs_sensor.h.

Typedef Documentation

Read-only strings that can be queried from the device. Not all information attributes are available on all camera types. This information is mainly available for camera debug and troubleshooting and should not be used in applications.

Cross-stream extrinsics: encodes the topology describing how the different devices are oriented.

typedef enum rs2_format rs2_format

A stream's format identifies how binary data is encoded within a frame.

typedef enum rs2_stream rs2_stream

Streams are different types of data provided by RealSense devices.

Enumeration Type Documentation

Read-only strings that can be queried from the device. Not all information attributes are available on all camera types. This information is mainly available for camera debug and troubleshooting and should not be used in applications.

Enumerator
RS2_CAMERA_INFO_NAME 

Friendly name

RS2_CAMERA_INFO_SERIAL_NUMBER 

Device serial number

RS2_CAMERA_INFO_FIRMWARE_VERSION 

Primary firmware version

RS2_CAMERA_INFO_RECOMMENDED_FIRMWARE_VERSION 

Recommended firmware version

RS2_CAMERA_INFO_PHYSICAL_PORT 

Unique identifier of the port the device is connected to (platform specific)

RS2_CAMERA_INFO_DEBUG_OP_CODE 

If device supports firmware logging, this is the command to send to get logs from firmware

RS2_CAMERA_INFO_ADVANCED_MODE 

True iff the device is in advanced mode

RS2_CAMERA_INFO_PRODUCT_ID 

Product ID as reported in the USB descriptor

RS2_CAMERA_INFO_CAMERA_LOCKED 

True iff EEPROM is locked

RS2_CAMERA_INFO_USB_TYPE_DESCRIPTOR 

Designated USB specification: USB2/USB3

RS2_CAMERA_INFO_PRODUCT_LINE 

Device product line D400/SR300/L500/T200

RS2_CAMERA_INFO_ASIC_SERIAL_NUMBER 

ASIC serial number

RS2_CAMERA_INFO_FIRMWARE_UPDATE_ID 

Firmware update ID

RS2_CAMERA_INFO_IP_ADDRESS 

IP address for remote camera.

RS2_CAMERA_INFO_COUNT 

Number of enumeration values. Not a valid input: intended to be used in for-loops.

Definition at line 22 of file rs_sensor.h.

enum rs2_format

A stream's format identifies how binary data is encoded within a frame.

Enumerator
RS2_FORMAT_ANY 

When passed to enable stream, librealsense will try to provide best suited format

RS2_FORMAT_Z16 

16-bit linear depth values. The depth is meters is equal to depth scale * pixel value.

RS2_FORMAT_DISPARITY16 

16-bit float-point disparity values. Depth->Disparity conversion : Disparity = Baseline*FocalLength/Depth.

RS2_FORMAT_XYZ32F 

32-bit floating point 3D coordinates.

RS2_FORMAT_YUYV 

32-bit y0, u, y1, v data for every two pixels. Similar to YUV422 but packed in a different order - https://en.wikipedia.org/wiki/YUV

RS2_FORMAT_RGB8 

8-bit red, green and blue channels

RS2_FORMAT_BGR8 

8-bit blue, green, and red channels – suitable for OpenCV

RS2_FORMAT_RGBA8 

8-bit red, green and blue channels + constant alpha channel equal to FF

RS2_FORMAT_BGRA8 

8-bit blue, green, and red channels + constant alpha channel equal to FF

RS2_FORMAT_Y8 

8-bit per-pixel grayscale image

RS2_FORMAT_Y16 

16-bit per-pixel grayscale image

RS2_FORMAT_RAW10 

Four 10 bits per pixel luminance values packed into a 5-byte macropixel

RS2_FORMAT_RAW16 

16-bit raw image

RS2_FORMAT_RAW8 

8-bit raw image

RS2_FORMAT_UYVY 

Similar to the standard YUYV pixel format, but packed in a different order

RS2_FORMAT_MOTION_RAW 

Raw data from the motion sensor

RS2_FORMAT_MOTION_XYZ32F 

Motion data packed as 3 32-bit float values, for X, Y, and Z axis

RS2_FORMAT_GPIO_RAW 

Raw data from the external sensors hooked to one of the GPIO's

RS2_FORMAT_6DOF 

Pose data packed as floats array, containing translation vector, rotation quaternion and prediction velocities and accelerations vectors

RS2_FORMAT_DISPARITY32 

32-bit float-point disparity values. Depth->Disparity conversion : Disparity = Baseline*FocalLength/Depth

RS2_FORMAT_Y10BPACK 

16-bit per-pixel grayscale image unpacked from 10 bits per pixel packed ([8:8:8:8:2222]) grey-scale image. The data is unpacked to LSB and padded with 6 zero bits

RS2_FORMAT_DISTANCE 

32-bit float-point depth distance value.

RS2_FORMAT_MJPEG 

Bitstream encoding for video in which an image of each frame is encoded as JPEG-DIB

RS2_FORMAT_Y8I 

8-bit per pixel interleaved. 8-bit left, 8-bit right.

RS2_FORMAT_Y12I 

12-bit per pixel interleaved. 12-bit left, 12-bit right. Each pixel is stored in a 24-bit word in little-endian order.

RS2_FORMAT_INZI 

multi-planar Depth 16bit + IR 10bit.

RS2_FORMAT_INVI 

8-bit IR stream.

RS2_FORMAT_W10 

Grey-scale image as a bit-packed array. 4 pixel data stream taking 5 bytes

RS2_FORMAT_Z16H 

Variable-length Huffman-compressed 16-bit depth values.

RS2_FORMAT_FG 

16-bit per-pixel frame grabber format.

RS2_FORMAT_COUNT 

Number of enumeration values. Not a valid input: intended to be used in for-loops.

Definition at line 59 of file rs_sensor.h.

enum rs2_stream

Streams are different types of data provided by RealSense devices.

Enumerator
RS2_STREAM_ANY 
RS2_STREAM_DEPTH 

Native stream of depth data produced by RealSense device

RS2_STREAM_COLOR 

Native stream of color data captured by RealSense device

RS2_STREAM_INFRARED 

Native stream of infrared data captured by RealSense device

RS2_STREAM_FISHEYE 

Native stream of fish-eye (wide) data captured from the dedicate motion camera

RS2_STREAM_GYRO 

Native stream of gyroscope motion data produced by RealSense device

RS2_STREAM_ACCEL 

Native stream of accelerometer motion data produced by RealSense device

RS2_STREAM_GPIO 

Signals from external device connected through GPIO

RS2_STREAM_POSE 

6 Degrees of Freedom pose data, calculated by RealSense device

RS2_STREAM_CONFIDENCE 

4 bit per-pixel depth confidence level

RS2_STREAM_COUNT 

Definition at line 42 of file rs_sensor.h.

Function Documentation

const char* rs2_camera_info_to_string ( rs2_camera_info  info)

Definition at line 1266 of file rs.cpp.

rs2_stream_profile* rs2_clone_stream_profile ( const rs2_stream_profile mode,
rs2_stream  stream,
int  index,
rs2_format  format,
rs2_error **  error 
)

Creates a copy of stream profile, assigning new values to some of the fields

Parameters
[in]modeinput stream profile
[in]streamstream type for the profile
[in]formatbinary data format of the profile
[in]indexstream index the profile in case there are multiple streams of the same type
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
new stream profile, must be deleted by rs2_delete_stream_profile

Definition at line 519 of file rs.cpp.

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 
)

Creates a copy of stream profile, assigning new values to some of the fields

Parameters
[in]modeinput stream profile
[in]streamstream type for the profile
[in]formatbinary data format of the profile
[in]widthnew width for the profile
[in]heightnew height for the profile
[in]intrnew intrinsics for the profile
[in]indexstream index the profile in case there are multiple streams of the same type
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
new stream profile, must be deleted by rs2_delete_stream_profile

Definition at line 533 of file rs.cpp.

void rs2_close ( const rs2_sensor sensor,
rs2_error **  error 
)

stop any streaming from specified subdevice

Parameters
[in]sensorRealSense device
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 614 of file rs.cpp.

rs2_device* rs2_create_device_from_sensor ( const rs2_sensor sensor,
rs2_error **  error 
)

This is a helper function allowing the user to discover the device from one of its sensors

Parameters
[in]sensorPointer to a sensor
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
new device wrapper for the device of the sensor. Needs to be released by delete_device

Definition at line 2338 of file rs.cpp.

rs2_sensor* rs2_create_sensor ( const rs2_sensor_list list,
int  index,
rs2_error **  error 
)

create sensor by index

Parameters
[in]indexthe zero based index of sensor to retrieve
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
the requested sensor, should be released by rs2_delete_sensor

Definition at line 308 of file rs.cpp.

void rs2_delete_recommended_processing_blocks ( rs2_processing_block_list list)

Deletes processing blocks list

Parameters
[in]listlist to delete

Definition at line 2788 of file rs.cpp.

void rs2_delete_sensor ( rs2_sensor sensor)

delete relasense sensor

Parameters
[in]sensorrealsense sensor to delete

Definition at line 320 of file rs.cpp.

void rs2_delete_sensor_list ( rs2_sensor_list info_list)

Deletes sensors list, any sensors created from this list will remain unaffected

Parameters
[in]info_listlist to delete

Definition at line 282 of file rs.cpp.

void rs2_delete_stream_profile ( rs2_stream_profile mode)

Delete stream profile allocated by rs2_clone_stream_profile Should not be called on stream profiles returned by the device

Parameters
[in]modeinput stream profile

Definition at line 512 of file rs.cpp.

void rs2_delete_stream_profiles_list ( rs2_stream_profile_list list)

delete stream profiles list

Parameters
[in]listthe list of supported profiles returned by rs2_get_supported_profiles

Definition at line 367 of file rs.cpp.

float rs2_depth_stereo_frame_get_baseline ( const rs2_frame frame_ref,
rs2_error **  error 
)

Retrieve the stereoscopic baseline value from frame. Applicable to stereo-based depth modules

Parameters
[out]floatStereoscopic baseline in millimeters
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 2364 of file rs.cpp.

const rs2_raw_data_buffer* rs2_export_localization_map ( const rs2_sensor sensor,
rs2_error **  error 
)

Extract and store the localization map of tm2 tracking device to file

Parameters
[in]sensorTM2 position-tracking sensor
[in]lmap_fnameThe file name of the localization map
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
Device's response in a rs2_raw_data_buffer, which should be released by rs2_delete_raw_data

Definition at line 2828 of file rs.cpp.

const char* rs2_format_to_string ( rs2_format  format)

Definition at line 1263 of file rs.cpp.

rs2_stream_profile_list* rs2_get_active_streams ( rs2_sensor sensor,
rs2_error **  error 
)

check how subdevice is streaming

Parameters
[in]sensorinput RealSense subdevice
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
list of stream profiles that given subdevice is currently streaming, should be released by rs2_delete_profiles_list

Definition at line 344 of file rs.cpp.

rs2_stream_profile_list* rs2_get_debug_stream_profiles ( rs2_sensor sensor,
rs2_error **  error 
)

retrieve list of debug stream profiles that given subdevice can provide

Parameters
[in]sensorinput RealSense subdevice
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
list of debug stream profiles that given subdevice can provide, should be released by rs2_delete_profiles_list

Definition at line 334 of file rs.cpp.

float rs2_get_depth_scale ( rs2_sensor sensor,
rs2_error **  error 
)

When called on a depth sensor, this method will return the number of meters represented by a single depth unit

Parameters
[in]sensordepth sensor
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
the number of meters represented by a single depth unit

Definition at line 2312 of file rs.cpp.

void rs2_get_dsm_params ( rs2_sensor const *  sensor,
rs2_dsm_params p_params_out,
rs2_error **  error 
)

Get the DSM parameters for a sensor

Parameters
[in]sensorSensor that supports the CALIBRATED_SENSOR extension
[out]p_params_outPointer to the structure that will get the DSM parameters
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 1146 of file rs.cpp.

void rs2_get_extrinsics ( const rs2_stream_profile from,
const rs2_stream_profile to,
rs2_extrinsics extrin,
rs2_error **  error 
)
Parameters
[in]fromorigin stream profile
[in]totarget stream profile
[out]extrinextrinsics from origin to target
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 1110 of file rs.cpp.

float rs2_get_max_usable_depth_range ( rs2_sensor const *  sensor,
rs2_error **  error 
)

When called on a depth sensor, this method will return the maximum range of the camera given the amount of ambient light in the scene

Parameters
[in]sensordepth sensor
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
the max usable range in meters

Definition at line 2320 of file rs.cpp.

void rs2_get_motion_intrinsics ( const rs2_stream_profile mode,
rs2_motion_device_intrinsic intrinsics,
rs2_error **  error 
)

Obtain the intrinsics of a specific stream configuration from the device.

Parameters
[in]modeinput stream profile
[out]intrinsicsPointer to the struct to store the data in
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 455 of file rs.cpp.

rs2_notification_category rs2_get_notification_category ( rs2_notification notification,
rs2_error **  error 
)

retrieve category from notification handle

Parameters
[in]notificationhandle returned from a callback
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
the notification category

Definition at line 875 of file rs.cpp.

const char* rs2_get_notification_description ( rs2_notification notification,
rs2_error **  error 
)

retrieve description from notification handle

Parameters
[in]notificationhandle returned from a callback
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
the notification description

Definition at line 854 of file rs.cpp.

const char* rs2_get_notification_serialized_data ( rs2_notification notification,
rs2_error **  error 
)

retrieve serialized data from notification handle

Parameters
[in]notificationhandle returned from a callback
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
the serialized data (in JSON format)

Definition at line 882 of file rs.cpp.

rs2_log_severity rs2_get_notification_severity ( rs2_notification notification,
rs2_error **  error 
)

retrieve severity from notification handle

Parameters
[in]notificationhandle returned from a callback
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
the notification severity

Definition at line 868 of file rs.cpp.

rs2_time_t rs2_get_notification_timestamp ( rs2_notification notification,
rs2_error **  error 
)

retrieve timestamp from notification handle

Parameters
[in]notificationhandle returned from a callback
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
the notification timestamp

Definition at line 861 of file rs.cpp.

rs2_processing_block* rs2_get_processing_block ( const rs2_processing_block_list list,
int  index,
rs2_error **  error 
)

Returns specific processing blocks from processing blocks list

Parameters
[in]listthe processing blocks list
[in]indexthe requested processing block
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
processing block

Definition at line 2772 of file rs.cpp.

rs2_processing_block_list* rs2_get_recommended_processing_blocks ( rs2_sensor sensor,
rs2_error **  error 
)

Returns the list of recommended processing blocks for a specific sensor. Order and configuration of the blocks are decided by the sensor

Parameters
[in]sensorinput sensor
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
list of supported sensor recommended processing blocks

Definition at line 2765 of file rs.cpp.

int rs2_get_recommended_processing_blocks_count ( const rs2_processing_block_list list,
rs2_error **  error 
)

Returns the processing blocks list size

Parameters
[in]listthe processing blocks list
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
the processing block list size

Definition at line 2781 of file rs.cpp.

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

Parameters
[in]sensorthe RealSense sensor
[out]min_xlower horizontal bound in pixels
[out]min_ylower vertical bound in pixels
[out]max_xupper horizontal bound in pixels
[out]max_yupper vertical bound in pixels
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 1238 of file rs.cpp.

const char* rs2_get_sensor_info ( const rs2_sensor sensor,
rs2_camera_info  info,
rs2_error **  error 
)

retrieve sensor specific information, like versions of various internal components

Parameters
[in]sensorthe RealSense sensor
[in]infocamera info type to retrieve
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
the requested camera info string, in a format specific to the device model

Definition at line 724 of file rs.cpp.

int rs2_get_sensors_count ( const rs2_sensor_list info_list,
rs2_error **  error 
)

Determines number of sensors in a list

Parameters
[in]info_listThe list of connected sensors captured using rs2_query_sensors
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
Sensors count

Definition at line 267 of file rs.cpp.

int rs2_get_static_node ( const rs2_sensor sensor,
const char *  guid,
rs2_vector pos,
rs2_quaternion orient,
rs2_error **  error 
)

Retrieve a named location tag

Parameters
[in]sensorT2xx position-tracking sensor
[in]guidNull-terminated string of up to 127 characters
[out]posPosition in meters of the tagged (stored) location
[out]orientQuaternion orientation of the tagged (stored) location
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
Non-zero if succeeded, otherwise 0

Definition at line 2852 of file rs.cpp.

float rs2_get_stereo_baseline ( rs2_sensor sensor,
rs2_error **  error 
)

Retrieve the stereoscopic baseline value from sensor. Applicable to stereo-based depth modules

Parameters
[out]floatStereoscopic baseline in millimeters
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 2330 of file rs.cpp.

const rs2_stream_profile* rs2_get_stream_profile ( const rs2_stream_profile_list list,
int  index,
rs2_error **  error 
)

Get pointer to specific stream profile

Parameters
[in]listthe list of supported profiles returned by rs2_get_supported_profiles
[in]indexthe zero based index of the streaming mode
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 351 of file rs.cpp.

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 
)

Extract common parameters of a stream profiles

Parameters
[in]modeinput stream profile
[out]streamstream type of the input profile
[out]formatbinary data format of the input profile
[out]indexstream index the input profile in case there are multiple streams of the same type
[out]unique_ididentifier for the stream profile, unique within the application
[out]framerateexpected rate for data frames to arrive, meaning expected number of frames per second
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 484 of file rs.cpp.

rs2_stream_profile_list* rs2_get_stream_profiles ( rs2_sensor sensor,
rs2_error **  error 
)

check if physical subdevice is supported

Parameters
[in]sensorinput RealSense subdevice
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
list of stream profiles that given subdevice can provide, should be released by rs2_delete_profiles_list

Definition at line 327 of file rs.cpp.

int rs2_get_stream_profiles_count ( const rs2_stream_profile_list list,
rs2_error **  error 
)

get the number of supported stream profiles

Parameters
[in]listthe list of supported profiles returned by rs2_get_supported_profiles
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
number of supported subdevice profiles

Definition at line 360 of file rs.cpp.

void rs2_get_video_stream_intrinsics ( const rs2_stream_profile mode,
rs2_intrinsics intrinsics,
rs2_error **  error 
)

When called on a video profile, returns the intrinsics of specific stream configuration

Parameters
[in]modeinput stream profile
[out]intrinsicsresulting intrinsics for the video profile
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 374 of file rs.cpp.

void rs2_get_video_stream_resolution ( const rs2_stream_profile mode,
int *  width,
int *  height,
rs2_error **  error 
)

When called on a video stream profile, will return the width and the height of the stream

Parameters
[in]modeinput stream profile
[out]widthwidth in pixels of the video stream
[out]heightheight in pixels of the video stream
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 466 of file rs.cpp.

int rs2_import_localization_map ( const rs2_sensor sensor,
const unsigned char *  lmap_blob,
unsigned int  blob_size,
rs2_error **  error 
)

Imports a localization map from file to tm2 tracking device

Parameters
[in]sensorTM2 position-tracking sensor
[in]lmap_blobLocalization map raw buffer, serialized
[in]blob_sizeThe buffer's size in bytes
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
Non-zero if succeeded, otherwise 0

Definition at line 2815 of file rs.cpp.

int rs2_is_sensor_extendable_to ( const rs2_sensor sensor,
rs2_extension  extension,
rs2_error **  error 
)

Test if the given sensor can be extended to the requested extension

Parameters
[in]sensorRealsense sensor
[in]extensionThe extension to which the sensor should be tested if it is extendable
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
non-zero value iff the sensor can be extended to the given extension

Definition at line 1394 of file rs.cpp.

int rs2_is_stream_profile_default ( const rs2_stream_profile mode,
rs2_error **  error 
)

Returns non-zero if selected profile is recommended for the sensor This is an optional hint we offer to suggest profiles with best performance-quality tradeof

Parameters
[in]modeinput stream profile
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
non-zero if selected profile is recommended for the sensor

Definition at line 477 of file rs.cpp.

int rs2_load_wheel_odometry_config ( const rs2_sensor sensor,
const unsigned char *  odometry_config_buf,
unsigned int  blob_size,
rs2_error **  error 
)

Load Wheel odometer settings from host to device

Parameters
[in]odometry_config_bufodometer configuration/calibration blob serialized from jsom file
Returns
true on success

Definition at line 2891 of file rs.cpp.

void rs2_open ( rs2_sensor device,
const rs2_stream_profile profile,
rs2_error **  error 
)

open subdevice for exclusive access, by committing to a configuration

Parameters
[in]devicerelevant RealSense device
[in]profilestream profile that defines single stream configuration
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 588 of file rs.cpp.

void rs2_open_multiple ( rs2_sensor device,
const rs2_stream_profile **  profiles,
int  count,
rs2_error **  error 
)

open subdevice for exclusive access, by committing to composite configuration, specifying one or more stream profiles this method should be used for interdependent streams, such as depth and infrared, that have to be configured together

Parameters
[in]devicerelevant RealSense device
[in]profileslist of stream profiles discovered by get_stream_profiles
[in]countnumber of simultaneous stream profiles to configure
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 599 of file rs.cpp.

void rs2_override_dsm_params ( rs2_sensor const *  sensor,
rs2_dsm_params const *  p_params,
rs2_error **  error 
)

Set the sensor DSM parameters This should ideally be done when the stream is NOT running. If it is, the parameters may not take effect immediately.

Parameters
[in]sensorSensor that supports the CALIBRATED_SENSOR extension
[out]p_paramsPointer to the structure that contains the DSM parameters
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 1156 of file rs.cpp.

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.

This will affect extrinsics at the source device and may affect multiple profiles. Used for DEPTH_TO_RGB calibration.

Parameters
[in]sensorThe sensor
[in]extrinsicsExtrinsics from Depth to the named sensor
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 1136 of file rs.cpp.

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.

This will affect intrinsics at the source and may affect multiple profiles. Used for DEPTH_TO_RGB calibration.

Parameters
[in]sensorThe RealSense device
[in]intrinsicsIntrinsics value to be written to the sensor
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 2688 of file rs.cpp.

void rs2_register_extrinsics ( const rs2_stream_profile from,
const rs2_stream_profile to,
rs2_extrinsics  extrin,
rs2_error **  error 
)
Parameters
[in]fromorigin stream profile
[in]totarget stream profile
[out]extrinextrinsics from origin to target
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 1125 of file rs.cpp.

int rs2_remove_static_node ( const rs2_sensor sensor,
const char *  guid,
rs2_error **  error 
)

Remove a named location tag

Parameters
[in]sensorT2xx position-tracking sensor
[in]guidNull-terminated string of up to 127 characters
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
Non-zero if succeeded, otherwise 0

Definition at line 2879 of file rs.cpp.

void rs2_reset_sensor_calibration ( rs2_sensor const *  sensor,
rs2_error **  error 
)

Reset the sensor DSM parameters This should ideally be done when the stream is NOT running. May not take effect immediately.

Parameters
[in]sensorSensor that supports the CALIBRATED_SENSOR extension
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 1166 of file rs.cpp.

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 
)

Send wheel odometry data for each individual sensor (wheel)

Parameters
[in]wo_sensor_id- Zero-based index of (wheel) sensor with the same type within device
[in]frame_num- Monotonocally increasing frame number, managed per sensor.
[in]translational_velocity- Translational velocity of the wheel sensor [meter/sec]
Returns
true on success

Definition at line 2907 of file rs.cpp.

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 
)

Set extrinsics between two sensors

Parameters
[in]from_sensorOrigin sensor
[in]from_profileOrigin profile
[in]to_sensorTarget sensor
[in]to_profileTarget profile
[out]extrinsicsExtrinsics from origin to target
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 2698 of file rs.cpp.

void rs2_set_intrinsics ( const rs2_sensor sensor,
const rs2_stream_profile profile,
const rs2_intrinsics intrinsics,
rs2_error **  error 
)

Set intrinsics of a given sensor

Parameters
[in]sensorThe RealSense device
[in]profileTarget stream profile
[in]intrinsicsIntrinsics value to be written to the device
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 2677 of file rs.cpp.

void rs2_set_motion_device_intrinsics ( const rs2_sensor sensor,
const rs2_stream_profile profile,
const rs2_motion_device_intrinsic intrinsics,
rs2_error **  error 
)

Set motion device intrinsics

Parameters
[in]sensorMotion sensor
[in]profileMotion stream profile
[out]intrinsicsPointer to the struct to store the data in
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 2722 of file rs.cpp.

void rs2_set_notifications_callback ( const rs2_sensor sensor,
rs2_notification_callback_ptr  on_notification,
void user,
rs2_error **  error 
)

set callback to get notifications from specified sensor

Parameters
[in]sensorRealSense device
[in]on_notificationfunction pointer to register as per-notifications callback
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 764 of file rs.cpp.

void rs2_set_notifications_callback_cpp ( const rs2_sensor sensor,
rs2_notifications_callback callback,
rs2_error **  error 
)

set callback to get notifications from specified device

Parameters
[in]sensorRealSense sensor
[in]callbackcallback object created from c++ application. ownership over the callback object is moved into the relevant subdevice lock
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 806 of file rs.cpp.

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

Parameters
[in]sensorthe RealSense sensor
[in]min_xlower horizontal bound in pixels
[in]min_ylower vertical bound in pixels
[in]max_xupper horizontal bound in pixels
[in]max_yupper vertical bound in pixels
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 1224 of file rs.cpp.

int rs2_set_static_node ( const rs2_sensor sensor,
const char *  guid,
const rs2_vector  pos,
const rs2_quaternion  orient,
rs2_error **  error 
)

Create a named location tag

Parameters
[in]sensorT2xx position-tracking sensor
[in]guidNull-terminated string of up to 127 characters
[in]posPosition in meters, relative to the current tracking session
[in]orientQuaternion orientation, expressed the the coordinate system of the current tracking session
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
Non-zero if succeeded, otherwise 0

Definition at line 2840 of file rs.cpp.

void rs2_set_stream_profile_data ( rs2_stream_profile mode,
rs2_stream  stream,
int  index,
rs2_format  format,
rs2_error **  error 
)

Override some of the parameters of the stream profile

Parameters
[in]modeinput stream profile
[in]streamstream type for the profile
[in]formatbinary data format of the profile
[in]indexstream index the profile in case there are multiple streams of the same type
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 500 of file rs.cpp.

void rs2_start ( const rs2_sensor sensor,
rs2_frame_callback_ptr  on_frame,
void user,
rs2_error **  error 
)

start streaming from specified configured sensor

Parameters
[in]sensorRealSense device
[in]on_framefunction pointer to register as per-frame callback
[in]userauxiliary data the user wishes to receive together with every frame callback
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 744 of file rs.cpp.

void rs2_start_cpp ( const rs2_sensor sensor,
rs2_frame_callback callback,
rs2_error **  error 
)

start streaming from specified configured sensor

Parameters
[in]sensorRealSense device
[in]callbackcallback object created from c++ application. ownership over the callback object is moved into the relevant streaming lock
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 798 of file rs.cpp.

void rs2_start_queue ( const rs2_sensor sensor,
rs2_frame_queue queue,
rs2_error **  error 
)

start streaming from specified configured sensor of specific stream to frame queue

Parameters
[in]sensorRealSense Sensor
[in]queueframe-queue to store new frames into
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 754 of file rs.cpp.

void rs2_stop ( const rs2_sensor sensor,
rs2_error **  error 
)

stops streaming from specified configured device

Parameters
[in]sensorRealSense sensor
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 831 of file rs.cpp.

int rs2_stream_profile_is ( const rs2_stream_profile mode,
rs2_extension  type,
rs2_error **  error 
)

Try to extend stream profile to an extension type

Parameters
[in]modeinput stream profile
[in]typeextension type, for example RS2_EXTENSION_VIDEO_STREAM_PROFILE
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
non-zero if profile is extendable to specified extension, zero otherwise

Definition at line 1504 of file rs.cpp.

const char* rs2_stream_to_string ( rs2_stream  stream)

Definition at line 1262 of file rs.cpp.

int rs2_supports_sensor_info ( const rs2_sensor sensor,
rs2_camera_info  info,
rs2_error **  error 
)

check if specific sensor info is supported

Parameters
[in]infothe parameter to check for support
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
true if the parameter both exist and well-defined for the specific device

Definition at line 736 of file rs.cpp.



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