Typedefs | Enumerations | Functions
rs_frame.h File Reference

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

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

Go to the source code of this file.

Typedefs

typedef enum rs2_calib_target_type rs2_calib_target_type
 Calibration target type. More...
 
typedef enum rs2_frame_metadata_value rs2_frame_metadata_value
 Per-Frame-Metadata is the set of read-only properties that might be exposed for each individual frame. More...
 
typedef enum rs2_timestamp_domain rs2_timestamp_domain
 Specifies the clock in relation to which the frame timestamp was measured. More...
 

Enumerations

enum  rs2_calib_target_type { RS2_CALIB_TARGET_RECT_GAUSSIAN_DOT_VERTICES, RS2_CALIB_TARGET_COUNT }
 Calibration target type. More...
 
enum  rs2_frame_metadata_value {
  RS2_FRAME_METADATA_FRAME_COUNTER, RS2_FRAME_METADATA_FRAME_TIMESTAMP, RS2_FRAME_METADATA_SENSOR_TIMESTAMP, RS2_FRAME_METADATA_ACTUAL_EXPOSURE,
  RS2_FRAME_METADATA_GAIN_LEVEL, RS2_FRAME_METADATA_AUTO_EXPOSURE, RS2_FRAME_METADATA_WHITE_BALANCE, RS2_FRAME_METADATA_TIME_OF_ARRIVAL,
  RS2_FRAME_METADATA_TEMPERATURE, RS2_FRAME_METADATA_BACKEND_TIMESTAMP, RS2_FRAME_METADATA_ACTUAL_FPS, RS2_FRAME_METADATA_FRAME_LASER_POWER,
  RS2_FRAME_METADATA_FRAME_LASER_POWER_MODE, RS2_FRAME_METADATA_EXPOSURE_PRIORITY, RS2_FRAME_METADATA_EXPOSURE_ROI_LEFT, RS2_FRAME_METADATA_EXPOSURE_ROI_RIGHT,
  RS2_FRAME_METADATA_EXPOSURE_ROI_TOP, RS2_FRAME_METADATA_EXPOSURE_ROI_BOTTOM, RS2_FRAME_METADATA_BRIGHTNESS, RS2_FRAME_METADATA_CONTRAST,
  RS2_FRAME_METADATA_SATURATION, RS2_FRAME_METADATA_SHARPNESS, RS2_FRAME_METADATA_AUTO_WHITE_BALANCE_TEMPERATURE, RS2_FRAME_METADATA_BACKLIGHT_COMPENSATION,
  RS2_FRAME_METADATA_HUE, RS2_FRAME_METADATA_GAMMA, RS2_FRAME_METADATA_MANUAL_WHITE_BALANCE, RS2_FRAME_METADATA_POWER_LINE_FREQUENCY,
  RS2_FRAME_METADATA_LOW_LIGHT_COMPENSATION, RS2_FRAME_METADATA_FRAME_EMITTER_MODE, RS2_FRAME_METADATA_FRAME_LED_POWER, RS2_FRAME_METADATA_RAW_FRAME_SIZE,
  RS2_FRAME_METADATA_GPIO_INPUT_DATA, RS2_FRAME_METADATA_SEQUENCE_NAME, RS2_FRAME_METADATA_SEQUENCE_ID, RS2_FRAME_METADATA_SEQUENCE_SIZE,
  RS2_FRAME_METADATA_COUNT
}
 Per-Frame-Metadata is the set of read-only properties that might be exposed for each individual frame. More...
 
enum  rs2_timestamp_domain { RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK, RS2_TIMESTAMP_DOMAIN_SYSTEM_TIME, RS2_TIMESTAMP_DOMAIN_GLOBAL_TIME, RS2_TIMESTAMP_DOMAIN_COUNT }
 Specifies the clock in relation to which the frame timestamp was measured. More...
 

Functions

rs2_framers2_allocate_composite_frame (rs2_source *source, rs2_frame **frames, int count, rs2_error **error)
 
rs2_framers2_allocate_points (rs2_source *source, const rs2_stream_profile *new_stream, rs2_frame *original, rs2_error **error)
 
rs2_framers2_allocate_synthetic_motion_frame (rs2_source *source, const rs2_stream_profile *new_stream, rs2_frame *original, rs2_extension frame_type, rs2_error **error)
 
