CalibrateHandEye¶
With this command you can achieve one of the following three goals:
Calibrate the position of the camera with respect to a robot
Calibrate the position of the camera with respect to a robot and recalibrate the robot geometry (see Angles and Links)
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¶
Depending on the geometry of your robot, not all parts of the camera and pattern pose are defined and can be computed from the observations. In this case you have to use the Fixed parameter to manually set them. Specify values for the fixed parameters in the initial guess for CameraPose or PatternPose and they will not change during the calibration.
Robot with 6 Degrees of Freedom at the End Effector¶
Examples:
Standard robot with 6 or more actuated hinge joints
6DOF delta robot
Hexapod
Any other configuration allowing 6DOF movement of the robot end effector
Recommended Pattern Movement
Collect at least 20 pattern observations/robot pose pairs.
Pattern observations should include pattern positions distributed in the operating volume and cover rotations in all axes.
Rotate the pattern as much as possible while it can still be observed in the camera, ideally 20° 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 is similar to the arm configuration during later operation in order to minimize mechanical offsets from robot joint reversal error / backlash.
Observable Parameters
Camera and pattern pose are completely defined by the observations. No specification of the Fixed parameter is necessary.
Robot with 4 Degrees of Freedom at the End Effector¶
Examples:
4 axis scara robot with XYZ movement and Z rotation
4 DOF delta robot allowing XYZ motion and Z rotation
Recommended Pattern Movement
Collect at least 20 pattern observations/robot pose pairs.
Pattern observations should include pattern positions distributed in the operating volume and cover all possible rotations of the pattern. Rotate the pattern as much as possible while it can still be observed in the camera.
Observable Parameters
Due to missing actuated rotation in two axes, the position of these two axes cannot be determined from the pattern observations. The z-coordinates of the camera and pattern poses remain unknown and need to be specified manually. You can choose whether you want to specify the z-coordinate of the camera pose or the pattern pose. Specifying one also determines the other.
Alternative 1: Fix the z-coordinate of the camera pose by specifying:
"Fixed": {
"Link": {
"Translation": [false, false, true]
}
}
Alternative 2: Fix the z-coordinate of the pattern pose by specifying:
"Fixed": {
"PatternPose": {
"Translation": [false, false, true]
}
}
Cartesian Robot¶
With three translational degrees of freedom at the end effector and no rotation.
Examples:
Gantry robot
3DOF delta robot
Recommended Pattern Movement
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).
Observable Parameters
Due to missing actuated rotation, the translation of the axes cannot be determined from the pattern observations. Only the direction of the coordinate axes can be estimated. You can choose whether you want to specify the translation of the camera pose or the pattern pose. Specifying one also determines the other.
Alternative 1: Fix the translation of the camera pose by specifying:
"Fixed": {
"Link": {
"Translation": [true, true, true]
}
}
Alternative 2: Fix the translation of the pattern pose by specifying:
"Fixed": {
"PatternPose": {
"Translation": [true, true, true]
}
}