CalibrateHandEye

With this command you can achieve one of the following three goals:

  1. Calibrate the position of the camera with respect to a robot

  2. Calibrate the position of the camera with respect to a robot and recalibrate the robot geometry (see Angles and Links)

  3. Evaluate an existing calibration (see MeasureCalibration)

The calibration routine currently supports two types of setup: either your camera has a fixed mounting point in the world or your camera is mounted on the robot hand and moves with it.

Fixed Camera

To calibrate a fixed camera you need to grab a calibration pattern with the robot, move the pattern around and observe it in these different poses with the camera. The exact position of the pattern in the robot hand does not need to be known, it will be calculated during calibration along with the camera’s pose relative to the robot origin.

Moving Camera

For this setup you need to place a calibration pattern inside the robot’s workspace so that the camera can observe it, move the robot hand and thus the camera around and observe the pattern from these different poses. Again, the exact position of the calibration pattern does not need to be known, it will be calculated during calibration along with the camera’s pose relative to the robot hand.

See the hand-eye calibration guide for an in-depth explanation of how this command works and the steps that are necessary to use it.

Note

The calibration data applied after the CalibrateHandEye command is not yet stored permanently on the camera! Use StoreCalibration to permanently store the link in the camera’s eeprom.

Note

The calibration can be interrupted by the Break command.

Parameters for Different Robot Geometries

Robot Type / Geometry

Recommended Pattern Movement

Observable Parameters

Fixed Parameter Value

Robot with 6 degrees of freedom at end effector, e.g.

  • standard robot with 6 or more actuated hinge joints

  • 6DOF delta robot

  • Hexapod

  • any other configuration allowing 6DOF movement of robot end effector

Collect at least 20 pattern observations/robot pose pairs

Pattern observations should include pattern positions distributed in the operating volume and cover variation of the pattern rotation in all axes.

Use the maximum possible pattern rotations to still allow observation of the pattern in the camera, ideally +/-20 degrees or more. Using an initial rotation and chaining rotations with random axes and fixed angle is generally sufficient.

Try to use a robot arm configuration during calibration which similar to the arm configuration during later operation in order to minimize mechanical offsets from robot joint reversal error / backlash.

Camera pose (Link) and pattern pose should be completely observable

leave empty to determine all parameters for Link and PatternPose

Robot with 4 degrees of freedom at end effector, e.g.

  • 4 axis scara robot with XYZ movement and Z rotation

  • 4 DOF delta robot allowing XYZ motion and Z rotation

Collect at least 20 pattern observations/robot pose pairs

Pattern observations should include pattern positions distributed in the operating volume and cover variation of the pattern rotation.

Use the maximum possible pattern rotations to still allow observation of the pattern in the camera.

Due to missing actuated rotation in two axes the position of these two axes cannot be determined from the pattern observations. The Z-coordinate of the Link and PatternPose transformations remain unknown and need to set fixed.

Alternative 1: Fix the camera pose Z component in robot or hand frame by specifying:

"Fixed": {
"Link":{
"Translation": [false, false, true]
 }
}

Alternative 2: Fix the pattern pose Z-component in robot or hand frame by specifying:

"Fixed": {
"PatternPose":{
"Translation": [false, false, true]
 }
}

Cartesian coordinate robot with 3 translational degrees of freedom at end effector without rotation, e.g.

  • Gantry robot

  • 3DOF delta robot

Collect at least 8 pattern observations/robot pose pairs

Pattern observations should include pattern positions distributed in the operating volume (e.g. all 8 corners).

Due to missing actuated rotation the position of the axes cannot be determined from the pattern observations. Only the direction of the coordinate axes can be estimated.

Alternative 1: Fix the camera pose in robot or hand frame by specifying:

 "Fixed": {
 "Link":{
 "Translation": [true, true, true]
 }
}

Alternative 2: Fix the pattern pose in robot or hand frame by specifying:

 "Fixed": {
 "PatternPose":{
 "Translation": [true, true, true]
 }
}

Note

Locked parameters in Fixed do not need to be fixed to zero. When specifying them in the initial guess for CameraPose or PatternPose the given values will be used instead.