rs2_framers2_allocate_synthetic_video_frame (rs2_source *source, const rs2_stream_profile *new_stream, rs2_frame *original, int new_bpp, int new_width, int new_height, int new_stride, rs2_extension frame_type, rs2_error **error)
 
const char * rs2_calib_target_type_to_string (rs2_calib_target_type type)
 
float rs2_depth_frame_get_units (const rs2_frame *frame, rs2_error **error)
 
int rs2_embedded_frames_count (rs2_frame *composite, rs2_error **error)
 
void rs2_export_to_ply (const rs2_frame *frame, const char *fname, rs2_frame *texture, rs2_error **error)
 
rs2_framers2_extract_frame (rs2_frame *composite, int index, rs2_error **error)
 
void rs2_extract_target_dimensions (const rs2_frame *frame, rs2_calib_target_type calib_type, float *target_dims, unsigned int target_dims_size, rs2_error **error)
 
void rs2_frame_add_ref (rs2_frame *frame, rs2_error **error)
 
const char * rs2_frame_metadata_to_string (rs2_frame_metadata_value metadata)
 
const char * rs2_frame_metadata_value_to_string (rs2_frame_metadata_value metadata)
 
int rs2_get_frame_bits_per_pixel (const rs2_frame *frame, rs2_error **error)
 
const voidrs2_get_frame_data (const rs2_frame *frame, rs2_error **error)
 
int rs2_get_frame_data_size (const rs2_frame *frame, rs2_error **error)
 
int rs2_get_frame_height (const rs2_frame *frame, rs2_error **error)
 
rs2_metadata_type rs2_get_frame_metadata (const rs2_frame *frame, rs2_frame_metadata_value frame_metadata, rs2_error **error)
 
unsigned long long rs2_get_frame_number (const rs2_frame *frame, rs2_error **error)
 
int rs2_get_frame_points_count (const rs2_frame *frame, rs2_error **error)
 
rs2_sensorrs2_get_frame_sensor (const rs2_frame *frame, rs2_error **error)
 
const rs2_stream_profilers2_get_frame_stream_profile (const rs2_frame *frame, rs2_error **error)
 
int rs2_get_frame_stride_in_bytes (const rs2_frame *frame, rs2_error **error)
 
rs2_pixelrs2_get_frame_texture_coordinates (const rs2_frame *frame, rs2_error **error)
 
rs2_time_t rs2_get_frame_timestamp (const rs2_frame *frame, rs2_error **error)
 
rs2_timestamp_domain rs2_get_frame_timestamp_domain (const rs2_frame *frameset, rs2_error **error)
 
rs2_vertexrs2_get_frame_vertices (const rs2_frame *frame, rs2_error **error)
 
int rs2_get_frame_width (const rs2_frame *frame, rs2_error **error)
 
int rs2_is_frame_extendable_to (const rs2_frame *frame, rs2_extension extension_type, rs2_error **error)
 
void rs2_keep_frame (rs2_frame *frame)
 
void rs2_pose_frame_get_pose_data (const rs2_frame *frame, rs2_pose *pose, rs2_error **error)
 
void rs2_release_frame (rs2_frame *frame)
 
int rs2_supports_frame_metadata (const rs2_frame *frame, rs2_frame_metadata_value frame_metadata, rs2_error **error)
 
void rs2_synthetic_frame_ready (rs2_source *source, rs2_frame *frame, rs2_error **error)
 
const char * rs2_timestamp_domain_to_string (rs2_timestamp_domain info)
 

Detailed Description

Exposes RealSense frame functionality for C compilers.

Definition in file rs_frame.h.

Typedef Documentation

Calibration target type.

Per-Frame-Metadata is the set of read-only properties that might be exposed for each individual frame.

Specifies the clock in relation to which the frame timestamp was measured.

Enumeration Type Documentation

Calibration target type.

Enumerator
RS2_CALIB_TARGET_RECT_GAUSSIAN_DOT_VERTICES 

Flat rectangle with vertices as the centers of Gaussian dots

RS2_CALIB_TARGET_COUNT 

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

Definition at line 74 of file rs_frame.h.

Per-Frame-Metadata is the set of read-only properties that might be exposed for each individual frame.

Enumerator
RS2_FRAME_METADATA_FRAME_COUNTER 

A sequential index managed per-stream. Integer value

RS2_FRAME_METADATA_FRAME_TIMESTAMP 

Timestamp set by device clock when data readout and transmit commence. usec

