Daniilidis Dual-Quaternion Hand-Eye Calibration | VitaVision
Back to atlas

Daniilidis Dual-Quaternion Hand-Eye Calibration

9 min readAdvancedView in graph
Based on
Hand-Eye Calibration Using Dual Quaternions
Daniilidis · The International Journal of Robotics Research 1999
DOI ↗

Goal

Given N2N \geq 2 motion pairs (Ai,Bi)(A_i, B_i) of rigid transforms — AiSE(3)A_i \in SE(3) the gripper-to-gripper displacement between two robot stations and BiSE(3)B_i \in SE(3) the camera-to-camera displacement observed at the same pair of stations — compute the constant camera-to-gripper transform XSE(3)X \in SE(3) that satisfies AiX=XBiA_i X = X B_i for every ii. Rotation and translation are solved jointly in a single SVD, without the two-stage decoupling used by Tsai-Lenz.

Algorithm

Write a rigid transform H=[Rt01]SE(3)H = \begin{bmatrix} R & t \\ 0 & 1 \end{bmatrix} \in SE(3) with rotation RSO(3)R \in SO(3) and translation tR3t \in \mathbb{R}^3. For a vector vR3v \in \mathbb{R}^3 let [v]×[v]_\times denote the skew-symmetric matrix such that [v]×w=v×w[v]_\times w = v \times w. Let \otimes denote the Hamilton product of quaternions.

Every rigid motion admits a screw decomposition: there exists an axis line \ell in space, a rotation angle θ\theta about that axis, and a translation distance dd along it (the pitch) such that HH is the composition of a rotation by θ\theta around \ell and a translation by dd along \ell. The line \ell is specified by a unit direction nS2n \in S^2 and its moment m=p×nm = p \times n for any point pp on the line.

Definition
Unit dual quaternion \hat q

A dual quaternion is a pair q^=q+εq\hat q = q + \varepsilon q' of ordinary quaternions, with ε2=0\varepsilon^2 = 0. It is a unit dual quaternion when q2=1|q|^2 = 1 and qq=0q \cdot q' = 0. Rigid motions are in one-to-one correspondence with unit dual quaternions up to sign.

q=cosθ2+sinθ2n,q=12tq,q = \cos\tfrac{\theta}{2} + \sin\tfrac{\theta}{2}\,n, \qquad q' = \tfrac{1}{2}\,t \otimes q,

where t=(0,tx,ty,tz)t = (0, t_x, t_y, t_z) is the translation as a pure quaternion.

Definition
Screw form

A compact equivalent representation in which the dual angle θ^\hat\theta and dual axis ^\hat\ell are Study's dual-number extensions of the real angle and axis.

q^=cosθ^2+sinθ^2^,θ^=θ+εd,^=n+εm.\hat q = \cos\tfrac{\hat\theta}{2} + \sin\tfrac{\hat\theta}{2}\,\hat\ell, \qquad \hat\theta = \theta + \varepsilon d, \qquad \hat\ell = n + \varepsilon m.

Write a^\hat a, b^\hat b, x^\hat x for the unit dual quaternions of AA, BB, XX. The hand-eye equation AX=XBA X = X B lifts to

a^x^  =  x^b^.\hat a\,\hat x \;=\; \hat x\,\hat b.
Definition
Screw congruence

Corresponding hand and eye motions share the same screw angle and pitch; XX rotates the hand screw axis into the eye screw axis and offsets its moment.

θa=θb,da=db.\theta_a = \theta_b, \qquad d_a = d_b.

The scalar parts of a^\hat a and b^\hat b coincide because they encode cos(θ^/2)\cos(\hat\theta/2). Split each quaternion into scalar and vector imaginary parts: q=(q0,q)q = (q_0, \mathbf q), and write a^=(a0,a)+ε(a0,a)\hat a = (a_0, \mathbf a) + \varepsilon(a_0', \mathbf a'), similarly for b^\hat b. Subtracting x^b^\hat x \hat b from a^x^\hat a \hat x and keeping only the imaginary parts yields six scalar equations per motion pair, linear in the eight unknowns (q0,q,q0,q)(q_0, \mathbf q, q_0', \mathbf q').

Definition
Hand-eye constraint matrix

For each motion pair (Ai,Bi)(A_i, B_i), the 6 × 8 matrix below annihilates the unknown dual quaternion of XX.

Si  =  [aibi[ai+bi]×003×3aibi[ai+bi]×aibi[ai+bi]×].S_i \;=\; \begin{bmatrix} \mathbf a_i - \mathbf b_i & [\mathbf a_i + \mathbf b_i]_\times & \mathbf 0 & 0_{3 \times 3} \\ \mathbf a'_i - \mathbf b'_i & [\mathbf a'_i + \mathbf b'_i]_\times & \mathbf a_i - \mathbf b_i & [\mathbf a_i + \mathbf b_i]_\times \end{bmatrix}.Si(q0qq0q)=06.S_i \begin{pmatrix} q_0 \\ \mathbf q \\ q'_0 \\ \mathbf q' \end{pmatrix} = \mathbf 0_6.

