Single-Camera Hand-Eye Calibration

Hand-eye calibration estimates the rigid transform between a camera and a robot's gripper (or base). This workflow combines intrinsics calibration with hand-eye estimation in a 4-step pipeline.

Problem Formulation

Transformation Chain (Eye-in-Hand)

For a camera mounted on the robot gripper:

where:

  • : camera-to-gripper (the calibrated hand-eye transform, inverted)
  • : gripper-to-base (known from robot kinematics, inverted)
  • : base-to-target (the target's pose in the robot base frame, also calibrated)

Equivalently:

Eye-to-Hand Variant

For a fixed camera observing a target on the gripper:

where is the camera-to-base transform and is the target-to-gripper transform.

Optimization Objective

Minimize reprojection error across all views, jointly over all parameters:

where depends on the known robot pose for view , the hand-eye transform , and the target pose .

4-Step Pipeline

Step 1: Intrinsics Initialization (step_intrinsics_init)

Runs the Iterative Intrinsics solver to estimate and distortion from the calibration board observations, ignoring robot poses entirely.

Step 2: Intrinsics Optimization (step_intrinsics_optimize)

Runs planar intrinsics bundle adjustment to refine , distortion, and per-view camera-to-target poses. This gives accurate per-view poses needed for hand-eye initialization.

Step 3: Hand-Eye Initialization (step_handeye_init)

Uses the Tsai-Lenz linear method (see Hand-Eye Linear):

  1. Compute relative motions from robot poses and camera poses
  2. Filter pairs by rotation magnitude (reject small rotations)
  3. Estimate rotation via quaternion SVD
  4. Estimate translation via linear least squares
  5. Estimate from the hand-eye and camera poses

Step 4: Hand-Eye Optimization (step_handeye_optimize)

Joint non-linear optimization of all parameters:

Parameter blocks:

  • "cam" (4D, Euclidean): intrinsics
  • "dist" (5D, Euclidean): distortion
  • "handeye" (7D, SE3): gripper-to-camera transform
  • "target" (7D, SE3): base-to-target transform

Residual blocks: ReprojPointPinhole4Dist5HandEye per observation.

The robot poses are not optimized — they are known constants from the robot kinematics (passed as per-residual data).

Optional: Robot Pose Refinement

If robot pose accuracy is suspect, the pipeline supports per-view SE(3) corrections:

Additional parameter blocks: "robot_delta/v" (7D, SE3) per view

Additional residuals: Se3TangentPrior per view, with configurable rotation and translation sigmas:

This penalizes deviations from the nominal robot poses, allowing small corrections while preventing the optimizer from absorbing all error into robot pose changes.

Configuration

#![allow(unused)]
fn main() {
pub struct SingleCamHandeyeConfig {
    // Intrinsics init
    pub intrinsics_init_iterations: usize,
    pub fix_k3: bool,              // Fix k3 (default: true)
    pub fix_tangential: bool,      // Fix p1, p2 (default: false)
    pub zero_skew: bool,           // Enforce zero skew (default: true)

    // Hand-eye
    pub handeye_mode: HandEyeMode, // EyeInHand or EyeToHand
    pub min_motion_angle_deg: f64, // Filter small rotations in Tsai-Lenz

    // Optimization
    pub max_iters: usize,          // LM iterations (default: 100)
    pub verbosity: usize,
    pub robust_loss: RobustLoss,

    // Robot pose refinement
    pub refine_robot_poses: bool,  // Enable per-view corrections
    pub robot_rot_sigma: f64,      // Rotation prior sigma (radians)
    pub robot_trans_sigma: f64,    // Translation prior sigma (meters)
}
}

Input Format

Each view is a View<HandeyeMeta> (aliased as SingleCamHandeyeView):

#![allow(unused)]
fn main() {
pub struct HandeyeMeta {
    pub base_se3_gripper: Iso3,  // Robot pose (from kinematics)
}

// Type alias
pub type SingleCamHandeyeView = View<HandeyeMeta>;
// Where View<Meta> has fields: obs: CorrespondenceView, meta: Meta
}

Complete Example

#![allow(unused)]
fn main() {
use vision_calibration::prelude::*;
use vision_calibration::single_cam_handeye::*;

let views: Vec<SingleCamHandeyeView> = /* load data */;
let input = SingleCamHandeyeInput::new(views)?;

let mut session = CalibrationSession::<SingleCamHandeyeProblem>::new();
session.set_input(input)?;

step_intrinsics_init(&mut session, None)?;
step_intrinsics_optimize(&mut session, None)?;
step_handeye_init(&mut session, None)?;
step_handeye_optimize(&mut session, None)?;

let export = session.export()?;
println!("Hand-eye: {:?}", export.gripper_se3_camera);
println!("Target in base: {:?}", export.base_se3_target);
println!("Reprojection error: {:.4} px", export.mean_reproj_error);
}

Practical Considerations

  • Rotation diversity is critical for Tsai-Lenz initialization. Include rotations around at least 2 axes.
  • 5-10 views minimum, with 10-20 recommended for robustness.
  • Robot accuracy: If the robot's reported poses have errors > 1mm or > 0.1°, enable robot pose refinement.
  • Initialization failure: If Tsai-Lenz produces a poor estimate (large reprojection error after optimization), the most likely cause is insufficient rotation diversity.

OpenCV equivalence: cv::calibrateHandEye provides the linear initialization step. calibration-rs adds joint non-linear refinement and optional robot pose correction.