RS2_FRAME_METADATA_SENSOR_TIMESTAMP 

Timestamp of the middle of sensor's exposure calculated by device. usec

RS2_FRAME_METADATA_ACTUAL_EXPOSURE 

Sensor's exposure width. When Auto Exposure (AE) is on the value is controlled by firmware. usec

RS2_FRAME_METADATA_GAIN_LEVEL 

A relative value increasing which will increase the Sensor's gain factor. \ When AE is set On, the value is controlled by firmware. Integer value

RS2_FRAME_METADATA_AUTO_EXPOSURE 

Auto Exposure Mode indicator. Zero corresponds to AE switched off.

RS2_FRAME_METADATA_WHITE_BALANCE 

White Balance setting as a color temperature. Kelvin degrees

RS2_FRAME_METADATA_TIME_OF_ARRIVAL 

Time of arrival in system clock

RS2_FRAME_METADATA_TEMPERATURE 

Temperature of the device, measured at the time of the frame capture. Celsius degrees

RS2_FRAME_METADATA_BACKEND_TIMESTAMP 

Timestamp get from uvc driver. usec

RS2_FRAME_METADATA_ACTUAL_FPS 

Actual fps

RS2_FRAME_METADATA_FRAME_LASER_POWER 

Laser power value 0-360.

RS2_FRAME_METADATA_FRAME_LASER_POWER_MODE 

Laser power mode. Zero corresponds to Laser power switched off and one for switched on. deprecated, replaced by RS2_FRAME_METADATA_FRAME_EMITTER_MODE

RS2_FRAME_METADATA_EXPOSURE_PRIORITY 

Exposure priority.

RS2_FRAME_METADATA_EXPOSURE_ROI_LEFT 

Left region of interest for the auto exposure Algorithm.

RS2_FRAME_METADATA_EXPOSURE_ROI_RIGHT 

Right region of interest for the auto exposure Algorithm.

RS2_FRAME_METADATA_EXPOSURE_ROI_TOP 

Top region of interest for the auto exposure Algorithm.

RS2_FRAME_METADATA_EXPOSURE_ROI_BOTTOM 

Bottom region of interest for the auto exposure Algorithm.

RS2_FRAME_METADATA_BRIGHTNESS 

Color image brightness.

RS2_FRAME_METADATA_CONTRAST 

Color image contrast.

RS2_FRAME_METADATA_SATURATION 

Color image saturation.

RS2_FRAME_METADATA_SHARPNESS 

Color image sharpness.

RS2_FRAME_METADATA_AUTO_WHITE_BALANCE_TEMPERATURE 

Auto white balance temperature Mode indicator. Zero corresponds to automatic mode switched off.

RS2_FRAME_METADATA_BACKLIGHT_COMPENSATION 

Color backlight compensation. Zero corresponds to switched off.

RS2_FRAME_METADATA_HUE 

Color image hue.

RS2_FRAME_METADATA_GAMMA 

Color image gamma.

RS2_FRAME_METADATA_MANUAL_WHITE_BALANCE 

Color image white balance.

RS2_FRAME_METADATA_POWER_LINE_FREQUENCY 

Power Line Frequency for anti-flickering Off/50Hz/60Hz/Auto.

RS2_FRAME_METADATA_LOW_LIGHT_COMPENSATION 

Color lowlight compensation. Zero corresponds to switched off.

RS2_FRAME_METADATA_FRAME_EMITTER_MODE 

Emitter mode: 0 - all emitters disabled. 1 - laser enabled. 2 - auto laser enabled (opt). 3 - LED enabled (opt).

RS2_FRAME_METADATA_FRAME_LED_POWER 

Led power value 0-360.

RS2_FRAME_METADATA_RAW_FRAME_SIZE 

The number of transmitted payload bytes, not including metadata

RS2_FRAME_METADATA_GPIO_INPUT_DATA 

GPIO input data

RS2_FRAME_METADATA_SEQUENCE_NAME 

sub-preset id

RS2_FRAME_METADATA_SEQUENCE_ID 

sub-preset sequence id

RS2_FRAME_METADATA_SEQUENCE_SIZE 

sub-preset sequence size

RS2_FRAME_METADATA_COUNT 

Definition at line 29 of file rs_frame.h.

Specifies the clock in relation to which the frame timestamp was measured.

Enumerator
RS2_TIMESTAMP_DOMAIN_HARDWARE_CLOCK 

