Skip to main content

Sim3

Struct Sim3 

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

Sim(3) group element representing similarity transformations in 3D.

Represented as (rotation, translation, scale).

Implementations§

Source§

impl Sim3

Source

pub const DIM: usize = 3

Space dimension - dimension of the ambient space

Source

pub const DOF: usize = 7

Degrees of freedom - dimension of the tangent space

Source

pub const REP_SIZE: usize = 8

Representation size - size of the underlying data representation

Source

pub fn identity() -> Sim3

Get the identity element of the group.

Source

pub fn jacobian_identity() -> Matrix<f64, Const<7>, Const<7>, ArrayStorage<f64, 7, 7>>

Get the identity matrix for Jacobians.

Source

pub fn new( translation: Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>, rotation: Unit<Quaternion<f64>>, scale: f64, ) -> Sim3

Create a new Sim(3) element from translation, rotation, and scale.

§Arguments
  • translation - Translation vector [x, y, z]
  • rotation - Unit quaternion representing rotation
  • scale - Scale factor (must be positive)
Source

pub fn from_components( translation: Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>, rotation: SO3, scale: f64, ) -> Sim3

Create Sim(3) from components.

Source

pub fn translation( &self, ) -> Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>

Get the translation part as a Vector3.

Source

pub fn scale(&self) -> f64

Get the scale factor.

Source

pub fn rotation_so3(&self) -> SO3

Get the rotation part as SO3.

Source

pub fn rotation_quaternion(&self) -> Unit<Quaternion<f64>>

Get the rotation part as a UnitQuaternion.

Source

pub fn rotation_matrix( &self, ) -> Matrix<f64, Const<3>, Const<3>, ArrayStorage<f64, 3, 3>>

Get the rotation matrix (3x3).

Source

pub fn matrix(&self) -> Matrix<f64, Const<4>, Const<4>, ArrayStorage<f64, 4, 4>>

Get the 4x4 homogeneous transformation matrix.

Source

pub fn x(&self) -> f64

Get the x component of translation.

Source

pub fn y(&self) -> f64

Get the y component of translation.

Source

pub fn z(&self) -> f64

Get the z component of translation.

Source

pub fn coeffs(&self) -> [f64; 8]

Get the parameter vector [tx, ty, tz, qw, qx, qy, qz, s].

Trait Implementations§

Source§

impl Clone for Sim3

Source§

fn clone(&self) -> Sim3

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 Display for Sim3

Source§

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

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

impl From<Matrix<f64, Dyn, Const<1>, VecStorage<f64, Dyn, Const<1>>>> for Sim3

Source§

fn from( data: Matrix<f64, Dyn, Const<1>, VecStorage<f64, Dyn, Const<1>>>, ) -> Sim3

Converts to this type from the input type.
Source§

impl From<Sim3> for Matrix<f64, Dyn, Const<1>, VecStorage<f64, Dyn, Const<1>>>

Source§

fn from( sim3: Sim3, ) -> Matrix<f64, Dyn, Const<1>, VecStorage<f64, Dyn, Const<1>>>

Converts to this type from the input type.
Source§

impl LieGroup for Sim3

Source§

fn inverse( &self, jacobian: Option<&mut <Sim3 as LieGroup>::JacobianMatrix>, ) -> Sim3

Get the inverse.

For Sim(3): g^{-1} = (R^T, -R^T * t / s, 1/s)

Source§

fn compose( &self, other: &Sim3, jacobian_self: Option<&mut <Sim3 as LieGroup>::JacobianMatrix>, jacobian_other: Option<&mut <Sim3 as LieGroup>::JacobianMatrix>, ) -> Sim3

Composition of this and another Sim(3) element.

g1 ∘ g2 = (R1R2, s1R1t2 + t1, s1s2)

Source§

fn log( &self, jacobian: Option<&mut <Sim3 as LieGroup>::JacobianMatrix>, ) -> <Sim3 as LieGroup>::TangentVector

Logarithmic map from Sim(3) to its tangent space.

Source§

type TangentVector = Sim3Tangent

The tangent space vector type
Source§

type JacobianMatrix = Matrix<f64, Const<7>, Const<7>, ArrayStorage<f64, 7, 7>>

The Jacobian matrix type
Source§

type LieAlgebra = Matrix<f64, Const<4>, Const<4>, ArrayStorage<f64, 4, 4>>

