Touch Test Unsafe to perform due to Bad Hand-Eye Calibration (Meters instead of Millimeters)

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

-0.214

-0.108

-1.683

-0.019

0.380

-0.925

375.305

0.239

0.900

0.365

457.970

0

0

0

1

The value 457.970 should be approximately 130 mm, and the value 375.305 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 significantly larger than expected, a couple of orders of magnitude higher.

Residuals

N (Poses)

Rot. avg (°)

Rot. max (°)

Trans. avg (mm)

Trans. max (mm)

14

5.247

12.851

135.333

760.322

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

760.322

2

0.746

92.317

3

2.557

177.495

4

9.364

167.930

5

10.202

174.986

6

0.951

55.776

7

10.514

65.690

8

12.851

69.575

9

2.470

70.544

10

2.625

81.236

11

0.927

43.069

12

2.134

32.829

13

10.851

44.558

14

6.316

58.329

Verification by Projection fails, which suggest that the hand-eye calibration is not correct, and that the touch test will fail badly.

../../_images/projection_verification_bad.png

Potential Cause

The robot poses (translation component) for the Hand-Eye Calibration are provided in meters.

Most industrial robots use meters as the default unit for the robot poses. However, Zivid point clouds are given in millimeters. To have a correct hand-eye calibration, the robot input poses for hand-eye calibration and point clouds must expressed in the same units. Having the robot poses in meters and the point clouds in millimeters is destined to lead to a bad hand-eye calibration with completely incorrect hand-eye transformation matrix.

Potential Solution

  1. Ensure the robot input poses are in millimeters.

    Note: You can just divide the translation component of the robot poses by 1000 if they are in meters, to convert them to millimeters.

  2. Repeat the hand-eye calibration using the same dataset (with robot poses in millimeters).

  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 (Robot Pose in Meters instead of Millimeters)

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

0.004

1.000

0.013

-91.613

-0.043

-0.013

0.999

128.667

0

0

0

1

Residuals

N (Poses)

Rot. avg (°)

Rot. max (°)

Trans. avg (mm)

Trans. max (mm)

14

0.019

0.029

0.144

0.222

Complete Residuals
Residuals

Pose

Rotation (°)

Translation (mm)

1

0.026

0.071

2

0.013

0.218

3

0.020

0.146

4

0.026

0.222

5

0.026

0.181

6

0.007

0.114

7

0.007

0.128

8

0.015

0.066

9

0.023

0.110

10

0.010

0.113

11

0.024

0.149

12

0.023

0.175

13

0.029

0.184

14

0.022

0.132

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 (robot poses in meters instead of millimeters)

To simulate the problem, translation vectors from the input robot poses in the hand-eye calibration dataset were converted from millimeters to meters. Hand-Eye calibration was performed again on the same dataset with modified robot poses.

The calibration resulted in the following results:

Hand-Eye Transformation Matrix

0.971

-0.214

-0.108

-1.683

-0.019

0.380

-0.925

375.305

0.239

0.900

0.365

457.970

0

0

0

1

Residuals

N (Poses)

Rot. avg (°)

Rot. max (°)

Trans. avg (mm)

Trans. max (mm)

14

5.247

12.851

135.333

760.322

Complete Residuals
Residuals

Pose

Rotation (°)

Translation (mm)

1

0.948

760.322

2

0.746

92.317

3

2.557

177.495

4

9.364

167.930

5

10.202

174.986

6

0.951

55.776

7

10.514

65.690

8

12.851

69.575

9

2.470

70.544

10

2.625

81.236

11

0.927

43.069

12

2.134

32.829

13

10.851

44.558

14

6.316

58.329

Verification by Projection failed, which suggests that the hand-eye calibration is not correct, and that the touch test will fail badly. Therefore, the touch test was skipped for safety reasons.

../../_images/projection_verification_bad.png

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 (Poses in mm)

-55.476

-91.613

128.667

Bad (Poses in m)

-1.683

375.305

457.970

Δ (Good - Bad)

-53.793

-466.918

-329.303

Residuals

Dataset

N

Rot. avg (°)

Rot. max (°)

Trans. avg (mm)

Trans. max (mm)

Good (Poses in mm)

14

0.019

0.029

0.144

0.222

Bad (Poses in m)

14

5.247

12.851

135.333

760.322