Skip to main content

LieGroup

Trait LieGroup 

Source
pub trait LieGroup: Clone + PartialEq {
    type TangentVector: Tangent<Self>;
    type JacobianMatrix: Clone + PartialEq + Neg<Output = Self::JacobianMatrix> + Mul<Output = Self::JacobianMatrix> + Index<(usize, usize), Output = f64>;
    type LieAlgebra: Clone + PartialEq;

Show 20 methods // Required methods fn inverse(&self, jacobian: Option<&mut Self::JacobianMatrix>) -> Self; fn compose( &self, other: &Self, jacobian_self: Option<&mut Self::JacobianMatrix>, jacobian_other: Option<&mut Self::JacobianMatrix>, ) -> Self; fn log( &self, jacobian: Option<&mut Self::JacobianMatrix>, ) -> Self::TangentVector; fn vee(&self) -> Self::TangentVector; fn act( &self, vector: &Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>, jacobian_self: Option<&mut Self::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>>; fn adjoint(&self) -> Self::JacobianMatrix; fn random() -> Self; fn jacobian_identity() -> Self::JacobianMatrix; fn zero_jacobian() -> Self::JacobianMatrix; fn normalize(&mut self); fn is_valid(&self, tolerance: f64) -> bool; fn is_approx(&self, other: &Self, tolerance: f64) -> bool; // Provided methods fn right_plus( &self, tangent: &Self::TangentVector, jacobian_self: Option<&mut Self::JacobianMatrix>, jacobian_tangent: Option<&mut Self::JacobianMatrix>, ) -> Self { ... } fn right_minus( &self, other: &Self, jacobian_self: Option<&mut Self::JacobianMatrix>, jacobian_other: Option<&mut Self::JacobianMatrix>, ) -> Self::TangentVector { ... } fn left_plus( &self, tangent: &Self::TangentVector, jacobian_tangent: Option<&mut Self::JacobianMatrix>, jacobian_self: Option<&mut Self::JacobianMatrix>, ) -> Self { ... } fn left_minus( &self, other: &Self, jacobian_self: Option<&mut Self::JacobianMatrix>, jacobian_other: Option<&mut Self::JacobianMatrix>, ) -> Self::TangentVector { ... } fn plus( &self, tangent: &Self::TangentVector, jacobian_self: Option<&mut Self::JacobianMatrix>, jacobian_tangent: Option<&mut Self::JacobianMatrix>, ) -> Self { ... } fn minus( &self, other: &Self, jacobian_self: Option<&mut Self::JacobianMatrix>, jacobian_other: Option<&mut Self::JacobianMatrix>, ) -> Self::TangentVector { ... } fn between( &self, other: &Self, jacobian_self: Option<&mut Self::JacobianMatrix>, jacobian_other: Option<&mut Self::JacobianMatrix>, ) -> Self { ... } fn tangent_dim(&self) -> usize { ... }
}
Expand description

Core trait for Lie group operations.

Provides group operations, exponential/logarithmic maps, plus/minus with Jacobians, and adjoint representations.

§Associated Types

  • TangentVector: Tangent space (Lie algebra) vector type
  • JacobianMatrix: Jacobian matrix type for this group
  • LieAlgebra: Matrix representation of the Lie algebra

Required Associated Types§

Source

type TangentVector: Tangent<Self>

The tangent space vector type

Source

type JacobianMatrix: Clone + PartialEq + Neg<Output = Self::JacobianMatrix> + Mul<Output = Self::JacobianMatrix> + Index<(usize, usize), Output = f64>

The Jacobian matrix type

Source

type LieAlgebra: Clone + PartialEq

Associated Lie algebra type

Required Methods§

Source

fn inverse(&self, jacobian: Option<&mut Self::JacobianMatrix>) -> Self

Compute the inverse of this manifold element.

For a group element g, returns g⁻¹ such that g ∘ g⁻¹ = e.

§Arguments
  • jacobian - Optional mutable reference to store the Jacobian ∂(g⁻¹)/∂g
Source

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

Compose this element with another (group multiplication).

Computes g₁ ∘ g₂ where ∘ is the group operation.

§Arguments
  • other - The right operand for composition
  • jacobian_self - Optional Jacobian ∂(g₁ ∘ g₂)/∂g₁
  • jacobian_other - Optional Jacobian ∂(g₁ ∘ g₂)/∂g₂
