Skip to main content

Transform3D

Struct Transform3D 

Source
pub struct Transform3D {
    pub tx: f64,
    pub ty: f64,
    pub tz: f64,
    pub rx: f64,
    pub ry: f64,
    pub rz: f64,
}
Expand description

A 3D rigid transformation (rotation + translation).

Internally uses nalgebra Isometry3 with quaternion rotation for gimbal-lock-free composition and inversion. The representation stores translation (tx, ty, tz) and Euler angles (roll, pitch, yaw) in radians for human readability.

§Euler Angle Convention

  • Roll (rx): rotation about X axis
  • Pitch (ry): rotation about Y axis
  • Yaw (rz): rotation about Z axis

Composition order: Rz * Ry * Rx (extrinsic rotations)

§Reference

Diebel (2006), “Representing Attitude: Euler Angles, Unit Quaternions, and Rotation Vectors”

Fields§

§tx: f64

Translation x.

§ty: f64

Translation y.

§tz: f64

Translation z.

§rx: f64

Roll (rotation about X axis) in radians.

§ry: f64

Pitch (rotation about Y axis) in radians.

§rz: f64

Yaw (rotation about Z axis) in radians.

Implementations§

Source§

impl Transform3D

Source

pub fn identity() -> Self

Identity transform.

Source

pub fn translation(tx: f64, ty: f64, tz: f64) -> Self

Creates a translation-only transform.

Source

pub fn new(tx: f64, ty: f64, tz: f64, rx: f64, ry: f64, rz: f64) -> Self

Creates a transform with translation and Euler angles.

Source

pub fn to_isometry(&self) -> Isometry3<f64>

Converts to a nalgebra Isometry3.

Uses the Euler angle convention: Rz * Ry * Rx.

Source

pub fn from_isometry(iso: &Isometry3<f64>) -> Self

Creates from a nalgebra Isometry3.

Source

pub fn apply(&self, x: f64, y: f64, z: f64) -> (f64, f64, f64)

Applies this transform to coordinates.

Source

pub fn apply_point(&self, p: &Point3) -> Point3

Applies this transform to a Point3.

Source

pub fn apply_points(&self, points: &[Point3]) -> Vec<Point3>

Transforms a slice of points.

Source

pub fn then(&self, other: &Self) -> Self

Composes two transforms: applies self first, then other.

Source

pub fn inverse(&self) -> Self

Returns the inverse transform.

Source

pub fn is_identity(&self, epsilon: f64) -> bool

Whether this is approximately an identity transform.

Trait Implementations§

Source§

impl Clone for Transform3D

Source§

fn clone(&self) -> Transform3D

Returns a duplicate of the value. Read more
1.0.0 (const: unstable) · Source§

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more
Source§

impl Copy for Transform3D

Source§

impl Debug for Transform3D

Source§

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

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

impl Default for Transform3D

Source§

fn default() -> Self

Returns the “default value” for a type. Read more
Source§

impl PartialEq for Transform3D

Source§

fn eq(&self, other: &Transform3D) -> bool

Tests for self and other values to be equal, and is used by ==.
1.0.0 (const: unstable) · Source§

fn ne(&self, other: &Rhs) -> bool

Tests for !=. The default implementation is almost always sufficient, and should not be overridden without very good reason.
Source§

impl StructuralPartialEq for Transform3D

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> CloneToUninit for T
where T: Clone,

Source§

unsafe fn clone_to_uninit(&self, dest: *mut u8)

🔬This is a nightly-only experimental API. (clone_to_uninit)
Performs copy-assignment from self to dest. 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> Same for T

Source§

type Output = T

Should always be Self
Source§

impl<T> Scalar for T
where T: 'static + Clone + PartialEq + Debug,

Source§

impl<SS, SP> SupersetOf<SS> for SP
where SS: SubsetOf<SP>,

Source§

fn to_subset(&self) -> Option<SS>

The inverse inclusion map: attempts to construct self from the equivalent element of its superset. Read more
Source§

fn is_in_subset(&self) -> bool

Checks if self is actually part of its subset T (and can be converted to it).
Source§

fn to_subset_unchecked(&self) -> SS

Use with care! Same as self.to_subset but without any property checks. Always succeeds.
Source§

fn from_subset(element: &SS) -> SP

The inclusion map: converts self to the equivalent element of its superset.
Source§

impl<T> ToOwned for T
where T: Clone,

Source§

type Owned = T

The resulting type after obtaining ownership.
Source§

fn to_owned(&self) -> T

Creates owned data from borrowed data, usually by cloning. Read more
Source§

fn clone_into(&self, target: &mut T)

Uses borrowed data to replace owned data, usually by cloning. Read more
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.