Struct Rotation3

Source
pub struct Rotation3<S>(/* private fields */)
where
    S: Ring + MaybeSerDes;
Expand description

Orthogonal 3x3 matrix with determinant +1, i.e. a member of the 3D rotation group $SO(3)$ of special orthogonal matrices

Implementations§

Source§

impl<S> Rotation3<S>
where S: Ring + MaybeSerDes,

Source

pub fn identity() -> Self

Identity rotation

Source

pub fn from_angle_x(angle: Rad<S>) -> Self
where S: Real,

Construct a rotation around the X axis.

Positive angles are counter-clockwise.

Source

pub fn from_angle_y(angle: Rad<S>) -> Self
where S: Real,

Construct a rotation around the Y axis

Positive angles are counter-clockwise.

Source

pub fn from_angle_z(angle: Rad<S>) -> Self
where S: Real,

Construct a rotation around the Z axis

Positive angles are counter-clockwise.

Source

pub fn from_angles_intrinsic(yaw: Rad<S>, pitch: Rad<S>, roll: Rad<S>) -> Self
where S: Real,

Construct a rotation from intrinsic ZX’Y’’ Euler angles:

  • yaw: rotation around Z axis
  • pitch: rotation around X’ axis
  • roll: rotation around Y’’ axis
Source

pub fn from_axis_angle(axis: Vector3<S>, angle: Rad<S>) -> Self
where S: Real,

Construct a rotation around the given axis vector with the given angle

Source

pub fn orthonormalize( v1: Vector3<S>, v2: Vector3<S>, v3: Vector3<S>, ) -> Option<Self>
where S: Field + Sqrt,

Construct an orthonormal matrix from a set of linearly-independent vectors using the Gram-Schmidt process

Source

pub fn look_at(point: Point3<S>) -> Self
where S: Float + FloatConst + RelativeEq<Epsilon = S> + Debug,

Returns a rotation with zero roll and oriented towards the target point.

Returns the identity rotation if point is the origin.

Source

pub fn new(mat: Matrix3<S>) -> Option<Self>

Returns None if called with a matrix that is not orthonormal with determinant +1.

This method checks whether mat * mat^T == I and mat.determinant() == 1.

Source

pub fn new_approx(mat: Matrix3<S>) -> Option<Self>
where S: RelativeEq<Epsilon = S>,

Returns None if called with a matrix that is not orthonormal with determinant +1.

This method checks whether mat * mat^T == I and mat.determinant() == 1 (approximately using relative equality).

Source

pub fn noisy(mat: Matrix3<S>) -> Self

Panic if the given matrix is not orthogonal with determinant +1.

This method checks whether mat * mat^T == I and mat.determinant() == 1.

Source

pub fn noisy_approx(mat: Matrix3<S>) -> Self
where S: RelativeEq<Epsilon = S> + Debug,

Panic if the given matrix is not orthogonal with determinant +1.

This method checks whether mat * mat^T == I and mat.determinant() == 1 (approximately using relative equality).

Source

pub fn unchecked(mat: Matrix3<S>) -> Self
where S: Debug,

It is a debug panic if the given matrix is not orthogonal with determinant +1.

This method checks whether mat * mat^T == I and mat.determinant() == 1.

Source

pub fn unchecked_approx(mat: Matrix3<S>) -> Self
where S: RelativeEq<Epsilon = S> + Debug,

It is a debug panic if the given matrix is not orthogonal with determinant +1.

This method checks whether mat * mat^T == I and mat.determinant() == 1 (approximately using relative equality).

Source

pub fn intrinsic_angles(&self) -> (Rad<S>, Rad<S>, Rad<S>)
where S: Real,

Return intrinsic yaw (Z), pitch (X’), roll (Y’’) angles.

NOTE: this function returns the raw output of the atan2 operations used to compute the angles. This function returns values in the range [-\pi, \pi].

Source

pub fn versor(self) -> Versor<S>
where S: Real + MaybeSerDes + Real + RelativeEq<Epsilon = S>,

Convert to versor (unit quaternion) representation.

https://stackoverflow.com/a/63745757

Methods from Deref<Target = Matrix3<S>>§

Source

pub const ROW_COUNT: usize = 3usize

Source

pub const COL_COUNT: usize = 3usize

Source

pub fn row_count(&self) -> usize

Convenience for getting the number of rows of this matrix.

Source

pub fn col_count(&self) -> usize

Convenience for getting the number of columns of this matrix.

Source

pub fn is_packed(&self) -> bool

Are all elements of this matrix tightly packed together in memory ?

This might not be the case for matrices in the repr_simd module (it depends on the target architecture).

Source

pub fn as_col_ptr(&self) -> *const T

