Touch Test Unsafe to perform due to Bad Hand-Eye Calibration (Calibration Board Moved or Shifted)

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 more than expected from the physical measurements. The differences are not extremely large, but they are beyond what would be considered reasonable for this setup.

Hand-Eye Transformation Matrix

0.994

0.040

0.099

-84.190

-0.042

0.999

0.021

-84.129

-0.098

-0.025

0.995

147.697

0

0

0

1

The value 147.697 should be approximately 130 mm, and the value -84.129 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)

13

2.449

5.590

4.626

10.946

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

5.590

10.946

2

4.864

6.151

3

5.294

5.707

4

1.682

7.975

5

1.537

4.446

6

1.570

6.958

7

1.738

2.492

8

0.950

2.917

9

1.973

5.113

10

1.546

0.831

11

1.851

0.773

12

1.701

3.509

13

1.544

2.329

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.png

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

Potential Cause

Eye-in-Hand:

The calibration board moved during the acquisition of the dataset.

Eye-to-Hand:

Either the camera or the calibration board moved during the acquisition of the dataset.

Any movement of the calibration board (Eye-in-Hand) or the camera/board-in-flange (Eye-to-Hand) during dataset acquisition breaks the assumption of rigid geometry that hand-eye calibration relies on. This introduces inconsistent robot-camera relationships from frame to frame, causing the solver to converge to a hand-eye transform that does not match the physical setup.

As a result, you may see high residuals, poor projection accuracy, and a hand-eye transformation matrix whose distances differ from real geometry. In severe cases, the resulting transform can make touch test validation unsafe due to risk of collision.

Potential Solution

  1. Ensure the camera and calibration board are securely mounted and will not move during data acquisition.

  2. Repeat the hand-eye calibration using the same 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 (calibration board moved on purpose)

Good Dataset

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

../../_images/hand-eye-calibration-small-movements-dataset.png

The calibration resulted in the following results:

Hand-Eye Transformation Matrix

0.999

-0.004

0.043

-55.936

0.003

0.999

0.013

-91.919

-0.043

-0.013

0.998

128.086

0

0

0

1

Residuals

N (Poses)

Rot. avg (°)

Rot. max (°)

Trans. avg (mm)

Trans. max (mm)

14

0.022

0.034

0.180

0.338

Complete Residuals
Residuals

Pose

Rotation (°)

Translation (mm)

1

0.017

0.163

2

0.008

0.135

3

0.028

0.172

4

0.009

0.053

5

0.031

0.236

6

0.006

0.060

7

0.009

0.154

8

0.015

0.102

9

0.031

0.147

10

0.009

0.145

11

0.030

0.249

12

0.023

0.152

13

0.034

0.255

14

0.031

0.169

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 (wrong hand-eye configuration)

To simulate the problem, the calibration board was intentionally moved between two captures during the acquisition of the dataset (see image below).

../../_images/hand-eye-calibration-small-movements-dataset-board-moved.png

The calibration resulted in the following results.

Hand-Eye Transformation Matrix

0.994

0.040

0.099

-84.190

-0.042

0.999

0.021

-84.129

-0.098

-0.025

0.995

147.697

0

0

0

1

Residuals

N (Poses)

Rot. avg (°)

Rot. max (°)

Trans. avg (mm)

Trans. max (mm)

13

2.449

5.590

4.626

10.946

Complete Residuals
Residuals

Pose

Rotation (°)

Translation (mm)

1

5.590

10.946

2

4.864

6.151

3

5.294

5.707

4

1.682

7.975

5

1.537

4.446

6

1.570

6.958

7

1.738

2.492

8

0.950

2.917

9

1.973

5.113

10

1.546

0.831

11

1.851

0.773

12

1.701

3.509

13

1.544

2.329

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.

Such results strongly suggest that the hand-eye calibration is not correct, and that the touch test will fail if attempted, so it was skipped for safety reasons.

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 (Board Stable)

-55.936

-91.919

128.086

Bad (Board Moved)

-84.190

-84.129

147.697

Δ (Good - Bad)

28.254

-7.790

-19.611

Residuals

Dataset

N

Rot. avg (°)

Rot. max (°)

Trans. avg (mm)

Trans. max (mm)

Good (Board Stable)

14

0.022

0.034

0.180

0.338

Bad (Board Moved)

13

2.449

5.590

4.626

10.946