Source

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

Logarithmic map from manifold to tangent space.

Maps a group element g ∈ G to its tangent vector log(g)^∨ ∈ 𝔤.

§Arguments
  • jacobian - Optional Jacobian ∂log(g)^∨/∂g
Source

fn vee(&self) -> Self::TangentVector

Vee operator: log(g)^∨.

Maps a group element g ∈ G to its tangent vector log(g)^∨ ∈ 𝔤.

§Arguments
  • jacobian - Optional Jacobian ∂log(g)^∨/∂g
Source

fn act( &self, vector: &Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>, jacobian_self: Option<&mut Self::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.

Group action on vectors (e.g., rotation for SO(3), transformation for SE(3)).

§Arguments
  • vector - Vector to transform
  • jacobian_self - Optional Jacobian ∂(g ⊙ v)/∂g
  • jacobian_vector - Optional Jacobian ∂(g ⊙ v)/∂v
Source

fn adjoint(&self) -> Self::JacobianMatrix

Adjoint matrix Ad(g).

The adjoint representation maps the group to linear transformations on the Lie algebra: Ad(g) φ = log(g ∘ exp(φ^∧) ∘ g⁻¹)^∨.

Source

fn random() -> Self

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

Source

fn jacobian_identity() -> Self::JacobianMatrix

Get the identity matrix for Jacobians.

Returns the identity matrix in the appropriate dimension for Jacobian computations. This is used to initialize Jacobian matrices in optimization algorithms.

Source

fn zero_jacobian() -> Self::JacobianMatrix

Get a zero Jacobian matrix.

Returns a zero matrix in the appropriate dimension for Jacobian computations. This is used to initialize Jacobian matrices before optimization computations.

Source

fn normalize(&mut self)

Normalize/project the element to the manifold.

Ensures the element satisfies manifold constraints (e.g., orthogonality for rotations).

Source

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

Check if the element is approximately on the manifold.

Source

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

Check if the element is approximately equal to another element.

§Arguments
  • other - The other element to compare with
  • tolerance - The tolerance for the comparison

Provided Methods§

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(φ^∧).

Applies a tangent space perturbation to this manifold element.

§Arguments
  • tangent - Tangent vector perturbation
  • jacobian_self - Optional Jacobian ∂(g ⊞ φ)/∂g
  • jacobian_tangent - Optional Jacobian ∂(g ⊞ φ)/∂φ
§Notes
§Equation 148:

J_R⊕θ_R = R(θ)ᵀ J_R⊕θ_θ = J_r(θ)

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₁)^∨.

Computes the tangent vector that transforms g₂ to g₁.

§Arguments
  • other - The reference element g₂
  • jacobian_self - Optional Jacobian ∂(g₁ ⊟ g₂)/∂g₁
  • jacobian_other - Optional Jacobian ∂(g₁ ⊟ g₂)/∂g₂
§Notes
§Equation 149:

J_Q⊖R_Q = J_r⁻¹(θ) J_Q⊖R_R = -J_l⁻¹(θ)

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.

§Arguments
  • tangent - Tangent vector perturbation
  • jacobian_tangent - Optional Jacobian ∂(φ ⊞ g)/∂φ
  • jacobian_self - Optional Jacobian ∂(φ ⊞ g)/∂g
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₂⁻¹)^∨.

§Arguments
  • other - The reference element g₂
  • jacobian_self - Optional Jacobian ∂(g₁ ⊟ g₂)/∂g₁
  • jacobian_other - Optional Jacobian ∂(g₁ ⊟ g₂)/∂g₂
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).

§Arguments
  • other - The target element g₂
  • jacobian_self - Optional Jacobian with respect to g₁
  • jacobian_other - Optional Jacobian with respect to g₂
Source

fn tangent_dim(&self) -> usize

Get the dimension of the tangent space for this manifold element.

For most manifolds, this returns the compile-time constant from the TangentVector type. For dynamically-sized manifolds like Rⁿ, this method should be overridden to return the actual runtime dimension.

§Returns

The dimension of the tangent space (degrees of freedom)

§Default Implementation

Returns Self::TangentVector::DIM which works for fixed-size manifolds (SE2=3, SE3=6, SO2=1, SO3=3).

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§