4 #ifndef LIBREALSENSE_RS2_FRAME_HPP 5 #define LIBREALSENSE_RS2_FRAME_HPP 14 class processing_block;
20 class video_stream_profile;
115 std::stringstream ss;
131 operator bool()
const {
return _profile !=
nullptr; }
181 explicit operator std::shared_ptr<rs2_stream_profile>() {
return _clone; }
190 std::shared_ptr<rs2_stream_profile>
_clone;
380 other.frame_ref =
nullptr;
401 : frame_ref(other.frame_ref)
403 if (frame_ref) add_ref();
443 operator bool()
const {
return frame_ref !=
nullptr; }
722 return (e ==
nullptr);
728 operator const float*()
const {
return &
x; }
732 operator const float*()
const {
return &u; }
907 auto data =
reinterpret_cast<const float*
>(get_data());
981 foreach_rs([&result, s,
f](
frame frm) {
997 auto frm = first_or_default(s,
f);
998 if (!frm)
throw error(
"Frame of requested stream type was not found!");
1134 throw error(
"Requested index is out of range!");
1137 class iterator :
public std::iterator<std::forward_iterator_tag, frame>
1166 on_frame_function(
frame{ fref });
1172 #endif // LIBREALSENSE_RS2_FRAME_HPP void rs2_register_extrinsics(const rs2_stream_profile *from, const rs2_stream_profile *to, rs2_extrinsics extrin, rs2_error **error)
frame apply_filter(filter_interface &filter)
depth_frame(const frame &f)
void rs2_export_to_ply(const rs2_frame *frame, const char *fname, rs2_frame *texture, rs2_error **error)
float rs2_depth_frame_get_units(const rs2_frame *frame, rs2_error **error)
::realsense_legacy_msgs::extrinsics_< std::allocator< void > > extrinsics
int rs2_get_frame_points_count(const rs2_frame *frame, rs2_error **error)
const rs2_stream_profile * rs2_get_frame_stream_profile(const rs2_frame *frame, rs2_error **error)
rs2_sensor * rs2_get_frame_sensor(const rs2_frame *frame, rs2_error **error)
rs2_motion_device_intrinsic get_motion_intrinsics() const
int rs2_is_frame_extendable_to(const rs2_frame *frame, rs2_extension extension_type, rs2_error **error)
void rs2_get_video_stream_resolution(const rs2_stream_profile *mode, int *width, int *height, rs2_error **error)
void register_extrinsics_to(const stream_profile &to, rs2_extrinsics extrinsics)
rs2_metadata_type get_frame_metadata(rs2_frame_metadata_value frame_metadata) const
void rs2_keep_frame(rs2_frame *frame)
void rs2_get_extrinsics(const rs2_stream_profile *from, const rs2_stream_profile *to, rs2_extrinsics *extrin, rs2_error **error)
rs2_extrinsics get_extrinsics_to(const stream_profile &to) const
stream_profile get_profile() const
bool operator!=(const iterator &other) const
frame operator[](size_t index) const
bool operator==(const iterator &other) const
rs2_calib_target_type
Calibration target type.
std::function< void(frame_interface *)> on_frame
int get_bytes_per_pixel() const
frame(frame &&other) noexcept
const void * get_data() const
bool supports_frame_metadata(rs2_frame_metadata_value frame_metadata) const
void export_to_ply(const std::string &fname, video_frame texture)
rs2_time_t rs2_get_frame_timestamp(const rs2_frame *frame, rs2_error **error)
int rs2_stream_profile_is(const rs2_stream_profile *mode, rs2_extension type, rs2_error **error)
std::string stream_name() const
rs2_pixel * rs2_get_frame_texture_coordinates(const rs2_frame *frame, rs2_error **error)
GLsizei const GLchar *const * string
int rs2_supports_frame_metadata(const rs2_frame *frame, rs2_frame_metadata_value frame_metadata, rs2_error **error)
rs2_stream_profile * rs2_clone_stream_profile(const rs2_stream_profile *mode, rs2_stream stream, int index, rs2_format format, rs2_error **error)
const texture_coordinate * get_texture_coordinates() const
rs2_pose get_pose_data() const
depth_frame get_depth_frame() const
int rs2_get_frame_height(const rs2_frame *frame, rs2_error **error)
std::shared_ptr< rs2_stream_profile > _clone
frame first_or_default(rs2_stream s, rs2_format f=RS2_FORMAT_ANY) const
pose_frame(const frame &f)
bool extract_target_dimensions(rs2_calib_target_type calib_type, float *target_dims, unsigned int target_dims_size) const
frame & operator=(frame other)
video_frame get_color_frame() const
frame_callback(T on_frame)
int rs2_get_frame_stride_in_bytes(const rs2_frame *frame, rs2_error **error)
const rs2_stream_profile * _profile
video_frame(const frame &f)
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_vector get_motion_data() const
frame first(rs2_stream s, rs2_format f=RS2_FORMAT_ANY) const
video_frame get_fisheye_frame(const size_t index=0) const
int rs2_embedded_frames_count(rs2_frame *composite, rs2_error **error)
int rs2_is_stream_profile_default(const rs2_stream_profile *mode, rs2_error **error)
pose_frame get_pose_frame(const size_t index=0) const
motion_frame(const frame &f)
int rs2_get_frame_width(const rs2_frame *frame, rs2_error **error)
float rs2_depth_frame_get_distance(const rs2_frame *frame_ref, int x, int y, rs2_error **error)
double get_timestamp() const
def pointcloud(out, verts, texcoords, color, painter=True)
rs2_timestamp_domain rs2_get_frame_timestamp_domain(const rs2_frame *frameset, rs2_error **error)
void rs2_delete_stream_profile(rs2_stream_profile *mode)
GLint GLsizei GLsizei height
float get_baseline(void) const
motion_stream_profile(const stream_profile &sp)
GLint GLint GLsizei GLint GLenum format
const vertex * get_vertices() const
video_stream_profile(const stream_profile &sp)
rs2_format
A stream's format identifies how binary data is encoded within a frame.
unsigned long long rs2_get_frame_number(const rs2_frame *frame, rs2_error **error)
rs2_intrinsics get_intrinsics() const
void swap(nlohmann::json &j1, nlohmann::json &j2) noexcept(is_nothrow_move_constructible< nlohmann::json >::value andis_nothrow_move_assignable< nlohmann::json >::value)
exchanges the values of two JSON objects
static void handle(rs2_error *e)
rs2_sensor * get_sensor()
int rs2_get_frame_data_size(const rs2_frame *frame, rs2_error **error)
rs2_stream
Streams are different types of data provided by RealSense devices.
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_get_video_stream_intrinsics(const rs2_stream_profile *mode, rs2_intrinsics *intrinsics, rs2_error **error)
void foreach_rs(T action) const
Cross-stream extrinsics: encodes the topology describing how the different devices are oriented...
stream_profile clone(rs2_stream type, int index, rs2_format format, int width, int height, const rs2_intrinsics &intr) const
iterator(const frameset *owner, size_t index=0)
rs2_format format() const
3D vector in Euclidean coordinate space
float get_distance(int x, int y) const
virtual rs2::frame process(rs2::frame frame) const =0
const char * rs2_stream_to_string(rs2_stream stream)
void on_frame(rs2_frame *fref) override
long long rs2_metadata_type
rs2_timestamp_domain get_frame_timestamp_domain() const
const rs2_stream_profile * get() const
int get_bits_per_pixel() const
rs2_vertex * rs2_get_frame_vertices(const rs2_frame *frame, rs2_error **error)
disparity_frame(const frame &f)
void rs2_frame_add_ref(rs2_frame *frame, rs2_error **error)
typename::boost::move_detail::remove_reference< T >::type && move(T &&t) BOOST_NOEXCEPT
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)
bool operator==(const stream_profile &rhs)
Motion device intrinsics: scale, bias, and variances.
const int get_data_size() const
video_frame get_infrared_frame(const size_t index=0) const
float rs2_depth_stereo_frame_get_baseline(const rs2_frame *frame_ref, rs2_error **error)
stream_profile(const rs2_stream_profile *profile)
void rs2_release_frame(rs2_frame *frame)
rs2_frame * rs2_extract_frame(rs2_frame *composite, int index, 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 get_frame_number() const
int get_stride_in_bytes() const
frame(const frame &other)
rs2_stream stream_type() const
void rs2_get_motion_intrinsics(const rs2_stream_profile *mode, rs2_motion_device_intrinsic *intrinsics, rs2_error **error)
bool operator==(const video_stream_profile &other) const
void rs2_pose_frame_get_pose_data(const rs2_frame *frame, rs2_pose *pose, rs2_error **error)
stream_profile clone(rs2_stream type, int index, rs2_format format) const
int rs2_get_frame_bits_per_pixel(const rs2_frame *frame, rs2_error **error)
rs2_frame_metadata_value
Per-Frame-Metadata is the set of read-only properties that might be exposed for each individual frame...
struct rs2_frame rs2_frame
GLdouble GLdouble GLint GLint const GLdouble * points
const void * rs2_get_frame_data(const rs2_frame *frame, rs2_error **error)
pose_stream_profile(const stream_profile &sp)
rs2_timestamp_domain
Specifies the clock in relation to which the frame timestamp was measured.