Gets a const pointer to this matrix’s elements.

§Panics

Panics if the matrix’s elements are not tightly packed in memory, which may be the case for matrices in the repr_simd module. You may check this with the is_packed() method.

Source

pub fn as_col_slice(&self) -> &[T]

View this matrix as an immutable slice.

§Panics

Panics if the matrix’s elements are not tightly packed in memory, which may be the case for matrices in the repr_simd module. You may check this with the is_packed() method.

Source

pub const GL_SHOULD_TRANSPOSE: bool = false

Source

pub fn gl_should_transpose(&self) -> bool

Gets the transpose parameter to pass to OpenGL glUniformMatrix*() functions.

The return value is a plain bool which you may directly cast to a GLboolean.

This takes &self to prevent surprises when changing the type of matrix you plan to send.

Trait Implementations§

Source§

impl<S> Clone for Rotation3<S>
where S: Ring + MaybeSerDes + Clone,

Source§

fn clone(&self) -> Rotation3<S>

Returns a duplicate of the value. Read more
1.0.0 · Source§

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

Performs copy-assignment from source. Read more
Source§

impl<S> Debug for Rotation3<S>
where S: Ring + MaybeSerDes + Debug,

Source§

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

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

impl<S> Default for Rotation3<S>
where S: Ring + MaybeSerDes + Default,

Source§

fn default() -> Rotation3<S>

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

impl<S> Deref for Rotation3<S>
where S: Ring + MaybeSerDes,

Source§

type Target = Mat3<S>

The resulting type after dereferencing.
Source§

fn deref(&self) -> &Self::Target

Dereferences the value.
Source§

impl<S> Div for Rotation3<S>
where S: Ring + MaybeSerDes,

Source§

type Output = Rotation3<S>

The resulting type after applying the / operator.
Source§

fn div(self, rhs: Self) -> Self::Output

Performs the / operation. Read more
Source§

impl<S> DivAssign for Rotation3<S>
where S: Ring + MaybeSerDes,

Source§

fn div_assign(&mut self, rhs: Self)

Performs the /= operation. Read more
Source§

impl<S> From<Angles3<S>> for Rotation3<S>
where S: Real + MaybeSerDes + Real,

Source§

fn from(angles: Angles3<S>) -> Self

Converts to this type from the input type.
Source§

impl<S> From<Rotation3<S>> for Angles3<S>
where S: Real + MaybeSerDes,

Source§

fn from(rotation: Rotation3<S>) -> Self

Converts to this type from the input type.
Source§

impl<S> From<Rotation3<S>> for Versor<S>
where S: Real + MaybeSerDes + Real + RelativeEq<Epsilon = S>,

Source§

fn from(rot: Rotation3<S>) -> Self

Converts to this type from the input type.
Source§

impl<S> Inv for Rotation3<S>
where S: Ring + MaybeSerDes,

Source§

type Output = Rotation3<S>

The result after applying the operator.
Source§

fn inv(self) -> Self::Output

Returns the multiplicative inverse of self. Read more
Source§

impl<S> Mul<Rotation3<S>> for Vector3<S>
where S: Ring + MaybeSerDes,

Source§

type Output = Vec3<S>

The resulting type after applying the * operator.
Source§

fn mul(self, rhs: Rotation3<S>) -> Self::Output

Performs the * operation. Read more
Source§

impl<S> Mul<Vec3<S>> for Rotation3<S>
where S: Ring + MaybeSerDes,

Source§

type Output = Vec3<S>

The resulting type after applying the * operator.
Source§

fn mul(self, rhs: Vector3<S>) -> Self::Output

Performs the * operation. Read more
Source§

impl<S> Mul for Rotation3<S>
where S: Ring + MaybeSerDes,

Source§

type Output = Rotation3<S>

The resulting type after applying the * operator.
Source§

fn mul(self, rhs: Self) -> Self::Output

Performs the * operation. Read more
Source§

impl<S> MulAssign for Rotation3<S>
where S: Ring + MaybeSerDes,

Source§

fn mul_assign(&mut self, rhs: Self)

Performs the *= operation. Read more
Source§

impl<S> One for Rotation3<S>
where S: Ring + MaybeSerDes + Zero + One,

Source§

fn one() -> Self

Returns the multiplicative identity element of Self, 1. Read more
Source§

fn set_one(&mut self)

Sets self to the multiplicative identity element of Self, 1.
Source§

fn is_one(&self) -> bool
where Self: PartialEq,

Returns true if self is equal to the multiplicative identity. Read more
Source§

impl<S> PartialEq for Rotation3<S>
where S: Ring + MaybeSerDes + PartialEq,

Source§

