Touch Test Unsafe to perform due to Bad Hand-Eye Calibration (Dataset with only Translations)

Problem

The hand-eye calibration results are bad, and it is unsafe to perform the touch test.

Hand-Eye Transform

Hand-Eye Residuals

Projection Verification

Touch Test

Bad

Bad

Bad

Unsafe

Example of bad hand-eye calibration results

The Hand-Eye Transformation Matrix does not look correct because several of its values differ from the physical measurements by extremely large amounts that are not reasonable for this setup.

Hand-Eye Transformation Matrix

0.999

-0.005

0.003

6041.859

0.005

0.999

0.024

4033.240

-0.003

-0.024

1.000

590.926

0

0

0

1

The value 590.926 should be approximately 130 mm, and the value 4033.240 should be roughly 90 mm. At this stage we ignore the sign (+/-), because it depends on the coordinate-system definitions; we focus only on the distances.

../../_images/eye_in_hand_approximate_hand_eye_matrix.png

The calibration residuals are also noticeably larger than expected, roughly an order of magnitude higher.

Residuals

N (Poses)

Rot. avg (°)

Rot. max (°)

Trans. avg (mm)

Trans. max (mm)

7

0.033

0.108

2.623

5.001

For smaller robots, we expect the residuals to 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
Residuals

Pose

Rotation (°)

Translation (mm)

1

0.031

1.189

2

0.020

4.366

3

0.108

5.001

4

0.022

1.581

5

0.028

0.765

6

0.018

1.977

7

0.007

3.482

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.

../../_images/projection_verification_poor_only_translations.png

Such results strongly suggest that the hand-eye calibration is not correct, and that the touch test will fail if attempted.

Potential Cause

Only translational movements have been made between the robot poses in the dataset.

This is insufficient for hand-eye calibration because the solver requires rotational motion to uniquely determine the camera’s orientation relative to the robot. Without rotations, the problem becomes under-constrained, leading to unstable or incorrect hand-eye calibration results, large residuals, failed projection verification, and an unsafe touch test.

Potential Solution

  1. Ensure to have both translational and rotational movements between robot poses in the dataset.

    Note: Check How to get Good Dataset for Hand-Eye Calibration.

  2. Re-run the hand-eye calibration (using the corrected dataset).

  3. Verify the hand-eye calibration results (transform, residuals, projection).

  4. Run the touch test (if the hand-eye calibration results are good).

../../_images/touching-test-result-aruco.jpg
Reproducing the issue (only translations in the dataset)

Good Dataset

A hand-eye calibration was successfully performed using the dataset shown in the images below.

../../_images/hand-eye-calibration-translations-and-rotations-dataset.png

The calibration resulted in the following results:

Hand-Eye Transformation Matrix

0.9991385

-0.00262377

0.04141687

-55.73573

0.001416378

0.9995739

0.02915465

-91.3017

-0.04147572

-0.02907087

0.9987165

129.1951

0

0

0

1

Residuals

N (Poses)

Rot. avg (°)

Rot. max (°)

Trans. avg (mm)

Trans. max (mm)

14

0.028

0.068

0.133

0.278

Complete Residuals
Residuals

Pose

Rotation (°)

Translation (mm)

1

0.030

0.149

2

0.039

0.278

3

0.021

0.065

4

0.037

0.138

5

0.013

0.272

6

0.014

0.079

7

0.018

0.133

8

0.013

0.075

9

0.038

0.088

10

0.015

0.061

11

0.026

0.179

12

0.036

0.065

13

0.068

0.209

14

0.023

0.066

The Hand-Eye calibration was verified with a touch test.

../../_images/touch_test_correct.png

The touch test was successful, which confirms that the hand-eye calibration is correct and accurate.

Bad Dataset (dataset with no rotations, only translations)

A hand-eye calibration was performed using the dataset shown in the image below, which contains only translations and no rotations.

../../_images/hand-eye-calibration-only-translations-dataset.png

The calibration resulted in the following results:

Hand-Eye Transformation Matrix

0.999

-0.005

0.003

6041.859

0.005

0.999

0.024

4033.240

-0.003

-0.024

1.000

590.926

0

0

0

1

Residuals

N (Poses)

Rot. avg (°)

Rot. max (°)

Trans. avg (mm)

Trans. max (mm)

7

0.033

0.108

2.623

5.001

Complete Residuals
Residuals

Pose

Rotation (°)

Translation (mm)

1

0.031

1.189

2

0.020

4.366

3

0.108

5.001

4

0.022

1.581

5

0.028

0.765

6

0.018

1.977

7

0.007

3.482

Verification by Projection technically succeeded, but the resulting error was 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.

../../_images/projection_verification_poor_only_translations.png

Such results strongly suggest that the hand-eye calibration is not correct, and that the touch test would fail if attempted.

Comparisons

The results between hand-eye transformation matrices (translation values) and hand-eye calibration residuals are compared in the tables below.

Translation Values in Hand-Eye Transformation Matrix

Dataset

X (mm)

Y (mm)

Z (mm)

Good

-55.73573

-91.3017

129.1951

Bad (only translations)

6041.859

4033.240

590.926

Δ (Good - Bad)

-6097.595

-4124.542

-461.731

Residuals

Dataset

N

Rot. avg (°)

Rot. max (°)

Trans. avg (mm)

Trans. max (mm)

Good

14

0.028

0.068

0.133

0.278

Bad (only translations)

7

0.033

0.108

2.623

5.001