Hand-Eye Calibration

The algorithm performs a hand-eye calibration between the two input tracking streams.

Input

Two tracking streams with the same number of samples. It’s expected that the corresponding samples are matching.

Output

Two tracking streams:

  • Cam-to-Calib with applied registration of Calib-to-Base (Eye-In-Hand case)/ Calib-to-Cam with applied registration of Cam-to-Base (Eye-On-Base case);
  • Hand-to-Base with applied calibration of Cam-to-Hand (Eye-In-Hand case)/ Calib-to-Hand (Eye-On-Base case).

The transformation matrices are printed in the log output

  • Cam-to-Hand (Eye-In-Hand case) or Calib-to-Hand (Eye-On-Base case);
  • Calib-to-Base (Eye-In-Hand case) or Cam-to-Base (Eye-On-Base case).

Description

The hand-eye calibration is used to find the relation between the coordinate system of the moving object (for example camera, or eye) and a coordinate system of a hand (for example a robot arm) which are moving rigidly together.

See the following image for clarification of the coordinate systems.

../../_images/HandEye1.png

The input tracking streams should represent hand T base and moving T fixed or their inverse. The algorithm will evaluate moving T hand and fixed T base

There are two common scenarios in a hand-eye calibration problem, so called Eye In Hand and Eye On Base. The particular scenario can be chosen via Calibration Type. See the following image for an illustration of these two scenarios.

../../_images/HandEye2.png

In case of Eye In Hand, the moving coordinate system is the coordinate system of the camera, and the fixed coordinate system is the coordinate system of the calibration board. In case of Eye On Base it’s vice versa.

The algorithm requires to specify the type of transformation provided in each tracking stream. This is done through the comboboxes Stream1 and Stream2. The possible options are:

  • CamToCalib (moving T fixed in Eye-In-Hand case and fixed T moving in Eye-On-Base case),
  • CalibToCam (fixed T moving in Eye-In-Hand case and moving T fixed in Eye-On-Base case),
  • HandToBase (hand T base),
  • BaseToHand (base T hand).

The computation algorithm can be specified through Method. The options are:

  • Tsai Lenz - refer to paper
  • Global MLSL - an optimization minimizing the pose difference between the left handside and right handside of the following equation:

moving T hand * fixed T moving = base T hand * fixed T base

Reset matrices indicates if matrices of the input tracking streams should be reset to Identity before starting the computation.

Min rel. angle for sample selection and Min rel. translation for sample selection specify the minimum angle/translation between a current tracking sample and a previously selected sample for the current sample to be selected for the computation.

Min rel. angle for pair selection specifies the minimum angle between two tracking samples for the current pair of samples to be selected for the computation. A pair is a set of correspondences i and j:

{fixed T moving (i), hand T base (i)} and {fixed T moving (j), hand T base (j)}

Pose inlier threshold specifies the maximum pair error for the pair to be considered as an inlier. The error is computed from the difference of the left handside and the right handside of the following equation:

hand(i) T hand(j) * moving T hand = moving T hand * moving(i) T moving(j)

Use RANSAC specifies if a RANSAC scheme should be used for the computation. If used, three random pairs of poses will be selected for the calibration, this will be repeated a number of iterations and the best result will be selected.

RANSAC iterations specifies the number of RANSAC itrations to be performed.

Apply non-linear refinement indicates if the result should be attempted to be improved by executing a non-linear refinement minimizing the pose difference between the left handside and the right handside of the following equation:

moving T hand * fixed T moving = base T hand * fixed T base

The output of the algorithm will be two tracking streams:

  • Cam-to-Calib with applied registration of Calib-to-Base (Eye-In-Hand case)/ Calib-to-Cam with applied registration of Cam-to-Base (Eye-On-Base case): fixed T base * moving T fixed
  • Hand-to-Base with applied calibration of Cam-to-Hand (Eye-In-Hand case)/ Calib-to-Hand (Eye-On-Base case): hand T base * moving T hand

When the calibration and the registration are applied, the two tracking streams should match as close as possible.

The transformation matrices are also printed in the log output:

  • Cam-to-Hand (Eye-In-Hand case) or Calib-to-Hand (Eye-On-Base case): moving T hand
  • Calib-to-Base (Eye-In-Hand case) or Cam-to-Base (Eye-On-Base case): fixed T base