apex_manifolds/lib.rs
1//! Manifold representations for optimization on non-Euclidean spaces.
2//!
3//! This module provides manifold representations commonly used in computer vision and robotics:
4//! - **SE(3)**: Special Euclidean group (rigid body transformations)
5//! - **SO(3)**: Special Orthogonal group (rotations)
6//! - **Sim(3)**: Similarity transformations
7//! - **SE(2)**: Rigid transformations in 2D
8//! - **SO(2)**: Rotations in 2D
9//!
10//! Lie group M,° | size | dim | X ∈ M | Constraint | T_E M | T_X M | Exp(T) | Comp. | Action
11//! ------------- | ------ | --- | ----------------------- | --------------- | ----------------- | --------------------- | ------------------ | ----- | ------
12//! n-D vector | Rⁿ,+ | n | n | v ∈ Rⁿ | |v-v|=0 | v ∈ Rⁿ | v ∈ Rⁿ | v = exp(v) | v₁+v₂ | v + x
13//! Circle | S¹,. | 2 | 1 | z ∈ C | z*z = 1 | iθ ∈ iR | θ ∈ R | z = exp(iθ) | z₁z₂ | zx
14//! Rotation | SO(2),.| 4 | 1 | R | RᵀR = I | [θ]x ∈ so(2) | [θ] ∈ R² | R = exp([θ]x) | R₁R₂ | Rx
15//! Rigid motion | SE(2),.| 9 | 3 | M = [R t; 0 1] | RᵀR = I | [v̂] ∈ se(2) | [v̂] ∈ R³ | Exp([v̂]) | M₁M₂ | Rx+t
16//! 3-sphere | S³,. | 4 | 3 | q ∈ H | q*q = 1 | θ/2 ∈ Hp | θ ∈ R³ | q = exp(uθ/2) | q₁q₂ | qxq*
17//! Rotation | SO(3),.| 9 | 3 | R | RᵀR = I | [θ]x ∈ so(3) | [θ] ∈ R³ | R = exp([θ]x) | R₁R₂ | Rx
18//! Rigid motion | SE(3),.| 16 | 6 | M = [R t; 0 1] | RᵀR = I | [v̂] ∈ se(3) | [v̂] ∈ R⁶ | Exp([v̂]) | M₁M₂ | Rx+t
19//!
20//! The design is inspired by the [manif](https://github.com/artivis/manif) C++ library
21//! and provides:
22//! - Analytic Jacobian computations for all operations
23//! - Right and left perturbation models
24//! - Composition and inverse operations
25//! - Exponential and logarithmic maps
26//! - Tangent space operations
27//!
28//! # Mathematical Background
29//!
30//! This module implements Lie group theory for robotics applications. Each manifold
31//! represents a Lie group with its associated tangent space (Lie algebra).
32//! Operations are differentiated with respect to perturbations on the local tangent space.
33//!
34
35use nalgebra::{Matrix3, Vector3};
36use std::ops::{Mul, Neg};
37use std::{
38 error, fmt,
39 fmt::{Display, Formatter},
40};
41
42/// Threshold for switching between exact formulas and Taylor approximations
43/// in small-angle computations.
44///
45/// `f64::EPSILON` (~2.2e-16) is too tight for small-angle detection — angles of ~1e-8 radians
46/// are well within Taylor approximation validity but would fall through to the exact formula
47/// path, where division by near-zero values causes numerical issues.
48///
49/// `1e-10` is chosen because:
50/// - Taylor expansions for sin(θ)/θ, (1-cos(θ))/θ² are accurate to ~1e-20 at this scale
51/// - Avoids catastrophic cancellation in exact formulas near zero
52/// - Consistent with production SLAM libraries (Sophus, GTSAM)
53///
54/// **Note:** This threshold is compared against `θ²` (not `θ`), so the effective angle
55/// threshold is `√(1e-10) ≈ 1e-5` radians (~0.00057°).
56pub const SMALL_ANGLE_THRESHOLD: f64 = 1e-10;
57
58pub mod rn;
59pub mod se2;
60pub mod se3;
61pub mod so2;
62pub mod so3;
63
64/// Errors that can occur during manifold operations.
65#[derive(Debug, Clone, PartialEq)]
66pub enum ManifoldError {
67 /// Invalid tangent vector dimension
68 InvalidTangentDimension { expected: usize, actual: usize },
69 /// Numerical instability in computation
70 NumericalInstability(String),
71 /// Invalid manifold element
72 InvalidElement(String),
73 /// Dimension validation failed during conversion
74 DimensionMismatch { expected: usize, actual: usize },
75 /// NaN or Inf detected in manifold element
76 InvalidNumber,
77 /// Normalization failed for manifold element
78 NormalizationFailed(String),
79}
80
81#[derive(Debug, Clone, PartialEq)]
82pub enum ManifoldType {
83 RN,
84 SE2,
85 SE3,
86 SO2,
87 SO3,
88}
89
90impl Display for ManifoldError {
91 fn fmt(&self, f: &mut Formatter<'_>) -> fmt::Result {
92 match self {
93 ManifoldError::InvalidTangentDimension { expected, actual } => {
94 write!(
95 f,
96 "Invalid tangent dimension: expected {expected}, got {actual}"
97 )
98 }
99 ManifoldError::NumericalInstability(msg) => {
100 write!(f, "Numerical instability: {msg}")
101 }
102 ManifoldError::InvalidElement(msg) => {
103 write!(f, "Invalid manifold element: {msg}")
104 }
105 ManifoldError::DimensionMismatch { expected, actual } => {
106 write!(f, "Dimension mismatch: expected {expected}, got {actual}")
107 }
108 ManifoldError::InvalidNumber => {
109 write!(f, "Invalid number: NaN or Inf detected")
110 }
111 ManifoldError::NormalizationFailed(msg) => {
112 write!(f, "Normalization failed: {msg}")
113 }
114 }
115 }
116}
117
118impl error::Error for ManifoldError {}
119
120/// Result type for manifold operations.
121pub type ManifoldResult<T> = Result<T, ManifoldError>;
122
123/// Core trait for Lie group operations.
124///
125/// Provides group operations, exponential/logarithmic maps, plus/minus with Jacobians,
126/// and adjoint representations.
127///
128/// # Associated Types
129///
130/// - `TangentVector`: Tangent space (Lie algebra) vector type
131/// - `JacobianMatrix`: Jacobian matrix type for this group
132/// - `LieAlgebra`: Matrix representation of the Lie algebra
133pub trait LieGroup: Clone + PartialEq {
134 /// The tangent space vector type
135 type TangentVector: Tangent<Self>;
136
137 /// The Jacobian matrix type
138 type JacobianMatrix: Clone
139 + PartialEq
140 + Neg<Output = Self::JacobianMatrix>
141 + Mul<Output = Self::JacobianMatrix>
142 + std::ops::Index<(usize, usize), Output = f64>;
143
144 /// Associated Lie algebra type
145 type LieAlgebra: Clone + PartialEq;
146
147 // Core group operations
148
149 /// Compute the inverse of this manifold element.
150 ///
151 /// For a group element g, returns g⁻¹ such that g ∘ g⁻¹ = e.
152 ///
153 /// # Arguments
154 /// * `jacobian` - Optional mutable reference to store the Jacobian ∂(g⁻¹)/∂g
155 fn inverse(&self, jacobian: Option<&mut Self::JacobianMatrix>) -> Self;
156
157 /// Compose this element with another (group multiplication).
158 ///
159 /// Computes g₁ ∘ g₂ where ∘ is the group operation.
160 ///
161 /// # Arguments
162 /// * `other` - The right operand for composition
163 /// * `jacobian_self` - Optional Jacobian ∂(g₁ ∘ g₂)/∂g₁
164 /// * `jacobian_other` - Optional Jacobian ∂(g₁ ∘ g₂)/∂g₂
165 fn compose(
166 &self,
167 other: &Self,
168 jacobian_self: Option<&mut Self::JacobianMatrix>,
169 jacobian_other: Option<&mut Self::JacobianMatrix>,
170 ) -> Self;
171
172 /// Logarithmic map from manifold to tangent space.
173 ///
174 /// Maps a group element g ∈ G to its tangent vector log(g)^∨ ∈ 𝔤.
175 ///
176 /// # Arguments
177 /// * `jacobian` - Optional Jacobian ∂log(g)^∨/∂g
178 fn log(&self, jacobian: Option<&mut Self::JacobianMatrix>) -> Self::TangentVector;
179
180 /// Vee operator: log(g)^∨.
181 ///
182 /// Maps a group element g ∈ G to its tangent vector log(g)^∨ ∈ 𝔤.
183 ///
184 /// # Arguments
185 /// * `jacobian` - Optional Jacobian ∂log(g)^∨/∂g
186 fn vee(&self) -> Self::TangentVector;
187
188 /// Act on a vector v: g ⊙ v.
189 ///
190 /// Group action on vectors (e.g., rotation for SO(3), transformation for SE(3)).
191 ///
192 /// # Arguments
193 /// * `vector` - Vector to transform
194 /// * `jacobian_self` - Optional Jacobian ∂(g ⊙ v)/∂g
195 /// * `jacobian_vector` - Optional Jacobian ∂(g ⊙ v)/∂v
196 fn act(
197 &self,
198 vector: &Vector3<f64>,
199 jacobian_self: Option<&mut Self::JacobianMatrix>,
200 jacobian_vector: Option<&mut Matrix3<f64>>,
201 ) -> Vector3<f64>;
202
203 // Adjoint operations
204
205 /// Adjoint matrix Ad(g).
206 ///
207 /// The adjoint representation maps the group to linear transformations
208 /// on the Lie algebra: Ad(g) φ = log(g ∘ exp(φ^∧) ∘ g⁻¹)^∨.
209 fn adjoint(&self) -> Self::JacobianMatrix;
210
211 // Utility operations
212
213 /// Generate a random element (useful for testing and initialization).
214 fn random() -> Self;
215
216 /// Get the identity matrix for Jacobians.
217 ///
218 /// Returns the identity matrix in the appropriate dimension for Jacobian computations.
219 /// This is used to initialize Jacobian matrices in optimization algorithms.
220 fn jacobian_identity() -> Self::JacobianMatrix;
221
222 /// Get a zero Jacobian matrix.
223 ///
224 /// Returns a zero matrix in the appropriate dimension for Jacobian computations.
225 /// This is used to initialize Jacobian matrices before optimization computations.
226 fn zero_jacobian() -> Self::JacobianMatrix;
227
228 /// Normalize/project the element to the manifold.
229 ///
230 /// Ensures the element satisfies manifold constraints (e.g., orthogonality for rotations).
231 fn normalize(&mut self);
232
233 /// Check if the element is approximately on the manifold.
234 fn is_valid(&self, tolerance: f64) -> bool;
235
236 /// Check if the element is approximately equal to another element.
237 ///
238 /// # Arguments
239 /// * `other` - The other element to compare with
240 /// * `tolerance` - The tolerance for the comparison
241 fn is_approx(&self, other: &Self, tolerance: f64) -> bool;
242
243 // Manifold plus/minus operations
244
245 /// Right plus operation: g ⊞ φ = g ∘ exp(φ^∧).
246 ///
247 /// Applies a tangent space perturbation to this manifold element.
248 ///
249 /// # Arguments
250 /// * `tangent` - Tangent vector perturbation
251 /// * `jacobian_self` - Optional Jacobian ∂(g ⊞ φ)/∂g
252 /// * `jacobian_tangent` - Optional Jacobian ∂(g ⊞ φ)/∂φ
253 ///
254 /// # Notes
255 /// # Equation 148:
256 /// J_R⊕θ_R = R(θ)ᵀ
257 /// J_R⊕θ_θ = J_r(θ)
258 fn right_plus(
259 &self,
260 tangent: &Self::TangentVector,
261 jacobian_self: Option<&mut Self::JacobianMatrix>,
262 jacobian_tangent: Option<&mut Self::JacobianMatrix>,
263 ) -> Self {
264 let exp_tangent = tangent.exp(None);
265
266 if let Some(jac_tangent) = jacobian_tangent {
267 *jac_tangent = tangent.right_jacobian();
268 }
269
270 self.compose(&exp_tangent, jacobian_self, None)
271 }
272
273 /// Right minus operation: g₁ ⊟ g₂ = log(g₂⁻¹ ∘ g₁)^∨.
274 ///
275 /// Computes the tangent vector that transforms g₂ to g₁.
276 ///
277 /// # Arguments
278 /// * `other` - The reference element g₂
279 /// * `jacobian_self` - Optional Jacobian ∂(g₁ ⊟ g₂)/∂g₁
280 /// * `jacobian_other` - Optional Jacobian ∂(g₁ ⊟ g₂)/∂g₂
281 ///
282 /// # Notes
283 /// # Equation 149:
284 /// J_Q⊖R_Q = J_r⁻¹(θ)
285 /// J_Q⊖R_R = -J_l⁻¹(θ)
286 fn right_minus(
287 &self,
288 other: &Self,
289 jacobian_self: Option<&mut Self::JacobianMatrix>,
290 jacobian_other: Option<&mut Self::JacobianMatrix>,
291 ) -> Self::TangentVector {
292 let other_inverse = other.inverse(None);
293 let result_group = other_inverse.compose(self, None, None);
294 let result = result_group.log(None);
295
296 if let Some(jac_self) = jacobian_self {
297 *jac_self = -result.left_jacobian_inv();
298 }
299
300 if let Some(jac_other) = jacobian_other {
301 *jac_other = result.right_jacobian_inv();
302 }
303
304 result
305 }
306
307 /// Left plus operation: φ ⊞ g = exp(φ^∧) ∘ g.
308 ///
309 /// # Arguments
310 /// * `tangent` - Tangent vector perturbation
311 /// * `jacobian_tangent` - Optional Jacobian ∂(φ ⊞ g)/∂φ
312 /// * `jacobian_self` - Optional Jacobian ∂(φ ⊞ g)/∂g
313 fn left_plus(
314 &self,
315 tangent: &Self::TangentVector,
316 jacobian_tangent: Option<&mut Self::JacobianMatrix>,
317 jacobian_self: Option<&mut Self::JacobianMatrix>,
318 ) -> Self {
319 let exp_tangent = tangent.exp(None);
320 let result = exp_tangent.compose(self, None, None);
321
322 if let Some(jac_self) = jacobian_self {
323 *jac_self = self.adjoint();
324 }
325
326 if let Some(jac_tangent) = jacobian_tangent {
327 *jac_tangent = self.inverse(None).adjoint() * tangent.right_jacobian();
328 }
329
330 result
331 }
332
333 /// Left minus operation: g₁ ⊟ g₂ = log(g₁ ∘ g₂⁻¹)^∨.
334 ///
335 /// # Arguments
336 /// * `other` - The reference element g₂
337 /// * `jacobian_self` - Optional Jacobian ∂(g₁ ⊟ g₂)/∂g₁
338 /// * `jacobian_other` - Optional Jacobian ∂(g₁ ⊟ g₂)/∂g₂
339 fn left_minus(
340 &self,
341 other: &Self,
342 jacobian_self: Option<&mut Self::JacobianMatrix>,
343 jacobian_other: Option<&mut Self::JacobianMatrix>,
344 ) -> Self::TangentVector {
345 let other_inverse = other.inverse(None);
346 let result_group = self.compose(&other_inverse, None, None);
347 let result = result_group.log(None);
348
349 if let Some(jac_self) = jacobian_self {
350 *jac_self = result.right_jacobian_inv() * other.adjoint();
351 }
352
353 if let Some(jac_other) = jacobian_other {
354 *jac_other = -(result.right_jacobian_inv() * other.adjoint());
355 }
356
357 result
358 }
359
360 // Convenience methods (use right operations by default)
361
362 /// Convenience method for right_plus. Equivalent to g ⊞ φ.
363 fn plus(
364 &self,
365 tangent: &Self::TangentVector,
366 jacobian_self: Option<&mut Self::JacobianMatrix>,
367 jacobian_tangent: Option<&mut Self::JacobianMatrix>,
368 ) -> Self {
369 self.right_plus(tangent, jacobian_self, jacobian_tangent)
370 }
371
372 /// Convenience method for right_minus. Equivalent to g₁ ⊟ g₂.
373 fn minus(
374 &self,
375 other: &Self,
376 jacobian_self: Option<&mut Self::JacobianMatrix>,
377 jacobian_other: Option<&mut Self::JacobianMatrix>,
378 ) -> Self::TangentVector {
379 self.right_minus(other, jacobian_self, jacobian_other)
380 }
381
382 // Additional operations
383
384 /// Compute g₁⁻¹ ∘ g₂ (relative transformation).
385 ///
386 /// # Arguments
387 /// * `other` - The target element g₂
388 /// * `jacobian_self` - Optional Jacobian with respect to g₁
389 /// * `jacobian_other` - Optional Jacobian with respect to g₂
390 fn between(
391 &self,
392 other: &Self,
393 jacobian_self: Option<&mut Self::JacobianMatrix>,
394 jacobian_other: Option<&mut Self::JacobianMatrix>,
395 ) -> Self {
396 let self_inverse = self.inverse(None);
397 let result = self_inverse.compose(other, None, None);
398
399 if let Some(jac_self) = jacobian_self {
400 *jac_self = -result.inverse(None).adjoint();
401 }
402
403 if let Some(jac_other) = jacobian_other {
404 *jac_other = Self::jacobian_identity();
405 }
406
407 result
408 }
409
410 /// Get the dimension of the tangent space for this manifold element.
411 ///
412 /// For most manifolds, this returns the compile-time constant from the TangentVector type.
413 /// For dynamically-sized manifolds like Rⁿ, this method should be overridden to return
414 /// the actual runtime dimension.
415 ///
416 /// # Returns
417 /// The dimension of the tangent space (degrees of freedom)
418 ///
419 /// # Default Implementation
420 /// Returns `Self::TangentVector::DIM` which works for fixed-size manifolds
421 /// (SE2=3, SE3=6, SO2=1, SO3=3).
422 fn tangent_dim(&self) -> usize {
423 Self::TangentVector::DIM
424 }
425}
426
427/// Trait for Lie algebra operations.
428///
429/// This trait provides operations for vectors in the Lie algebra of a Lie group,
430/// including vector space operations, adjoint actions, and conversions to matrix form.
431///
432/// # Type Parameters
433///
434/// - `G`: The associated Lie group type
435pub trait Tangent<Group: LieGroup>: Clone + PartialEq {
436 // Dimension constants
437
438 /// Dimension of the tangent space.
439 ///
440 /// For fixed-size manifolds (SE2, SE3, SO2, SO3), this is the compile-time constant.
441 /// For dynamic-size manifolds (Rn), this is `0` as a sentinel value — use the
442 /// `is_dynamic()` method to check, and the `LieGroup::tangent_dim()` instance method
443 /// to get the actual runtime dimension.
444 const DIM: usize;
445
446 /// Whether this tangent type has dynamic (runtime-determined) dimension.
447 ///
448 /// Returns `true` for `RnTangent` where `DIM == 0` is used as a sentinel.
449 /// Returns `false` for all fixed-size tangent types (SE2, SE3, SO2, SO3).
450 fn is_dynamic() -> bool {
451 Self::DIM == 0
452 }
453
454 // Exponential map and Jacobians
455
456 /// Exponential map to Lie group: exp(φ^∧).
457 ///
458 /// # Arguments
459 /// * `jacobian` - Optional Jacobian ∂exp(φ^∧)/∂φ
460 fn exp(&self, jacobian: Option<&mut Group::JacobianMatrix>) -> Group;
461
462 /// Right Jacobian Jr.
463 ///
464 /// Matrix Jr such that for small δφ:
465 /// exp((φ + δφ)^∧) ≈ exp(φ^∧) ∘ exp((Jr δφ)^∧)
466 fn right_jacobian(&self) -> Group::JacobianMatrix;
467
468 /// Left Jacobian Jl.
469 ///
470 /// Matrix Jl such that for small δφ:
471 /// exp((φ + δφ)^∧) ≈ exp((Jl δφ)^∧) ∘ exp(φ^∧)
472 fn left_jacobian(&self) -> Group::JacobianMatrix;
473
474 /// Inverse of right Jacobian Jr⁻¹.
475 fn right_jacobian_inv(&self) -> Group::JacobianMatrix;
476
477 /// Inverse of left Jacobian Jl⁻¹.
478 fn left_jacobian_inv(&self) -> Group::JacobianMatrix;
479
480 // Matrix representations
481
482 /// Hat operator: φ^∧ (vector to matrix).
483 ///
484 /// Maps the tangent vector to its matrix representation in the Lie algebra.
485 /// For SO(3): 3×1 vector → 3×3 skew-symmetric matrix
486 /// For SE(3): 6×1 vector → 4×4 transformation matrix
487 fn hat(&self) -> Group::LieAlgebra;
488
489 /// Small adjugate operator: adj(φ) = φ^∧.
490 ///
491 /// Maps the tangent vector to its matrix representation in the Lie algebra.
492 /// For SO(3): 3×1 vector → 3×3 skew-symmetric matrix
493 /// For SE(3): 6×1 vector → 4×4 transformation matrix
494 fn small_adj(&self) -> Group::JacobianMatrix;
495
496 /// Lie bracket: [φ, ψ] = φ ∘ ψ - ψ ∘ φ.
497 ///
498 /// Computes the Lie bracket of two tangent vectors in the Lie algebra.
499 /// For SO(3): 3×1 vector → 3×1 vector
500 /// For SE(3): 6×1 vector → 6×1 vector
501 fn lie_bracket(&self, other: &Self) -> Group::TangentVector;
502
503 /// Check if the tangent vector is approximately equal to another tangent vector.
504 ///
505 /// # Arguments
506 /// * `other` - The other tangent vector to compare with
507 /// * `tolerance` - The tolerance for the comparison
508 fn is_approx(&self, other: &Self, tolerance: f64) -> bool;
509
510 /// Get the i-th generator of the Lie algebra.
511 fn generator(&self, i: usize) -> Group::LieAlgebra;
512
513 // Utility functions
514
515 /// Zero tangent vector.
516 fn zero() -> Group::TangentVector;
517
518 /// Random tangent vector (useful for testing).
519 fn random() -> Group::TangentVector;
520
521 /// Check if the tangent vector is approximately zero.
522 fn is_zero(&self, tolerance: f64) -> bool;
523
524 /// Normalize the tangent vector to unit norm.
525 fn normalize(&mut self);
526
527 /// Return a unit tangent vector in the same direction.
528 fn normalized(&self) -> Group::TangentVector;
529}
530
531/// Trait for Lie groups that support interpolation.
532pub trait Interpolatable: LieGroup {
533 /// Linear interpolation in the manifold.
534 ///
535 /// For parameter t ∈ [0,1]: interp(g₁, g₂, 0) = g₁, interp(g₁, g₂, 1) = g₂.
536 ///
537 /// # Arguments
538 /// * `other` - Target element for interpolation
539 /// * `t` - Interpolation parameter in [0,1]
540 fn interp(&self, other: &Self, t: f64) -> Self;
541
542 /// Spherical linear interpolation (when applicable).
543 fn slerp(&self, other: &Self, t: f64) -> Self;
544}