Rigid Transformations and SE(3)
Camera calibration is fundamentally about estimating rigid transformations — rotations and translations that relate different coordinate frames: camera, world, robot gripper, calibration target, rig, etc. This chapter covers the rotation representations and transformation algebra used throughout calibration-rs.
Rotation Representations
Rotation Matrix
A orthogonal matrix with determinant :
The set of all such matrices forms the special orthogonal group . It has 3 degrees of freedom (9 entries minus 6 constraints).
Unit Quaternion
A 4-element vector with unit norm . The rotation of a vector is:
where is quaternion multiplication and is the conjugate.
Quaternions are preferred for optimization because they avoid gimbal lock and have simpler interpolation properties than Euler angles. calibration-rs (via nalgebra) stores quaternions as [i, j, k, w] internally, which maps to .
Axis-Angle
A rotation of angle around unit axis is represented as:
with and .
The Rodrigues formula converts axis-angle to rotation matrix:
where is the skew-symmetric matrix of :
Rigid Transformations: SE(3)
A rigid body transformation combines a rotation and translation :
The special Euclidean group has 6 degrees of freedom (3 rotation + 3 translation).
Applying a Transform
A point transformed by :
or in homogeneous coordinates:
Composition
Transforms compose by matrix multiplication:
Inverse
Naming Convention
calibration-rs uses the notation to mean "the transform from frame to frame ":
Common transforms:
| Symbol | Meaning |
|---|---|
| World to camera (camera extrinsics) | |
| Calibration board to camera | |
| Camera to rig (rig extrinsics) | |
| Camera to gripper (hand-eye) | |
| Target to base (hand-eye target pose) |
nalgebra Type: Iso3
calibration-rs uses nalgebra's Isometry3<f64> (aliased as Iso3) for SE(3) transforms:
#![allow(unused)] fn main() { pub type Iso3 = nalgebra::Isometry3<f64>; }
This stores a UnitQuaternion (rotation) and a Translation3 (translation) separately, avoiding the redundancy of a full matrix.
SE(3) Storage for Optimization
In the optimization IR, SE(3) parameters are stored as a 7-element vector:
The quaternion is unit-constrained. The optimizer uses the SE(3) manifold (see Manifold Optimization) to maintain this constraint during parameter updates.
The Exponential Map
The Lie algebra provides a 6-dimensional tangent space at the identity. A tangent vector maps to an SE(3) element via the exponential map:
where is the left Jacobian of SO(3):
The exponential map is central to manifold optimization: parameter updates are computed in the tangent space and then retracted to the manifold (see Manifold Optimization).