Associated Lie algebra type
Source§

fn act( &self, vector: &Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>, jacobian_self: Option<&mut <Sim3 as LieGroup>::JacobianMatrix>, jacobian_vector: Option<&mut Matrix<f64, Const<3>, Const<3>, ArrayStorage<f64, 3, 3>>>, ) -> Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>

Act on a vector v: g ⊙ v. Read more
Source§

fn adjoint(&self) -> <Sim3 as LieGroup>::JacobianMatrix

Adjoint matrix Ad(g). Read more
Source§

fn random() -> Sim3

Generate a random element (useful for testing and initialization).
Source§

fn normalize(&mut self)

Normalize/project the element to the manifold. Read more
Source§

fn is_valid(&self, tolerance: f64) -> bool

Check if the element is approximately on the manifold.
Source§

fn vee(&self) -> <Sim3 as LieGroup>::TangentVector

Vee operator: log(g)^∨. Read more
Source§

fn is_approx(&self, other: &Sim3, tolerance: f64) -> bool

Check if the element is approximately equal to another element. Read more
Source§

fn jacobian_identity() -> <Sim3 as LieGroup>::JacobianMatrix

Get the identity matrix for Jacobians. Read more
Source§

fn zero_jacobian() -> <Sim3 as LieGroup>::JacobianMatrix

Get a zero Jacobian matrix. Read more
Source§

fn right_plus( &self, tangent: &Self::TangentVector, jacobian_self: Option<&mut Self::JacobianMatrix>, jacobian_tangent: Option<&mut Self::JacobianMatrix>, ) -> Self

Right plus operation: g ⊞ φ = g ∘ exp(φ^∧). Read more
Source§

fn right_minus( &self, other: &Self, jacobian_self: Option<&mut Self::JacobianMatrix>, jacobian_other: Option<&mut Self::JacobianMatrix>, ) -> Self::TangentVector

Right minus operation: g₁ ⊟ g₂ = log(g₂⁻¹ ∘ g₁)^∨. Read more
Source§

fn left_plus( &self, tangent: &Self::TangentVector, jacobian_tangent: Option<&mut Self::JacobianMatrix>, jacobian_self: Option<&mut Self::JacobianMatrix>, ) -> Self

Left plus operation: φ ⊞ g = exp(φ^∧) ∘ g. Read more
Source§

fn left_minus( &self, other: &Self, jacobian_self: Option<&mut Self::JacobianMatrix>, jacobian_other: Option<&mut Self::JacobianMatrix>, ) -> Self::TangentVector

Left minus operation: g₁ ⊟ g₂ = log(g₁ ∘ g₂⁻¹)^∨. Read more
Source§

fn plus( &self, tangent: &Self::TangentVector, jacobian_self: Option<&mut Self::JacobianMatrix>, jacobian_tangent: Option<&mut Self::JacobianMatrix>, ) -> Self

Convenience method for right_plus. Equivalent to g ⊞ φ.
Source§

fn minus( &self, other: &Self, jacobian_self: Option<&mut Self::JacobianMatrix>, jacobian_other: Option<&mut Self::JacobianMatrix>, ) -> Self::TangentVector

Convenience method for right_minus. Equivalent to g₁ ⊟ g₂.
Source§

fn between( &self, other: &Self, jacobian_self: Option<&mut Self::JacobianMatrix>, jacobian_other: Option<&mut Self::JacobianMatrix>, ) -> Self

Compute g₁⁻¹ ∘ g₂ (relative transformation). Read more
Source§

fn tangent_dim(&self) -> usize

Get the dimension of the tangent space for this manifold element. Read more
Source§

impl PartialEq for Sim3

Source§

fn eq(&self, other: &Sim3) -> 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 Tangent<Sim3> for Sim3Tangent

Source§

fn exp(&self, jacobian: Option<&mut <Sim3 as LieGroup>::JacobianMatrix>) -> Sim3

Exponential map to Sim(3).

Source§

fn right_jacobian(&self) -> <Sim3 as LieGroup>::JacobianMatrix

Right Jacobian for Sim(3).

Source§

fn left_jacobian(&self) -> <Sim3 as LieGroup>::JacobianMatrix

Left Jacobian for Sim(3).

Source§

fn right_jacobian_inv(&self) -> <Sim3 as LieGroup>::JacobianMatrix

Inverse of right Jacobian.

Source§