Frame timestamp was measured in relation to the camera clock

RS2_TIMESTAMP_DOMAIN_SYSTEM_TIME 

Frame timestamp was measured in relation to the OS system clock

RS2_TIMESTAMP_DOMAIN_GLOBAL_TIME 

Frame timestamp was measured in relation to the camera clock and converted to OS system clock by constantly measure the difference

RS2_TIMESTAMP_DOMAIN_COUNT 

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

Definition at line 19 of file rs_frame.h.

Function Documentation

rs2_frame* rs2_allocate_composite_frame ( rs2_source source,
rs2_frame **  frames,
int  count,
rs2_error **  error 
)

Allocate new composite frame, aggregating a set of existing frames

Parameters
[in]sourceFrame pool to allocate the frame from
[in]framesArray of existing frames
[in]countNumber of input frames
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
reference to a newly allocated frame, must be released with release_frame when composite frame gets released it will automatically release all of the input frames

Definition at line 2127 of file rs.cpp.

rs2_frame* rs2_allocate_points ( rs2_source source,
const rs2_stream_profile new_stream,
rs2_frame original,
rs2_error **  error 
)

Allocate new points frame using a frame-source provided from a processing block

Parameters
[in]sourceFrame pool to allocate the frame from
[in]new_streamNew stream profile to assign to newly created frame
[in]originalA reference frame that can be used to fill in auxilary information like format, width, height, bpp, stride (if applicable)
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
reference to a newly allocated frame, must be released with release_frame memory for the frame is likely to be re-used from previous frame, but in lack of available frames in the pool will be allocated from the free store

Definition at line 1732 of file rs.cpp.

rs2_frame* rs2_allocate_synthetic_motion_frame ( rs2_source source,
const rs2_stream_profile new_stream,
rs2_frame original,
rs2_extension  frame_type,
rs2_error **  error 
)

Allocate new motion frame using a frame-source provided form a processing block

Parameters
[in]sourceFrame pool to allocate the frame from
[in]new_streamNew stream profile to assign to newly created frame
[in]originalA reference frame that can be used to fill in auxilary information like format, width, height, bpp, stride (if applicable)
[in]frame_typeNew value for frame type for the allocated frame
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
reference to a newly allocated frame, must be released with release_frame memory for the frame is likely to be re-used from previous frame, but in lack of available frames in the pool will be allocated from the free store

Definition at line 1718 of file rs.cpp.

rs2_frame* rs2_allocate_synthetic_video_frame ( rs2_source source,
const rs2_stream_profile new_stream,
rs2_frame original,
int  new_bpp,
int  new_width,
int  new_height,
int  new_stride,
rs2_extension  frame_type,
rs2_error **  error 
)

Allocate new video frame using a frame-source provided form a processing block

Parameters
[in]sourceFrame pool to allocate the frame from
[in]new_streamNew stream profile to assign to newly created frame
[in]originalA reference frame that can be used to fill in auxilary information like format, width, height, bpp, stride (if applicable)
[in]new_bppNew value for bits per pixel for the allocated frame
[in]new_widthNew value for width for the allocated frame
[in]new_heightNew value for height for the allocated frame
[in]new_strideNew value for stride in bytes for the allocated frame
[in]frame_typeNew value for frame type for the allocated frame
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
reference to a newly allocated frame, must be released with release_frame memory for the frame is likely to be re-used from previous frame, but in lack of available frames in the pool will be allocated from the free store

Definition at line 1704 of file rs.cpp.

const char* rs2_calib_target_type_to_string ( rs2_calib_target_type  type)

Definition at line 1269 of file rs.cpp.

float rs2_depth_frame_get_units ( const rs2_frame frame,
rs2_error **  error 
)

retrieve the scaling factor to use when converting a depth frame's get_data() units to meters

Returns
float - depth, in meters, per 1 unit stored in the frame data

Definition at line 2356 of file rs.cpp.

int rs2_embedded_frames_count ( rs2_frame composite,
rs2_error **  error 
)

Get number of frames embedded within a composite frame

Parameters
[in]compositeComposite input frame
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
Number of embedded frames

Definition at line 2144 of file rs.cpp.

void rs2_export_to_ply ( const rs2_frame frame,
const char *  fname,
rs2_frame texture,
rs2_error **  error 
)

When called on Points frame type, this method creates a ply file of the model with the given file name.

