Struct PointsFrame

Source
pub struct PointsFrame { /* private fields */ }
Expand description

Holds the raw data pointer and derived data for an RS2 Points frame.

All fields in this struct are initialized during struct creation (via try_from). Everything called from here during runtime should be valid as long as the Frame is in scope… like normal Rust.

Implementations§

Source§

impl PointsFrame

Source

pub fn vertices(&self) -> &[rs2_vertex]

Gets vertices of the point cloud.

Source

pub fn texture_coordinates(&self) -> &[[f32; 2]]

Retrieve the texture coordinates (uv map) for the point cloud.

§Safety

The librealsense2 C++ API directly casts the rs2_pixel* returned from rs2_get_frame_texture_coordinates() into a texture_coordinate*, thereby re-interpreting [[c_int; 2]; N] as [[c_float; 2]; N] values. Note that C does not generally guarantee that sizeof(int) == sizeof(float).

Source

pub fn points_count(&self) -> usize

Gets number of points in the point cloud.

Trait Implementations§

Source§

impl Debug for PointsFrame

Source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result

Formats the value using the given formatter. Read more
Source§

impl Drop for PointsFrame

Source§

fn drop(&mut self)

Drop the raw pointer stored with this struct whenever it goes out of scope.

Source§

impl FrameCategory for PointsFrame

Source§

fn extension() -> Rs2Extension

Identifies the corresponding Rs2Extension for the type implementing this trait.
Source§

fn kind() -> Rs2StreamKind

Identifies the stream kind corresponding to a given type implementing this trait.
Source§

fn has_correct_kind(&self) -> bool

Predicate for checking if the RS2 frame’s stream has the same kind as the frame category.
Source§

impl FrameEx for PointsFrame

Source§

fn stream_profile(&self) -> &StreamProfile

Get the stream profile associated with the frame.
Source§

fn sensor(&self) -> Result<Sensor>

Get the sensor associated with the frame.
Source§

fn timestamp(&self) -> f64

Get the frame timestamp.
Source§

fn timestamp_domain(&self) -> Rs2TimestampDomain

Get the RealSense timestamp domain for the current timestamp.
Source§

fn frame_number(&self) -> u64

Get the frame number.
Source§

fn metadata(&self, metadata_kind: Rs2FrameMetadata) -> Option<c_longlong>

Get frame metadata. Read more
Source§

fn supports_metadata(&self, metadata_kind: Rs2FrameMetadata) -> bool

Test whether the metadata arguemnt is supported by the frame.
Source§

unsafe fn get_owned_raw(self) -> NonNull<rs2_frame>

Get (and own) the underlying frame pointer for this frame. Read more
Source§

impl TryFrom<NonNull<rs2_frame>> for PointsFrame

Source§

fn try_from(frame_ptr: NonNull<rs2_frame>) -> Result<Self, Self::Error>

Attempt to construct a points frame from a raw pointer to rs2_frame

All members of the PointsFrame struct are validated and populated during this call.

§Errors

There are a number of errors that may occur if the data in the rs2_frame is not valid, all of type FrameConstructionError.

See FrameConstructionError documentation for more details.

Source§

type Error = Error

The type returned in the event of a conversion error.
Source§

impl Send for PointsFrame

Auto Trait Implementations§

Blanket Implementations§

Source§

impl<T> Any for T
where T: 'static + ?Sized,

Source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
Source§

impl<T> Borrow<T> for T
where T: ?Sized,

Source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
Source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

Source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

Source§

impl<T, U> Into<U> for T
where U: From<T>,

Source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

Source§

impl<T, U> TryFrom<U> for T
where U: Into<T>,

Source§

type Error = Infallible

The type returned in the event of a conversion error.
Source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
Source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

Source§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
Source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.