fn eq(&self, other: &Rotation3<S>) -> bool

Tests for self and other values to be equal, and is used by ==.
1.0.0 · 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<S> Copy for Rotation3<S>
where S: Ring + MaybeSerDes + Copy,

Source§

impl<S> MultiplicativeGroup for Rotation3<S>
where S: Ring + MaybeSerDes,

Source§

impl<S> MultiplicativeMonoid for Rotation3<S>
where S: Ring + MaybeSerDes,

Source§

impl<S> StructuralPartialEq for Rotation3<S>
where S: Ring + MaybeSerDes,

Auto Trait Implementations§

§

impl<S> Freeze for Rotation3<S>
where S: Freeze,

§

impl<S> RefUnwindSafe for Rotation3<S>
where S: RefUnwindSafe,

§

impl<S> Send for Rotation3<S>
where S: Send,

§

impl<S> Sync for Rotation3<S>
where S: Sync,

§

impl<S> Unpin for Rotation3<S>
where S: Unpin,

§

impl<S> UnwindSafe for Rotation3<S>
where S: UnwindSafe,

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> Az for T

Source§

fn az<Dst>(self) -> Dst
where T: Cast<Dst>,

Casts the value.
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<Src, Dst> CastFrom<Src> for Dst
where Src: Cast<Dst>,

Source§

fn cast_from(src: Src) -> Dst

Casts the value.
Source§

impl<T> CheckedAs for T

Source§

fn checked_as<Dst>(self) -> Option<Dst>
where T: CheckedCast<Dst>,

Casts the value.
Source§

impl<Src, Dst> CheckedCastFrom<Src> for Dst
where Src: CheckedCast<Dst>,

Source§

fn checked_cast_from(src: Src) -> Option<Dst>

Casts the value.
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> IntoEither for T

Source§

fn into_either(self, into_left: bool) -> Either<Self, Self>

Converts self into a Left variant of Either<Self, Self> if into_left is true. Converts self into a Right variant of Either<Self, Self> otherwise. Read more
Source§

fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
where F: FnOnce(&Self) -> bool,

Converts self into a Left variant of Either<Self, Self> if into_left(&self) returns true. Converts self into a Right variant of Either<Self, Self> otherwise. Read more
Source§

impl<Src, Dst> LosslessTryInto<Dst> for Src
where Dst: LosslessTryFrom<Src>,

Source§

fn lossless_try_into(self) -> Option<Dst>

Performs the conversion.
Source§

impl<Src, Dst> LossyInto<Dst> for Src
where Dst: LossyFrom<Src>,

Source§

fn lossy_into(self) -> Dst

Performs the conversion.
Source§

impl<T> OverflowingAs for T

Source§

fn overflowing_as<Dst>(self) -> (Dst, bool)
where T: OverflowingCast<Dst>,

Casts the value.
Source§

impl<Src, Dst> OverflowingCastFrom<Src> for Dst
where Src: OverflowingCast<Dst>,

Source§

fn overflowing_cast_from(src: Src) -> (Dst, bool)

Casts the value.
Source§

impl<P, T> Receiver for P
where P: Deref<Target = T> + ?Sized, T: ?Sized,

Source§

type Target = T

🔬This is a nightly-only experimental API. (arbitrary_self_types)
The target type on which the method may be called.
Source§

impl<T> Same for T

Source§

type Output = T

Should always be Self
Source§

impl<T> SaturatingAs for T

Source§

fn saturating_as<Dst>(self) -> Dst
where T: SaturatingCast<Dst>,

Casts the value.
Source§

impl<Src, Dst> SaturatingCastFrom<Src> for Dst
where Src: SaturatingCast<Dst>,

Source§

fn saturating_cast_from(src: Src) -> Dst

Casts the value.
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.
Source§

impl<T> UnwrappedAs for T

Source§

fn unwrapped_as<Dst>(self) -> Dst
where T: UnwrappedCast<Dst>,

Casts the value.
Source§

impl<Src, Dst> UnwrappedCastFrom<Src> for Dst
where Src: UnwrappedCast<Dst>,

Source§

fn unwrapped_cast_from(src: Src) -> Dst

Casts the value.
Source§

impl<V, T> VZip<V> for T
where V: MultiLane<T>,

Source§

fn vzip(self) -> V

Source§

impl<T> WrappingAs for T

Source§

fn wrapping_as<Dst>(self) -> Dst
where T: WrappingCast<Dst>,

Casts the value.
Source§

impl<Src, Dst> WrappingCastFrom<Src> for Dst
where Src: WrappingCast<Dst>,

Source§

fn wrapping_cast_from(src: Src) -> Dst

Casts the value.
Source§

impl<T> MaybeSerDes for T