Parameters
[in]framePoints frame
[in]fnameThe name for the ply file
[in]textureTexture frame
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 2162 of file rs.cpp.

rs2_frame* rs2_extract_frame ( rs2_frame composite,
int  index,
rs2_error **  error 
)

Extract frame from within a composite frame

Parameters
[in]compositeComposite frame
[in]indexIndex of the frame to extract within the composite frame
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
returns reference to a frame existing within the composite frame If you wish to keep this frame after the composite is released, you need to call acquire_ref Otherwise the resulting frame lifetime is bound by owning composite frame

Definition at line 2114 of file rs.cpp.

void rs2_extract_target_dimensions ( const rs2_frame frame,
rs2_calib_target_type  calib_type,
float *  target_dims,
unsigned int  target_dims_size,
rs2_error **  error 
)

Extract the target dimensions on the specific target

Parameters
[in]frameLeft or right camera frame of specified size based on the target type
[in]calib_typeCalibration target type
[in]target_dims_sizeTarget dimension array size
[out]target_dimsThe array to hold the result target dimensions calculated. For type RS2_CALIB_TARGET_RECT_GAUSSIAN_DOT_VERTICES, the four rectangle side sizes in pixels with the order of top, bottom, left, and right
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 2402 of file rs.cpp.

void rs2_frame_add_ref ( rs2_frame frame,
rs2_error **  error 
)

create additional reference to a frame without duplicating frame data

Parameters
[in]framehandle returned from a callback
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
new frame reference, has to be released by rs2_release_frame

Definition at line 1015 of file rs.cpp.

const char* rs2_frame_metadata_to_string ( rs2_frame_metadata_value  metadata)

Definition at line 1275 of file rs.cpp.

const char* rs2_frame_metadata_value_to_string ( rs2_frame_metadata_value  metadata)

Definition at line 1277 of file rs.cpp.

int rs2_get_frame_bits_per_pixel ( const rs2_frame frame,
rs2_error **  error 
)

retrieve bits per pixels in the frame image (note that bits per pixel is not necessarily divided by 8, as in 12bpp)

Parameters
[in]framehandle returned from a callback
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
bits per pixel

Definition at line 978 of file rs.cpp.

const void* rs2_get_frame_data ( const rs2_frame frame,
rs2_error **  error 
)

retrieve data from frame handle

Parameters
[in]framehandle returned from a callback
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
the pointer to the start of the frame data

Definition at line 940 of file rs.cpp.

int rs2_get_frame_data_size ( const rs2_frame frame,
rs2_error **  error 
)

retrieve data size from frame handle

Parameters
[in]framehandle returned from a callback
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
the size of the frame data

Definition at line 933 of file rs.cpp.

int rs2_get_frame_height ( const rs2_frame frame,
rs2_error **  error 
)

retrieve frame height in pixels

Parameters
[in]framehandle returned from a callback
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
frame height in pixels

Definition at line 955 of file rs.cpp.

rs2_metadata_type rs2_get_frame_metadata ( const rs2_frame frame,
rs2_frame_metadata_value  frame_metadata,
rs2_error **  error 
)

retrieve metadata from frame handle

Parameters
[in]framehandle returned from a callback
[in]frame_metadatathe rs2_frame_metadata whose latest frame we are interested in
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
the metadata value

Definition at line 846 of file rs.cpp.

unsigned long long rs2_get_frame_number ( const rs2_frame frame,
rs2_error **  error 
)

retrieve frame number from frame handle

Parameters
[in]framehandle returned from a callback
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
the frame nubmer of the frame, in milliseconds since the device was started

Definition at line 986 of file rs.cpp.

int rs2_get_frame_points_count ( const rs2_frame frame,
rs2_error **  error 
)

When called on Points frame type, this method returns the number of vertices in the frame

Parameters
[in]framePoints frame
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
Number of vertices

Definition at line 2179 of file rs.cpp.

rs2_sensor* rs2_get_frame_sensor ( const rs2_frame frame,
rs2_error **  error 
)

retrieve frame parent sensor from frame handle

Parameters
[in]framehandle returned from a callback
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
the parent sensor of the frame

Definition at line 922 of file rs.cpp.

const rs2_stream_profile* rs2_get_frame_stream_profile ( const rs2_frame frame,
rs2_error **  error 
)

Returns the stream profile that was used to start the stream of this frame

