Unsatisfactory Hand-Eye Calibration Results (Bad Robot Zeroing/Mastering)
Problem
The hand-eye calibration results are bad, looking like one of the following combinations:
Hand-Eye Transform |
Hand-Eye Residuals |
Projection Verification |
Touch Test |
|---|---|---|---|
Reasonable |
Marginal |
Poor |
Bad |
Reasonable |
Good |
Poor |
Bad |
Example of bad hand-eye calibration results
The Hand-Eye Transformation Matrix appears reasonable and is consistent with what one would expect from rough manual measurements (see table and image below).
0.999 |
-0.005 |
0.040 |
-49.956 |
0.003 |
0.999 |
0.037 |
-95.704 |
-0.040 |
-0.037 |
0.998 |
132.236 |
0 |
0 |
0 |
1 |
The calibration residuals are slightly larger than expected.
N (Poses) |
Rot. avg (°) |
Rot. max (°) |
Trans. avg (mm) |
Trans. max (mm) |
|---|---|---|---|---|
13 |
0.083 |
0.213 |
0.438 |
1.205 |
For smaller robots, we expect the residuals to be in the sub-millimeter range, while for larger robots, the residuals can be in the millimeter range. As for the rotational component of the residuals, we expect them to be in the sub-degree range.
Complete Residuals
Pose |
Rotation (°) |
Translation (mm) |
|---|---|---|
1 |
0.030 |
0.092 |
2 |
0.033 |
0.382 |
3 |
0.045 |
0.201 |
4 |
0.140 |
0.565 |
5 |
0.212 |
1.205 |
6 |
0.032 |
0.273 |
7 |
0.146 |
0.356 |
8 |
0.178 |
0.338 |
9 |
0.57 |
0.491 |
10 |
0.029 |
0.471 |
11 |
0.061 |
0.290 |
12 |
0.043 |
0.234 |
13 |
0.073 |
0.794 |
Verification by Projection technically succeeds, but the resulting error is still too large to be acceptable. One should be very critical of projection verification, as the projection error may seem acceptable even if the hand-eye calibration is incorrect.
The touch test result is unsatisfactory. For example, the tip of the touch test misses the ArUco marker.
Potential Cause
The robot zeroing (mastering, or calibration of joint zero positions) is not correct.
Every industrial robot has encoders on the joints. After a power loss, an encoder battery failure, or disassembly, the robot forgets its absolute encoder position. So the controller needs to be retaught exactly where joint zeros are.
When do you typically need to re-master the robot?
After collision
Robot reports Mastering required, Joint not referenced, or similar
Robot moves inaccurately (TCP drift)
The encoder battery died, resulting in joint positions lost
After replacing a joint, motor, or gear
After changing base flange or tool flange
Potential Solution
Ensure your robot zeroing (mastering or calibration of joint zero positions) is correct. When the robot is in the zero pose (all joints set to zero), the physical marks on the robot’s links and joins should be aligned.
Repeat the hand-eye calibration using the same dataset.
Verify the hand-eye calibration results (transform, residuals, projection).
Run the touch test (if the hand-eye calibration results are good).
Reproducing the issue (bad robot zeroing/mastering)
All hand-eye calibrations covered in this section were performed using the dataset shown in the images below.
Good Dataset (robot zeroed)
This hand-eye calibration was performed with a robot that was properly zeroed/mastered. The calibration resulted in the following results:
0.999 |
-0.004 |
0.043 |
-55.558 |
0.003 |
1.000 |
0.013 |
-91.637 |
-0.043 |
-0.013 |
0.999 |
128.629 |
0 |
0 |
0 |
1 |
N (Poses) |
Rot. avg (°) |
Rot. max (°) |
Trans. avg (mm) |
Trans. max (mm) |
|---|---|---|---|---|
13 |
0.020 |
0.031 |
0.143 |
0.221 |
Complete Residuals
Pose |
Rotation (°) |
Translation (mm) |
|---|---|---|
1 |
0.025 |
0.069 |
2 |
0.012 |
0.221 |
3 |
0.017 |
0.140 |
4 |
0.024 |
0.207 |
5 |
0.025 |
0.188 |
6 |
0.007 |
0.123 |
7 |
0.008 |
0.134 |
8 |
0.019 |
0.044 |
9 |
0.027 |
0.116 |
10 |
0.012 |
0.116 |
11 |
0.025 |
0.156 |
12 |
0.027 |
0.179 |
13 |
0.031 |
0.160 |
Verification by Projection was successful.
The Hand-Eye calibration was then verified with a touch test.
The touch test was successful, which confirms that the hand-eye calibration is correct and accurate.
Bad Dataset (robot needs zeroing)
To simulate incorrect robot zeroing/mastering, we modified the angle offsets for the following joints:
J2 = J2 + 0.5°
J3 = J3 + 0.5°
J4 = J4 - 0.5°
The calibration resulted in the following results:
0.999 |
-0.005 |
0.040 |
-49.956 |
0.003 |
0.999 |
0.037 |
-95.704 |
-0.040 |
-0.037 |
0.998 |
132.236 |
0 |
0 |
0 |
1 |
N (Poses) |
Rot. avg (°) |
Rot. max (°) |
Trans. avg (mm) |
Trans. max (mm) |
|---|---|---|---|---|
13 |
0.083 |
0.213 |
0.438 |
1.205 |
Complete Residuals
Pose |
Rotation (°) |
Translation (mm) |
|---|---|---|
1 |
0.030 |
0.092 |
2 |
0.033 |
0.382 |
3 |
0.045 |
0.201 |
4 |
0.140 |
0.565 |
5 |
0.212 |
1.205 |
6 |
0.032 |
0.273 |
7 |
0.146 |
0.356 |
8 |
0.178 |
0.338 |
9 |
0.57 |
0.491 |
10 |
0.029 |
0.471 |
11 |
0.061 |
0.290 |
12 |
0.043 |
0.234 |
13 |
0.073 |
0.794 |
Verification by Projection technically succeeded, but the resulting error was too large to be acceptable. One should be very critical of projection verification, as the projection error may seem acceptable even if the hand-eye calibration is incorrect.
The touch test result was unsatisfactory as the tip of the touch test missed the ArUco marker.
Comparisons
The results between hand-eye calibration matrices (translation values) and hand-eye calibration residuals are compared in the tables below.
Dataset |
X (mm) |
Y (mm) |
Z (mm) |
|---|---|---|---|
Good Zeroing |
-55.558 |
-91.637 |
128.629 |
Bad Zeroing |
-49.956 |
-95.704 |
132.236 |
Δ (Good - Bad) |
-5.602 |
3.933 |
-3.607 |
Dataset |
N |
Rot. avg (°) |
Rot. max (°) |
Trans. avg (mm) |
Trans. max (mm) |
|---|---|---|---|---|---|
Good Zeroing |
13 |
0.020 |
0.031 |
0.143 |
0.221 |
Bad Zeroing |
13 |
0.083 |
0.213 |
0.438 |
1.205 |