Skip to main content

Tangent

Trait Tangent 

Source
pub trait Tangent<Group>: Clone + PartialEq
where Group: LieGroup,
{ const DIM: usize;
Show 16 methods // Required methods fn exp( &self, jacobian: Option<&mut <Group as LieGroup>::JacobianMatrix>, ) -> Group; fn right_jacobian(&self) -> <Group as LieGroup>::JacobianMatrix; fn left_jacobian(&self) -> <Group as LieGroup>::JacobianMatrix; fn right_jacobian_inv(&self) -> <Group as LieGroup>::JacobianMatrix; fn left_jacobian_inv(&self) -> <Group as LieGroup>::JacobianMatrix; fn hat(&self) -> <Group as LieGroup>::LieAlgebra; fn small_adj(&self) -> <Group as LieGroup>::JacobianMatrix; fn lie_bracket(&self, other: &Self) -> <Group as LieGroup>::TangentVector; fn is_approx(&self, other: &Self, tolerance: f64) -> bool; fn generator(&self, i: usize) -> <Group as LieGroup>::LieAlgebra; fn zero() -> <Group as LieGroup>::TangentVector; fn random() -> <Group as LieGroup>::TangentVector; fn is_zero(&self, tolerance: f64) -> bool; fn normalize(&mut self); fn normalized(&self) -> <Group as LieGroup>::TangentVector; // Provided method fn is_dynamic() -> bool { ... }
}
Expand description

Trait for Lie algebra operations.

This trait provides operations for vectors in the Lie algebra of a Lie group, including vector space operations, adjoint actions, and conversions to matrix form.

§Type Parameters

  • G: The associated Lie group type

Required Associated Constants§

Source

const DIM: usize

Dimension of the tangent space.

For fixed-size manifolds (SE2, SE3, SO2, SO3), this is the compile-time constant. For dynamic-size manifolds (Rn), this is 0 as a sentinel value — use the is_dynamic() method to check, and the LieGroup::tangent_dim() instance method to get the actual runtime dimension.

Required Methods§

Source

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

Exponential map to Lie group: exp(φ^∧).

§Arguments
  • jacobian - Optional Jacobian ∂exp(φ^∧)/∂φ
Source

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

Right Jacobian Jr.

Matrix Jr such that for small δφ: exp((φ + δφ)^∧) ≈ exp(φ^∧) ∘ exp((Jr δφ)^∧)

Source

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

Left Jacobian Jl.

Matrix Jl such that for small δφ: exp((φ + δφ)^∧) ≈ exp((Jl δφ)^∧) ∘ exp(φ^∧)

Source

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

Inverse of right Jacobian Jr⁻¹.

Source

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

Inverse of left Jacobian Jl⁻¹.

Source

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

Hat operator: φ^∧ (vector to matrix).

Maps the tangent vector to its matrix representation in the Lie algebra. For SO(3): 3×1 vector → 3×3 skew-symmetric matrix For SE(3): 6×1 vector → 4×4 transformation matrix

Source

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

Small adjugate operator: adj(φ) = φ^∧.

Maps the tangent vector to its matrix representation in the Lie algebra. For SO(3): 3×1 vector → 3×3 skew-symmetric matrix For SE(3): 6×1 vector → 4×4 transformation matrix

Source

fn lie_bracket(&self, other: &Self) -> <Group as LieGroup>::TangentVector

Lie bracket: [φ, ψ] = φ ∘ ψ - ψ ∘ φ.

Computes the Lie bracket of two tangent vectors in the Lie algebra. For SO(3): 3×1 vector → 3×1 vector For SE(3): 6×1 vector → 6×1 vector

Source

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

Check if the tangent vector is approximately equal to another tangent vector.

§Arguments
  • other - The other tangent vector to compare with
  • tolerance - The tolerance for the comparison
Source

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

Get the i-th generator of the Lie algebra.

Source

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

Zero tangent vector.

Source

fn random() -> <Group 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) -> <Group as LieGroup>::TangentVector

Return a unit tangent vector in the same direction.

Provided Methods§

Source

fn is_dynamic() -> bool

Whether this tangent type has dynamic (runtime-determined) dimension.

Returns true for RnTangent where DIM == 0 is used as a sentinel. Returns false for all fixed-size tangent types (SE2, SE3, SO2, SO3).

Dyn Compatibility§

This trait is not dyn compatible.

In older versions of Rust, dyn compatibility was called "object safety", so this trait is not object safe.

Implementors§