Parameters
[in]frameframe reference, owned by the user
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
Pointer to the stream profile object, lifetime is managed elsewhere

Definition at line 971 of file rs.cpp.

int rs2_get_frame_stride_in_bytes ( const rs2_frame frame,
rs2_error **  error 
)

retrieve frame stride in bytes (number of bytes from start of line N to start of line N+1)

Parameters
[in]framehandle returned from a callback
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
stride in bytes

Definition at line 963 of file rs.cpp.

rs2_pixel* rs2_get_frame_texture_coordinates ( const rs2_frame frame,
rs2_error **  error 
)

When called on Points frame type, this method returns a pointer to an array of texture coordinates per vertex Each coordinate represent a (u,v) pair within [0,1] range, to be mapped to texture image

Parameters
[in]framePoints frame
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
Pointer to an array of texture coordinates, lifetime is managed by the frame

Definition at line 2171 of file rs.cpp.

rs2_time_t rs2_get_frame_timestamp ( const rs2_frame frame,
rs2_error **  error 
)

retrieve timestamp from frame handle in milliseconds

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

Definition at line 908 of file rs.cpp.

rs2_timestamp_domain rs2_get_frame_timestamp_domain ( const rs2_frame frameset,
rs2_error **  error 
)

retrieve timestamp domain from frame handle. timestamps can only be comparable if they are in common domain (for example, depth timestamp might come from system time while color timestamp might come from the device) this method is used to check if two timestamp values are comparable (generated from the same clock)

Parameters
[in]framesethandle returned from a callback
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
the timestamp domain of the frame (camera / microcontroller / system time)

Definition at line 915 of file rs.cpp.

rs2_vertex* rs2_get_frame_vertices ( const rs2_frame frame,
rs2_error **  error 
)

When called on Points frame type, this method returns a pointer to an array of 3D vertices of the model The coordinate system is: X right, Y up, Z away from the camera. Units: Meters

Parameters
[in]framePoints frame
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
Pointer to an array of vertices, lifetime is managed by the frame

Definition at line 2154 of file rs.cpp.

int rs2_get_frame_width ( const rs2_frame frame,
rs2_error **  error 
)

retrieve frame width in pixels

Parameters
[in]framehandle returned from a callback
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
frame width in pixels

Definition at line 947 of file rs.cpp.

int rs2_is_frame_extendable_to ( const rs2_frame frame,
rs2_extension  extension_type,
rs2_error **  error 
)

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

Parameters
[in]frameRealsense frame
[in]extension_typeThe extension to which the frame 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 frame can be extended to the given extension

Definition at line 1461 of file rs.cpp.

void rs2_keep_frame ( rs2_frame frame)

communicate to the library you intend to keep the frame alive for a while this will remove the frame from the regular count of the frame pool once this function is called, the SDK can no longer guarantee 0-allocations during frame cycling

Parameters
[in]framehandle returned from a callback

Definition at line 1000 of file rs.cpp.

void rs2_pose_frame_get_pose_data ( const rs2_frame frame,
rs2_pose pose,
rs2_error **  error 
)

When called on Pose frame type, this method returns the transformation represented by the pose data

Parameters
[in]framePose frame
[out]posePointer to a user allocated struct, which contains the pose info after a successful return
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 2372 of file rs.cpp.

void rs2_release_frame ( rs2_frame frame)

relases the frame handle

Parameters
[in]framehandle returned from a callback

Definition at line 993 of file rs.cpp.

int rs2_supports_frame_metadata ( const rs2_frame frame,
rs2_frame_metadata_value  frame_metadata,
rs2_error **  error 
)

determine device metadata

Parameters
[in]framehandle returned from a callback
[in]frame_metadatathe metadata to check for support
[out]errorif non-null, receives any error that occurs during this call, otherwise, errors are ignored
Returns
true if device has this metadata

Definition at line 838 of file rs.cpp.

void rs2_synthetic_frame_ready ( rs2_source source,
rs2_frame frame,
rs2_error **  error 
)

This method will dispatch frame callback on a frame

Parameters
[in]sourceFrame pool provided by the processing block
[in]frameFrame to dispatch, frame ownership is passed to this function, so you don't have to call release_frame after it
[out]errorIf non-null, receives any error that occurs during this call, otherwise, errors are ignored

Definition at line 1745 of file rs.cpp.

const char* rs2_timestamp_domain_to_string ( rs2_timestamp_domain  info)

Definition at line 1267 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