fn left_jacobian_inv(&self) -> <Sim3 as LieGroup>::JacobianMatrix

Inverse of left Jacobian.

Source§

fn hat(&self) -> <Sim3 as LieGroup>::LieAlgebra

Hat operator: maps tangent vector to Lie algebra matrix (4x4).

Source§

const DIM: usize = 7

Dimension of the tangent space. Read more
Source§

fn zero() -> <Sim3 as LieGroup>::TangentVector

Zero tangent vector.
Source§

fn random() -> <Sim3 as LieGroup>::TangentVector

Random tangent vector (useful for testing).
Source§

fn is_zero(&self, tolerance: f64) -> bool

Check if the tangent vector is approximately zero.
Source§

fn normalize(&mut self)

Normalize the tangent vector to unit norm.
Source§

fn normalized(&self) -> <Sim3 as LieGroup>::TangentVector

Return a unit tangent vector in the same direction.
Source§

fn small_adj(&self) -> <Sim3 as LieGroup>::JacobianMatrix

Small adjugate operator: adj(φ) = φ^∧. Read more
Source§

fn lie_bracket(&self, other: &Sim3Tangent) -> <Sim3 as LieGroup>::TangentVector

Lie bracket: [φ, ψ] = φ ∘ ψ - ψ ∘ φ. Read more
Source§

fn is_approx(&self, other: &Sim3Tangent, tolerance: f64) -> bool

Check if the tangent vector is approximately equal to another tangent vector. Read more
Source§

fn generator(&self, i: usize) -> <Sim3 as LieGroup>::LieAlgebra

Get the i-th generator of the Lie algebra.
Source§

fn is_dynamic() -> bool

Whether this tangent type has dynamic (runtime-determined) dimension. Read more
Source§

impl StructuralPartialEq for Sim3

Auto Trait Implementations§

§

impl Freeze for Sim3

§

impl RefUnwindSafe for Sim3

§

impl Send for Sim3

§

impl Sync for Sim3

§

impl Unpin for Sim3

§

impl UnsafeUnpin for Sim3

§

impl UnwindSafe for Sim3

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

Source§

fn by_ref(&self) -> &T

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> DistributionExt for T
where T: ?Sized,

Source§

fn rand<T>(&self, rng: &mut (impl Rng + ?Sized)) -> T
where Self: Distribution<T>,

Source§

impl<T> ErrorLogging for T
where T: Display,

Source§

fn log(self) -> Self

Log the error with tracing::error and return self for chaining. Read more
Source§

fn log_with_source<E: Debug>(self, source_error: E) -> Self

Log the error with an additional source error for debugging context. Read more
Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

Source§

impl<T> Instrument for T

Source§

fn instrument(self, span: Span) -> Instrumented<Self>

Instruments this type with the provided Span, returning an Instrumented wrapper. Read more
Source§

fn in_current_span(self) -> Instrumented<Self>

Instruments this type with the current Span, returning an Instrumented wrapper. Read more
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<T> Pointable for T

Source§

const ALIGN: usize

The alignment of pointer.
Source§

type Init = T

The type for initializers.
Source§

unsafe fn init(init: <T as Pointable>::Init) -> usize

Initializes a with the given initializer. Read more
Source§

unsafe fn deref<'a>(ptr: usize) -> &'a T

Dereferences the given pointer. Read more
Source§

unsafe fn deref_mut<'a>(ptr: usize) -> &'a mut T

Mutably dereferences the given pointer. Read more
Source§

unsafe fn drop(ptr: usize)

Drops the object pointed to by the given pointer. Read more
Source§

impl<T> Same for T

Source§

type Output = T

Should always be Self
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> ToString for T
where T: Display + ?Sized,

Source§

fn to_string(&self) -> String

Converts the given value to a String. 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<V, T> VZip<V> for T
where V: MultiLane<T>,

Source§

fn vzip(self) -> V

Source§

impl<T> WithSubscriber for T

Source§

fn with_subscriber<S>(self, subscriber: S) -> WithDispatch<Self>
where S: Into<Dispatch>,

Attaches the provided Subscriber to this type, returning a WithDispatch wrapper. Read more
Source§

fn with_current_subscriber(self) -> WithDispatch<Self>

Attaches the current default Subscriber to this type, returning a WithDispatch wrapper. Read more
Source§

impl<T, U> Imply<T> for U
where T: ?Sized, U: ?Sized,