Intel® RealSense™ Cross Platform API
Intel Realsense Cross-platform API
Public Member Functions | List of all members
rs2::depth_frame Class Reference

#include <rs_frame.hpp>

Inheritance diagram for rs2::depth_frame:
rs2::video_frame rs2::frame rs2::disparity_frame

Public Member Functions

 depth_frame (const frame &f)
 
float get_distance (int x, int y) const
 
float get_units () const
 
- Public Member Functions inherited from rs2::video_frame
 video_frame (const frame &f)
 
int get_width () const
 
int get_height () const
 
int get_stride_in_bytes () const
 
int get_bits_per_pixel () const
 
int get_bytes_per_pixel () const
 
bool extract_target_dimensions (rs2_calib_target_type calib_type, float *target_dims, unsigned int target_dims_size) const
 
- Public Member Functions inherited from rs2::frame
 frame ()
 
 frame (rs2_frame *ref)
 
 frame (frame &&other) noexcept
 
frameoperator= (frame other)
 
 frame (const frame &other)
 
void swap (frame &other)
 
 ~frame ()
 
void keep ()
 
 operator bool () const
 
rs2_sensorget_sensor ()
 
double get_timestamp () const
 
rs2_timestamp_domain get_frame_timestamp_domain () const
 
rs2_metadata_type get_frame_metadata (rs2_frame_metadata_value frame_metadata) const
 
bool supports_frame_metadata (rs2_frame_metadata_value frame_metadata) const
 
unsigned long long get_frame_number () const
 
const int get_data_size () const
 
const void * get_data () const
 
stream_profile get_profile () const
 
template<class T >
bool is () const
 
template<class T >
as () const
 
rs2_frameget () const
 
 operator rs2_frame * ()
 
frame apply_filter (filter_interface &filter)
 

Additional Inherited Members

- Protected Member Functions inherited from rs2::frame
void add_ref () const
 
void reset ()
 

Constructor & Destructor Documentation

◆ depth_frame()

rs2::depth_frame::depth_frame ( const frame f)
inline

Extends the video_frame class with additional depth related attributes and functions

Parameters
[in]frame- existing frame instance

Member Function Documentation

◆ get_distance()

float rs2::depth_frame::get_distance ( int  x,
int  y 
) const
inline

Provide the depth in meters at the given pixel

Parameters
[in]intx - pixel's x coordinate.
[in]inty - pixel's y coordinate.
Returns
float - depth in metric units at given pixel

◆ get_units()

float rs2::depth_frame::get_units ( ) const
inline

Provide the scaling factor to use when converting from get_data() units to meters

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

The documentation for this class was generated from the following file: