Struct PoseFrame

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

Holds information describing the motion and position of a device at a point in time.

Implementations§

Source§

impl PoseFrame

Source

pub fn translation(&self) -> [f32; 3]

X, Y, Z values of translation, in meters (relative to initial position)

Source

pub fn velocity(&self) -> [f32; 3]

X, Y, Z values of velocity, in meters/sec

Source

pub fn acceleration(&self) -> [f32; 3]

X, Y, Z values of acceleration, in meters/sec^2

Source

pub fn rotation(&self) -> [f32; 4]

Qi, Qj, Qk, Qr components of rotation as represented in quaternion rotation (relative to initial position)

Source

pub fn angular_velocity(&self) -> [f32; 3]

X, Y, Z values of angular velocity, in radians/sec

Source

pub fn angular_acceleration(&self) -> [f32; 3]

X, Y, Z values of angular acceleration, in radians/sec^2

Source

pub fn tracker_confidence(&self) -> Confidence

Pose confidence from Confidence::Failed to Confidence::High

Source

pub fn mapper_confidence(&self) -> Confidence

Pose map confidence from Confidence::Failed to Confidence::High

Trait Implementations§

Source§

impl Debug for PoseFrame

Source§

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

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

impl Drop for PoseFrame

Source§

fn drop(&mut self)

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

Source§

impl FrameCategory for PoseFrame

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 PoseFrame

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 PoseFrame

Source§

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

Attempt to construct a PoseFrame from the raw pointer to rs2_frame

All members of the PoseFrame 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 PoseFrame

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.