Special Euclidean Group
The group of rigid-body transformations in dimensions: combines a rotation and a translation into a single manifold element.
Geometry Summary
| Property | Value |
|---|---|
| Points | SEPoint<N>: rotation + translation |
| Tangent at | SETangent<N>: with |
| Metric | |
| Dimension | (: 3, : 6) |
| Injectivity radius | (limited by factor) |
| Curvature | Not implemented (use cartan-geo on for rotation-only curvature) |
| Group operation |
The weight field controls the relative importance of rotation vs. translation in the metric:
weight = 1.0: equal weighting (default)weight >> 1: translation-dominant (large-scale SLAM)weight << 1: rotation-dominant (attitude estimation)
Note: does not implement
Curvature. Homogeneous matrix representation $(N+1)\times(N+1)$ is unavailable due to the unstablegeneric_const_exprsfeature; rotation and translation are stored separately inSEPoint.
Formula Reference
Group operation and inverse:
Exponential map (via exp and left Jacobian ):
where and are body-frame components.
Logarithmic map:
Riemannian metric:
where and .
Code Examples
Constructing
use cartan::prelude::*;
use cartan::manifolds::{SpecialEuclidean, SEPoint};
use nalgebra::{SMatrix, SVector};
// SE(3) with default (equal) weighting
let se3 = SpecialEuclidean::<3> { weight: 1.0 };
// SE(3) with translation-dominant metric (useful for large-scale SLAM)
let se3_trans = SpecialEuclidean::<3> { weight: 10.0 };
let mut rng = rand::rng();
let p = se3.random_point(&mut rng); // random rigid-body transform
let v = se3.random_tangent(&p, &mut rng);Exp/log roundtrip
let q = se3.exp(&p, &v);
let v_back = se3.log(&p, &q).unwrap();
// Rotation and translation components recover separately
assert!((v_back.rotation - v.rotation).norm() < 1e-10);
assert!((v_back.translation - v.translation).norm() < 1e-10);Group composition
// Compose two rigid-body transforms manually
let r1 = p.rotation;
let t1 = p.translation;
let r2 = q.rotation;
let t2 = q.translation;
let composed = SEPoint {
rotation: r1 * r2,
translation: r1 * t2 + t1,
};Geodesic interpolation
let mid = se3.geodesic(&p, &q, 0.5).unwrap();
// mid is the midpoint rigid transform on the geodesic from p to qNumerical Notes
Injectivity radius: π; the logarithm fails when the rotational component
is a rotation (i.e., has eigenvalue $-1$). Returns Err at
the cut locus of .
Weight selection: The weight does not affect whether exp/log succeed, only
the geodesic path. For optimization tasks, tuning weight to match the physical
scale of rotations vs. translations improves convergence.
No Curvature impl: is not flat (the factor has positive curvature)
but Curvature is not yet implemented. Use cartan-geo's CurvatureQuery on a
SpecialOrthogonal<N> manifold for rotation-only curvature.
Applications
- Robotics: for 6-DOF end-effector poses, for mobile robot configurations
- SLAM: Lie group optimization of robot trajectories
- Computer vision: camera pose estimation, structure-from-motion
- Motion planning: interpolating between rigid-body configurations
- Biomechanics: modeling joint kinematics in N-dimensional configuration space