Stacking MM motion pairs gives a 6M×86M \times 8 system T=[S1SM]T = [S_1^\top \ldots S_M^\top]^\top with Tx^=0T\,\hat x = 0. 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 TT down to two dimensions. The two vectors v7,v8v_7, v_8 spanning that null space are the right singular vectors of TT associated with the two zero singular values.

The physical solution is a linear combination x^=λ1v7+λ2v8\hat x = \lambda_1 v_7 + \lambda_2 v_8 subject to the two dual-quaternion unit constraints:

q2=1,qq=0.|q|^2 = 1, \qquad q \cdot q' = 0.

Split each vkv_k into its qq-half ukR4u_k \in \mathbb{R}^4 (rows 1–4) and its qq'-half wkR4w_k \in \mathbb{R}^4 (rows 5–8). The second constraint is quadratic in s=λ1/λ2s = \lambda_1 / \lambda_2:

(u1w1)s2+(u1w2+u2w1)s+(u2w2)=0.(u_1 \cdot w_1)\,s^2 + (u_1 \cdot w_2 + u_2 \cdot w_1)\,s + (u_2 \cdot w_2) = 0.

Of its two real roots, pick the one that maximises s2u12+2su1u2+u22s^2\,|u_1|^2 + 2s\,u_1 \cdot u_2 + |u_2|^2; the reciprocal square root of that value fixes λ2\lambda_2, and λ1=sλ2\lambda_1 = s\,\lambda_2 follows.

Algorithm
Daniilidis dual-quaternion hand-eye
Input: Motion pairs {(Ai,Bi)}i=1M\{(A_i, B_i)\}_{i=1}^{M} with M2M \geq 2 and non-parallel screw axes across pairs.
Output: Camera-to-gripper transform X=[RXtX01]X = \begin{bmatrix} R_X & t_X \\ 0 & 1 \end{bmatrix}.
  1. Convert each AiA_i, BiB_i to its unit dual quaternion a^i=(a0,i,ai)+ε(a0,i,ai)\hat a_i = (a_{0,i}, \mathbf a_i) + \varepsilon(a'_{0,i}, \mathbf a'_i) and b^i\hat b_i.
  2. Assemble SiS_i from the imaginary parts (ai,ai,bi,bi)(\mathbf a_i, \mathbf a'_i, \mathbf b_i, \mathbf b'_i) and stack into TR6M×8T \in \mathbb{R}^{6M \times 8}.
  3. Compute the SVD T=UΣVT = U \Sigma V^\top; take v7,v8v_7, v_8 as the last two columns of VV.
  4. Split each vkv_k into uk,wkR4u_k, w_k \in \mathbb{R}^4. Solve the quadratic (u1w1)s2+(u1w2+u2w1)s+(u2w2)=0(u_1 \cdot w_1) s^2 + (u_1 \cdot w_2 + u_2 \cdot w_1) s + (u_2 \cdot w_2) = 0 for ss.
  5. Choose the root maximising s2u12+2su1u2+u22s^2 |u_1|^2 + 2 s\,u_1 \cdot u_2 + |u_2|^2; set λ2=(s2u12+2su1u2+u22)1/2\lambda_2 = (s^2 |u_1|^2 + 2 s\,u_1 \cdot u_2 + |u_2|^2)^{-1/2}, λ1=sλ2\lambda_1 = s\,\lambda_2.
  6. Assemble q=λ1u1+λ2u2q = \lambda_1 u_1 + \lambda_2 u_2 and q=λ1w1+λ2w2q' = \lambda_1 w_1 + \lambda_2 w_2; recover RX=R(q)R_X = R(q) and tX=2(qq)vect_X = 2\,(q' \otimes q^*)_{\text{vec}}.

Implementation

The per-pair block SiS_i of Eq. 31 in Rust. A stacked TR6M×8T \in \mathbb{R}^{6M \times 8} 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 V=svd(T).VV = \mathrm{svd}(T).V. Let v7,v8v_7, v_8 be the right singular vectors at the two smallest singular values; split each into an upper qq-half and lower qq'-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 RX=R(q)R_X = R(q) and tX=2(qq)vect_X = 2\,(q' \otimes q^*)_{\text{vec}} 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 RXTcijR_X T_{c_{ij}} 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) — TT loses rank and the null space grows beyond two dimensions.
  • Computational cost is dominated by one SVD of a 6M×86M \times 8 matrix, O(M)O(M) 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 ss, only one yields a non-degenerate q2|q|^2 under the q2=1|q|^2 = 1 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 SE(3)SE(3): x^\hat x and x^-\hat x represent the same rigid transform. The solver returns whichever sign the SVD produces; downstream code should canonicalise by requiring q00q_0 \geq 0.
  • 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

  1. K. Daniilidis. Hand-Eye Calibration Using Dual Quaternions. International Journal of Robotics Research 18(3)
    –298, 1999. doi
  2. 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
  3. 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

Alternative formulation of

  • Tsai-Lenz Hand-Eye Calibration

    Daniilidis's dual-quaternion solver couples rotation and translation simultaneously; both methods remain in practitioner use.