Exposes RealSense sensor functionality for C compilers. More...
#include "rs_types.h"
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... | |
Exposes RealSense sensor functionality for C compilers.
Definition in file rs_sensor.h.
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.
typedef struct rs2_extrinsics rs2_extrinsics |
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.
enum 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.
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.
Definition at line 42 of file rs_sensor.h.
const char* rs2_camera_info_to_string | ( | rs2_camera_info | info | ) |
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
[in] | mode | input stream profile |
[in] | stream | stream type for the profile |
[in] | format | binary data format of the profile |
[in] | index | stream index the profile in case there are multiple streams of the same type |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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
[in] | mode | input stream profile |
[in] | stream | stream type for the profile |
[in] | format | binary data format of the profile |
[in] | width | new width for the profile |
[in] | height | new height for the profile |
[in] | intr | new intrinsics for the profile |
[in] | index | stream index the profile in case there are multiple streams of the same type |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
void rs2_close | ( | const rs2_sensor * | sensor, |
rs2_error ** | error | ||
) |
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
[in] | sensor | Pointer to a sensor |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
rs2_sensor* rs2_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 | ) |
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
[in] | sensor | TM2 position-tracking sensor |
[in] | lmap_fname | The file name of the localization map |
[out] | error | If non-null, receives any error that occurs during this call, otherwise, errors are ignored |
const char* rs2_format_to_string | ( | rs2_format | format | ) |
rs2_stream_profile_list* rs2_get_active_streams | ( | rs2_sensor * | sensor, |
rs2_error ** | error | ||
) |
check how subdevice is streaming
[in] | sensor | input RealSense subdevice |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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
[in] | sensor | input RealSense subdevice |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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
[in] | sensor | depth sensor |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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
[in] | sensor | Sensor that supports the CALIBRATED_SENSOR extension |
[out] | p_params_out | Pointer to the structure that will get the DSM parameters |
[out] | error | If non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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 | ||
) |
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
[in] | sensor | depth sensor |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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.
[in] | mode | input stream profile |
[out] | intrinsics | Pointer to the struct to store the data in |
[out] | error | If non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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_block* rs2_get_processing_block | ( | const rs2_processing_block_list * | list, |
int | index, | ||
rs2_error ** | error | ||
) |
Returns specific processing blocks from processing blocks list
[in] | list | the processing blocks list |
[in] | index | the requested processing block |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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
[in] | sensor | input sensor |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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
[in] | sensor | the RealSense sensor |
[out] | min_x | lower horizontal bound in pixels |
[out] | min_y | lower vertical bound in pixels |
[out] | max_x | upper horizontal bound in pixels |
[out] | max_y | upper vertical bound in pixels |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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
[in] | sensor | the RealSense sensor |
[in] | info | camera info type to retrieve |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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 | ||
) |
Retrieve a named location tag
[in] | sensor | T2xx position-tracking sensor |
[in] | guid | Null-terminated string of up to 127 characters |
[out] | pos | Position in meters of the tagged (stored) location |
[out] | orient | Quaternion orientation of the tagged (stored) location |
[out] | error | If non-null, receives any error that occurs during this call, otherwise, errors are ignored |
float rs2_get_stereo_baseline | ( | rs2_sensor * | sensor, |
rs2_error ** | error | ||
) |
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
[in] | list | the list of supported profiles returned by rs2_get_supported_profiles |
[in] | index | the zero based index of the streaming mode |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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
[in] | mode | input stream profile |
[out] | stream | stream type of the input profile |
[out] | format | binary data format of the input profile |
[out] | index | stream index the input profile in case there are multiple streams of the same type |
[out] | unique_id | identifier for the stream profile, unique within the application |
[out] | framerate | expected rate for data frames to arrive, meaning expected number of frames per second |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
rs2_stream_profile_list* rs2_get_stream_profiles | ( | rs2_sensor * | sensor, |
rs2_error ** | error | ||
) |
check if physical subdevice is supported
[in] | sensor | input RealSense subdevice |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
int rs2_get_stream_profiles_count | ( | const rs2_stream_profile_list * | list, |
rs2_error ** | error | ||
) |
get the number of supported stream profiles
[in] | list | the list of supported profiles returned by rs2_get_supported_profiles |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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
[in] | mode | input stream profile |
[out] | intrinsics | resulting intrinsics for the video profile |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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
[in] | mode | input stream profile |
[out] | width | width in pixels of the video stream |
[out] | height | height in pixels of the video stream |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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
[in] | sensor | TM2 position-tracking sensor |
[in] | lmap_blob | Localization map raw buffer, serialized |
[in] | blob_size | The buffer's size in bytes |
[out] | error | If non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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
[in] | sensor | Realsense sensor |
[in] | extension | The extension to which the sensor should be tested if it is extendable |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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
[in] | mode | input stream profile |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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 | ||
) |
open subdevice for exclusive access, by committing to a configuration
[in] | device | relevant RealSense device |
[in] | profile | stream profile that defines single stream configuration |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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
[in] | device | relevant RealSense device |
[in] | profiles | list of stream profiles discovered by get_stream_profiles |
[in] | count | number of simultaneous stream profiles to configure |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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.
[in] | sensor | Sensor that supports the CALIBRATED_SENSOR extension |
[out] | p_params | Pointer to the structure that contains the DSM parameters |
[out] | error | If non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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.
[in] | sensor | The sensor |
[in] | extrinsics | Extrinsics from Depth to the named sensor |
[out] | error | If non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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.
[in] | sensor | The RealSense device |
[in] | intrinsics | Intrinsics value to be written to the sensor |
[out] | error | If non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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 | ||
) |
Remove a named location tag
[in] | sensor | T2xx position-tracking sensor |
[in] | guid | Null-terminated string of up to 127 characters |
[out] | error | If non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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.
[in] | sensor | Sensor that supports the CALIBRATED_SENSOR extension |
[out] | error | If non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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)
[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] |
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
[in] | from_sensor | Origin sensor |
[in] | from_profile | Origin profile |
[in] | to_sensor | Target sensor |
[in] | to_profile | Target profile |
[out] | extrinsics | Extrinsics from origin to target |
[out] | error | If non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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
[in] | sensor | The RealSense device |
[in] | profile | Target stream profile |
[in] | intrinsics | Intrinsics value to be written to the device |
[out] | error | If non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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 | ||
) |
set callback to get notifications from specified sensor
[in] | sensor | RealSense device |
[in] | on_notification | function pointer to register as per-notifications callback |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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
[in] | sensor | RealSense sensor |
[in] | callback | callback object created from c++ application. ownership over the callback object is moved into the relevant subdevice lock |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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
[in] | sensor | the RealSense sensor |
[in] | min_x | lower horizontal bound in pixels |
[in] | min_y | lower vertical bound in pixels |
[in] | max_x | upper horizontal bound in pixels |
[in] | max_y | upper vertical bound in pixels |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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
[in] | sensor | T2xx position-tracking sensor |
[in] | guid | Null-terminated string of up to 127 characters |
[in] | pos | Position in meters, relative to the current tracking session |
[in] | orient | Quaternion orientation, expressed the the coordinate system of the current tracking session |
[out] | error | If non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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
[in] | mode | input stream profile |
[in] | stream | stream type for the profile |
[in] | format | binary data format of the profile |
[in] | index | stream index the profile in case there are multiple streams of the same type |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
void rs2_start | ( | const rs2_sensor * | sensor, |
rs2_frame_callback_ptr | on_frame, | ||
void * | user, | ||
rs2_error ** | error | ||
) |
start streaming from specified configured sensor
[in] | sensor | RealSense device |
[in] | on_frame | function pointer to register as per-frame callback |
[in] | user | auxiliary data the user wishes to receive together with every frame callback |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
void rs2_start_cpp | ( | const rs2_sensor * | sensor, |
rs2_frame_callback * | callback, | ||
rs2_error ** | error | ||
) |
start streaming from specified configured sensor
[in] | sensor | RealSense device |
[in] | callback | callback object created from c++ application. ownership over the callback object is moved into the relevant streaming lock |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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
[in] | sensor | RealSense Sensor |
[in] | queue | frame-queue to store new frames into |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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 | ||
) |
Try to extend stream profile to an extension type
[in] | mode | input stream profile |
[in] | type | extension type, for example RS2_EXTENSION_VIDEO_STREAM_PROFILE |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |
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 | ||
) |
check if specific sensor info is supported
[in] | info | the parameter to check for support |
[out] | error | if non-null, receives any error that occurs during this call, otherwise, errors are ignored |