Hand-Eye Calibration (Tsai-Lenz)
Hand-eye calibration estimates the rigid transform between a camera and a robot gripper (or between a camera and a robot base). It is essential for any application where a camera is mounted on a robot arm and the robot needs to localize objects in its own coordinate frame.
The AX = XB Problem
Setup
Consider a camera rigidly mounted on a robot gripper (eye-in-hand configuration). The system involves four coordinate frames:
- Base (B): The robot's fixed base frame
- Gripper (G): The robot's end-effector frame (known from robot kinematics)
- Camera (C): The camera frame (observations come from here)
- Target (T): The calibration board frame (fixed in the world)
The unknown is (gripper-to-camera transform).
The Equation
Given two observations , we can compute:
- Robot motion: (relative gripper motion, known from robot kinematics)
- Camera motion: (relative camera motion, from calibration board observations)
Since the camera is rigidly attached to the gripper:
This is the classic equation. We need to find that satisfies this for all motion pairs.
Eye-to-Hand Variant
When the camera is fixed and the target is on the gripper (eye-to-hand), the equation becomes:
where now is the relative gripper motion and is the relative target-in-camera motion, and (camera-to-base transform).
The Tsai-Lenz Method
Overview
Tsai and Lenz (1989) decomposed into separate rotation and translation subproblems:
- Rotation: Solve for
- Translation: Given , solve for
Step 1: All-Pairs Motion Computation
From observations, construct all motion pairs. For each pair :
Step 2: Filtering
Discard pairs with insufficient rotation (degenerate for the rotation subproblem):
- Reject pairs where (default: 10°)
- Optionally reject pairs where rotation axes of and are near-parallel (ill-conditioned)
Rotation diversity is critical: If all robot motions are rotations around the same axis, the hand-eye rotation around that axis is undetermined. Use poses with diverse rotation axes (roll, pitch, and yaw).
Step 3: Rotation Estimation
The rotation constraint is solved using quaternion algebra.
Convert and to quaternions and . The constraint becomes:
Using the left and right quaternion multiplication matrices and :
Stacking all motion pairs gives a system:
Solve via SVD: is the right singular vector of corresponding to the smallest singular value. Normalize to unit quaternion.
Step 4: Translation Estimation
Given , the translation constraint for each motion pair is:
This is a overdetermined linear system , solved via least squares:
with optional ridge regularization for numerical stability.
Target-in-Base Estimation
After finding , the target pose in the base frame can be estimated. For each observation :
The estimates from different views are averaged (quaternion averaging for rotation, arithmetic mean for translation).
Alternatively, is included in the non-linear optimization.
Practical Requirements
- Minimum 3 views with diverse rotations (in practice, 5-10 views recommended)
- Rotation diversity: Motions should span multiple rotation axes. Pure translations provide no rotation constraint. Pure Z-axis rotations leave the Z-component of the hand-eye rotation undetermined.
- Accuracy: The linear Tsai-Lenz method typically gives 5-20% translation accuracy and 2-10° rotation accuracy. This initializes the non-linear joint optimization.
API
#![allow(unused)] fn main() { let X = estimate_handeye_dlt( &base_se3_gripper, // &[Iso3]: robot poses (base to gripper) &target_se3_camera, // &[Iso3]: camera-to-target poses (inverted) min_angle_deg, // f64: minimum rotation angle filter )?; }
Returns as an Iso3 transform.
OpenCV equivalence:
cv::calibrateHandEyewith methodCALIB_HAND_EYE_TSAI.
References
- Tsai, R.Y. & Lenz, R.K. (1989). "A New Technique for Fully Autonomous and Efficient 3D Robotics Hand/Eye Calibration." IEEE Transactions on Robotics and Automation, 5(3), 345-358.