Goal
Given motion pairs of rigid transforms — the gripper-to-gripper displacement between two robot stations and the camera-to-camera displacement observed at the same pair of stations — compute the constant camera-to-gripper transform that satisfies for every . Rotation and translation are solved jointly in a single SVD, without the two-stage decoupling used by Tsai-Lenz.
Algorithm
Write a rigid transform with rotation and translation . For a vector let denote the skew-symmetric matrix such that . Let denote the Hamilton product of quaternions.
Every rigid motion admits a screw decomposition: there exists an axis line in space, a rotation angle about that axis, and a translation distance along it (the pitch) such that is the composition of a rotation by around and a translation by along . The line is specified by a unit direction and its moment for any point on the line.
A dual quaternion is a pair of ordinary quaternions, with . It is a unit dual quaternion when and . Rigid motions are in one-to-one correspondence with unit dual quaternions up to sign.
where is the translation as a pure quaternion.
A compact equivalent representation in which the dual angle and dual axis are Study's dual-number extensions of the real angle and axis.
Write , , for the unit dual quaternions of , , . The hand-eye equation lifts to
Corresponding hand and eye motions share the same screw angle and pitch; rotates the hand screw axis into the eye screw axis and offsets its moment.
The scalar parts of and coincide because they encode . Split each quaternion into scalar and vector imaginary parts: , and write , similarly for . Subtracting from and keeping only the imaginary parts yields six scalar equations per motion pair, linear in the eight unknowns .
For each motion pair , the 6 × 8 matrix below annihilates the unknown dual quaternion of .
Stacking motion pairs gives a system with . Each pair contributes a rank-6 block in generic position; two pairs with non-parallel screw axes are enough to cut the null space of down to two dimensions. The two vectors spanning that null space are the right singular vectors of associated with the two zero singular values.
The physical solution is a linear combination subject to the two dual-quaternion unit constraints:
Split each into its -half (rows 1–4) and its -half (rows 5–8). The second constraint is quadratic in :
Of its two real roots, pick the one that maximises ; the reciprocal square root of that value fixes , and follows.
- Convert each , to its unit dual quaternion and .
- Assemble from the imaginary parts and stack into .
- Compute the SVD ; take as the last two columns of .
- Split each into . Solve the quadratic for .
- Choose the root maximising ; set , .
- Assemble and ; recover and .
Implementation
The per-pair block of Eq. 31 in Rust. A stacked is filled by calling fill_block for every motion pair.
use nalgebra::{DMatrix, Matrix3, Vector3};
fn skew(v: &Vector3<f64>) -> Matrix3<f64> {
Matrix3::new(0.0, -v.z, v.y,
v.z, 0.0, -v.x,
-v.y, v.x, 0.0)
}
fn fill_block(t_mat: &mut DMatrix<f64>, k: usize,
a: Vector3<f64>, ap: Vector3<f64>,
b: Vector3<f64>, bp: Vector3<f64>)
{
let (d, dp) = (a - b, ap - bp);
let (sx, spx) = (skew(&(a + b)), skew(&(ap + bp)));
t_mat.fixed_view_mut::<3, 1>(6 * k, 0).copy_from(&d);
t_mat.fixed_view_mut::<3, 3>(6 * k, 1).copy_from(&sx);
t_mat.fixed_view_mut::<3, 1>(6 * k + 3, 0).copy_from(&dp);
t_mat.fixed_view_mut::<3, 3>(6 * k + 3, 1).copy_from(&spx);
t_mat.fixed_view_mut::<3, 1>(6 * k + 3, 4).copy_from(&d);
t_mat.fixed_view_mut::<3, 3>(6 * k + 3, 5).copy_from(&sx);
}
Null-space resolution after . Let be the right singular vectors at the two smallest singular values; split each into an upper -half and lower -half of length 4.
use nalgebra::{SVector, Vector4};
fn resolve(v7: &SVector<f64, 8>, v8: &SVector<f64, 8>)
-> (Vector4<f64>, Vector4<f64>)
{
let uq: Vector4<f64> = v7.fixed_rows::<4>(0).into_owned();
let uqp: Vector4<f64> = v7.fixed_rows::<4>(4).into_owned();
let wq: Vector4<f64> = v8.fixed_rows::<4>(0).into_owned();
let wqp: Vector4<f64> = v8.fixed_rows::<4>(4).into_owned();
let (a, b, c) = (uq.dot(&uqp),
uq.dot(&wqp) + wq.dot(&uqp),
wq.dot(&wqp));
let disc = (b * b - 4.0 * a * c).max(0.0).sqrt();
let norm = |s: f64| s * s * uq.dot(&uq)
+ 2.0 * s * uq.dot(&wq)
+ wq.dot(&wq);
let s = [(-b + disc) / (2.0 * a), (-b - disc) / (2.0 * a)]
.into_iter()
.max_by(|x, y| norm(*x).partial_cmp(&norm(*y)).unwrap())
.unwrap();
let lam2 = norm(s).sqrt().recip();
let lam1 = s * lam2;
(lam1 * uq + lam2 * wq, lam1 * uqp + lam2 * wqp)
}
The rigid transform is then and by standard quaternion-to-matrix and quaternion multiplication.
Remarks
- Joint rotation-and-translation solution avoids the error propagation of two-stage decoupled solvers: any bias in the rotation estimate of Tsai-Lenz feeds directly into the translation residual through the term, while here rotation and translation are co-estimated from the same null space.
- Minimum two motion pairs; uniqueness requires the screw axes of the two (or more) pairs to be non-parallel. Degenerates when all motions share a common screw axis (planar or pure-rotation trajectories) — loses rank and the null space grows beyond two dimensions.
- Computational cost is dominated by one SVD of a matrix, in the number of motion pairs.
- The root-selection step is a standard dual-quaternion trick: of the two real roots of the quadratic in , only one yields a non-degenerate under the normalisation. A purely imaginary or negative value flags either a sign flip on one of the input quaternions or ill-conditioned motions.
- Unit dual quaternions are a double cover of : and represent the same rigid transform. The solver returns whichever sign the SVD produces; downstream code should canonicalise by requiring .
- Compared with Tsai-Lenz: see When to choose Tsai-Lenz over Daniilidis on the Tsai-Lenz page, which hosts the comparison per the older-paper-hosts rule.
References
- K. Daniilidis. Hand-Eye Calibration Using Dual Quaternions. International Journal of Robotics Research 18(3)–298, 1999. doi
- R. Y. Tsai and R. K. Lenz. A new technique for fully autonomous and efficient 3D robotics hand/eye calibration. IEEE Transactions on Robotics and Automation 5(3)–358, 1989. pdf
- Y. C. Shiu and S. Ahmad. Calibration of wrist-mounted robotic sensors by solving homogeneous transform equations of the form AX=XB. IEEE Transactions on Robotics and Automation 5(1)–29, 1989. doi