Struct Skew3

Source
pub struct Skew3(pub Vector3<f64>);
Expand description

Contains a member of the lie algebra so(3), a representation of the tangent space of 3d rotation. This is also known as the lie algebra of the 3d rotation group SO(3).

This is only intended to be used in optimization problems where it is desirable to have unconstranied variables representing the degrees of freedom of the rotation. In all other cases, a rotation matrix should be used to store rotations, since the conversion to and from a rotation matrix is non-trivial.

Tuple Fields§

§0: Vector3<f64>

Implementations§

Source§

impl Skew3

Source

pub fn rotation(self) -> Rotation3<f64>

Converts the Skew3 to a Rotation3 matrix.

Source

pub fn vee(mat: Matrix3<f64>) -> Self

This converts a matrix in skew-symmetric form into a Skew3.

Warning: Does no check to ensure matrix is actually skew-symmetric.

Source

pub fn hat(self) -> Matrix3<f64>

This converts the Skew3 into its skew-symmetric matrix form.

Source

pub fn hat2(self) -> Matrix3<f64>

This converts the Skew3 into its squared skew-symmetric matrix form efficiently.

Source

pub fn bracket(self, rhs: Self) -> Self

Computes the lie bracket [self, rhs].

Source

pub fn jacobian_input(self) -> Matrix4<f64>

The jacobian of the output of a rotation in respect to the input of a rotation.

y = R * x

dy/dx = R

The formula is pretty simple and is just the rotation matrix created from the exponential map of this so(3) element into SO(3). The result is converted to homogeneous form (by adding a new dimension with a 1 in the diagonal) so that it is compatible with homogeneous coordinates.

If you have the rotation matrix already, please use the rotation matrix itself rather than calling this method. Calling this method will waste time converting the Skew3 back into a Rotation3, which is non-trivial.

Source

pub fn jacobian_self(y: Vector3<f64>) -> Matrix3<f64>

The jacobian of the output of a rotation in respect to the rotation itself.

y = R * x

dy/dR = -hat(y)

The derivative is purely based on the current output vector, and thus doesn’t take self.

Note that when working with homogeneous projective coordinates, only the first three components (the bearing) are relevant, hence the resulting matrix is a Matrix3.

Trait Implementations§

Source§

impl AsMut<Matrix<f64, U3, U1, <DefaultAllocator as Allocator<f64, U3>>::Buffer>> for Skew3

Source§

fn as_mut(&mut self) -> &mut Vector3<f64>

Converts this type into a mutable reference of the (usually inferred) input type.
Source§

impl AsRef<Matrix<f64, U3, U1, <DefaultAllocator as Allocator<f64, U3>>::Buffer>> for Skew3

Source§

fn as_ref(&self) -> &Vector3<f64>

Converts this type into a shared reference of the (usually inferred) input type.
Source§

impl Clone for Skew3

Source§

fn clone(&self) -> Skew3

Returns a copy 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 Debug for Skew3

Source§

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

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

impl Deref for Skew3

Source§

type Target = Matrix<f64, U3, U1, <DefaultAllocator as Allocator<f64, U3>>::Buffer>

The resulting type after dereferencing.
Source§

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

Dereferences the value.
Source§

impl DerefMut for Skew3

Source§

fn deref_mut(&mut self) -> &mut Self::Target

Mutably dereferences the value.
Source§

impl From<Matrix<f64, U3, U1, <DefaultAllocator as Allocator<f64, U3>>::Buffer>> for Skew3

Source§

fn from(original: Vector3<f64>) -> Skew3

Converts to this type from the input type.
Source§

impl From<Rotation<f64, U3>> for Skew3

This is the log map.

Source§

fn from(r: Rotation3<f64>) -> Self

Converts to this type from the input type.
Source§

impl From<Skew3> for Vector3<f64>

Source§

fn from(original: Skew3) -> Self

Converts to this type from the input type.
Source§

impl From<Skew3> for Rotation3<f64>

This is the exponential map.

Source§

fn from(w: Skew3) -> Self

Converts to this type from the input type.
Source§

impl PartialEq for Skew3

Source§

fn eq(&self, other: &Skew3) -> 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 PartialOrd for Skew3

Source§

fn partial_cmp(&self, other: &Skew3) -> Option<Ordering>

This method returns an ordering between self and other values if one exists. Read more
1.0.0 · Source§

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

Tests less than (for self and other) and is used by the < operator. Read more
1.0.0 · Source§

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

Tests less than or equal to (for self and other) and is used by the <= operator. Read more
1.0.0 · Source§

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

Tests greater than (for self and other) and is used by the > operator. Read more
1.0.0 · Source§

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

Tests greater than or equal to (for self and other) and is used by the >= operator. Read more
Source§

impl Copy for Skew3

Source§

impl StructuralPartialEq for Skew3

Auto Trait Implementations§

§

impl Freeze for Skew3

§

impl RefUnwindSafe for Skew3

§

impl Send for Skew3

§

impl Sync for Skew3

§

impl Unpin for Skew3

§

impl UnwindSafe for Skew3

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<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> Scalar for T
where T: Copy + PartialEq + Debug + Any,

Source§

fn inlined_clone(&self) -> T

Performance hack: Clone doesn’t get inlined for Copy types in debug mode, so make it inline anyway.
Source§

fn is<T>() -> bool
where T: Scalar,

Tests if Self the same as the type T Read more
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, 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<V, T> VZip<V> for T
where V: MultiLane<T>,

Source§

fn vzip(self) -> V