Hand-eye calibration¶
For applications, in which the camera is integrated into one or more robot systems, it needs to be calibrated w.r.t. some robot reference frames. For this purpose, the rc_visard is shipped with an on-board calibration routine called the hand-eye calibration module. It is a base module which is available on every rc_visard.
Note
The implemented calibration routine is completely agnostic about the user-defined robot frame to which the camera is calibrated. It might be a robot’s end-effector (e.g., flange or tool center point) or any point on the robot structure. The method’s only requirement is that the pose (i.e., translation and rotation) of this robot frame w.r.t. a user-defined external reference frame (e.g., world or robot mounting point) is exactly observable by the robot controller and can be reported to the calibration module.
The Calibration routine itself is an easy-to-use multi-step procedure using a calibration grid which can be obtained from Basler.
Calibration interfaces¶
The following two interfaces are offered to conduct hand-eye calibration:
All services and parameters of this module required to conduct the hand-eye calibration programmatically are exposed by the rc_visard’s REST-API interface. The respective node name of this module is
rc_hand_eye_calibration
and the respective service calls are documented Services.Note
The described approach requires a network connection between the rc_visard and the robot controller to pass robot poses from the controller to the rc_visard’s calibration module.
For use cases where robot poses cannot be passed programmatically to the rc_visard’s hand-eye calibration module, the Web GUI’s Hand-Eye Calibration page under Configuration offers a guided process to conduct the calibration routine manually.
Note
During the process, the described approach requires the user to manually enter into the Web GUI robot poses, which need to be accessed from the respective robot-teaching or handheld device.
Camera mounting¶
As illustrated in Fig. 36 and Fig. 38, two different use cases w.r.t. to the mounting of the camera generally have to be considered:
- The camera is mounted on the robot, i.e., it is mechanically fixed to a robot link (e.g., at its flange or a flange-mounted tool), and hence moves with the robot.
- The camera is not mounted on the robot but is fixed to a table or other place in the robot’s vicinity and remains at a static position w.r.t. the robot.
While the general Calibration routine is very similar in both use cases, the calibration process’s output, i.e., the resulting calibration transform, will be semantically different, and the fixture of the calibration grid will also differ.
- Calibration with a robot-mounted camera
When calibrating a robot-mounted camera with the robot, the calibration grid has to be secured in a static position w.r.t. the robot, e.g., on a table or some other fixed-base coordinate system as sketched in Fig. 36.
Warning
It is extremely important that the calibration grid does not move during step 2 of the Calibration routine. Securely fixing its position to prevent unintended movements such as those caused by vibrations, moving cables, or the like is therefore strongly recommended.
The result of the calibration (step 3 of the Calibration routine) is a pose describing the (previously unknown) relative positional and rotational transformation from the camera frame into the user-selected robot frame such that
(3)¶
where is a 3D point with its coordinates expressed in the robot frame, is the same point represented in the camera coordinate frame, and as well as are the corresponding rotation matrix and translation vector of the pose , respectively. In practice, in the calibration result and in the provided robot poses, the rotation is defined by Euler angles or as quaternion instead of a rotation matrix (see Pose formats).
Additional user input is required if the movement of the robot is constrained and the robot can rotate the Tool Center Point (TCP) only around one axis. This is typically the case for robots with four Degrees Of Freedom (4DOF) that are often used for palletizing tasks. In this case, the user must specify which axis of the robot frame is the rotation axis of the TCP. Further, the signed offset from the TCP to the camera coordinate system along the TCP rotation axis has to be provided. Fig. 37 illustrates the situation.
For the rc_visard, the camera coordinate system is located in the optical center of the left camera. The approximate location is given in section Coordinate frames.
- Calibration with a statically-mounted camera
In use cases where the camera is positioned statically w.r.t. the robot, the calibration grid needs to be mounted to the robot as shown for example in Fig. 38 and Fig. 39.
Note
The hand-eye calibration module is completely agnostic about the exact mounting and positioning of the calibration grid w.r.t. the user-defined robot frame. That means, the relative positioning of the calibration grid to that frame neither needs to be known, nor it is relevant for the calibration routine, as shown in Fig. 39.
Warning
It is extremely important that the calibration grid is attached securely to the robot such that it does not change its relative position w.r.t. the user-defined robot frame during step 2 of the Calibration routine.
In this use case, the result of the calibration (step 3 of the Calibration routine) is the pose describing the (previously unknown) relative positional and rotational transformation between the camera frame and the user-selected external reference frame ext such that
(4)¶
where is a 3D point with its coordinates expressed in the external reference frame ext, is the same point represented in the camera coordinate frame, and as well as are the corresponding rotation matrix and translation vector of the pose , respectively. In practice, in the calibration result and in the provided robot poses, the rotation is defined by Euler angles or as quaternion instead of a rotation matrix (see Pose formats).
Additional user input is required if the movement of the robot is constrained and the robot can rotate the Tool Center Point (TCP) only around one axis. This is typically the case for robots with four Degrees Of Freedom (4DOF) that are often used for palletizing tasks. In this case, the user must specify which axis of the robot frame is the rotation axis of the TCP. Further, the signed offset from the TCP to the visible surface of the calibration grid along the TCP rotation axis has to be provided. The grid must be mounted such that the TCP rotation axis is orthogonal to the grid. Fig. 40 illustrates the situation.
Calibration routine¶
The hand-eye calibration can be performed manually using the Web GUI or programmatically via the REST-API interface. The general calibration routine will be described by following the steps of the hand-eye calibration wizard provided on the Web GUI. This wizard can be found in the rc_visard’s Web GUI under . References to the corresponding REST-API calls are provided at the appropriate places.
Step 1: Hand-Eye Calibration Status¶
The starting page of the hand-eye calibration wizard shows the current status of the hand-eye calibration. If a hand-eye calibration is saved on the rc_visard, the calibration transformation is displayed here (see Fig. 41).
To query the hand-eye calibration status programmatically, the module’s REST-API
offers the get_calibration
service call (see
Services).
An existing hand-eye calibration can be removed by pressing
Remove Calibration or using remove_calibration
in the REST-API (see
Services).
To start a new hand-eye calibration, click on Perform Hand-Eye Calibration or Next.
Step 2: Checking Grid Detection¶
To achieve good calibration results, the images should be well exposed so that the calibration grid can be detected accurately and reliably. In this step, the grid detection can be checked and the camera settings can be adjusted if necessary. In case parts of the calibration grid are overexposed, the respective squares of the calibration grid will be highlighted in red. A successful grid detection is visualized by green check marks on every square of the calibration grid and a thick green border around the grid as shown in Fig. 42.
Step 3: Record Poses¶
In this step, the user records images of the calibration grid at several different robot poses. These poses must each ensure that the calibration grid is completely visible in the left camera image. Furthermore, the robot poses need to be selected properly to achieve a variety of different perspectives for the camera to perceive the calibration grid. Fig. 43 shows a schematic recommendation of four different grid positions which should be recorded from a close and a far point of view, resulting in eight images for the calibration.
Warning
Calibration quality, i.e., the accuracy of the calculated calibration result, depends on the calibration-grid views provided. The more diverse the perspectives are, the better is the calibration. Choosing very similar views, i.e., varying the robot pose only slightly before recording a new calibration pose, may lead to inaccurate estimation of the desired calibration transformation.
After the robot reaches each calibration pose, the corresponding pose of the user-defined robot frame in the user-defined external reference frame ext needs to be reported to the hand-eye calibration module. For this purpose, the module offers different slots to store the reported poses and the corresponding left camera images. All filled slots will then be used to calculate the desired calibration transformation between the camera frame and either the user-defined robot frame (robot-mounted camera) or the user-defined external reference frame ext (static camera).
In the Web GUI, the user can choose between many different pose formats for providing the calibration poses (see Pose formats). When calibrating using the REST-API, the poses are always given in XYZ+quaternion. The Web GUI offers eight slots (Close View 1, Close View 2, etc.) for the user to fill manually with robot poses. Next to each slot, a figure suggests a respective dedicated viewpoint on the grid. For each slot, the robot should be operated to achieve the suggested view.
To record a calibration pose, click on Set Pose for the respective slot and enter the robot frame’s pose into the respective text fields. The pose is then stored with the corresponding camera image by clicking the Take Picture to Proceed button. This will save the calibration pose in the respective slot.
To transmit the poses programmatically, the module’s REST-API
offers the set_pose
service call (see
Services).
Note
The user’s acquisition of robot pose data depends on the robot model and manufacturer – it might be read from a teaching or handheld device, which is shipped with the robot.
Warning
Please be careful to correctly and accurately enter the values; even small variations or typos may lead to calibration-process failure.
The Web GUI displays the currently saved poses (only with slot numbers from 0 to 7)
with their camera images and also allows to delete them by clicking
Delete Pose to remove a single pose, or clicking Clear all Poses to remove all poses.
In the REST-API the currently stored poses can be retrieved via get_poses
and removed
via delete_poses
for single poses or reset_calibration
for removing all poses
(see Services).
When at least four poses are set, the user can continue to the computation of the calibration result by pressing Next.
Note
To successfully calculate the hand-eye calibration transformation, at least four different robot calibration poses need to be reported and stored in slots. However, to prevent errors induced by possible inaccurate measurements, at least eight calibration poses are recommended.
Step 4: Compute Calibration¶
Before computing the calibration result, the user has to provide the correct calibration parameters. These include the exact calibration grid dimensions and the sensor mounting type. The Web GUI also offers settings for calibrating 4DOF robots. In this case, the rotation axis, as well as the offset from the TCP to the camera coordinate system (robot-mounted camera) or grid surface (statically mounted camera) must be given. For the REST-API, the respective parameters are listed in Parameters.
When the parameters are correct, the desired calibration transformation
can be computed from the collected poses and camera images by clicking
Compute Calibration. The REST-API offers this functionality via the
calibrate
service call
(see Services).
Depending on the way the camera is mounted, the calibration result contains the transformation (i.e., the pose) between the camera frame and either the user-defined robot frame (robot-mounted camera) or the user-defined external reference frame ext (statically mounted camera); see Camera mounting.
To enable users to judge the quality of the resulting calibration transformation, the translational and rotational calibration errors are reported, which are computed from the variance of the calibration result.
If the calibration error is not acceptable, the user can change the calibration parameters and recompute the result, or return to step 3 of the calibration procedure and add more poses or update poses.
To save the calibration result, press Save Calibration or use the
REST-API save_calibration
service call
(see Services).
Parameters¶
The hand-eye calibration module is called rc_hand_eye_calibration
in the REST-API and is
represented in the
Web GUI
under .
The user can change the calibration parameters there or use the
REST-API interface.
Parameter overview¶
This module offers the following run-time parameters:
Name | Type | Min | Max | Default | Description |
---|---|---|---|---|---|
grid_height |
float64 | 0.0 | 10.0 | 0.0 | The height of the calibration pattern in meters |
grid_width |
float64 | 0.0 | 10.0 | 0.0 | The width of the calibration pattern in meters |
robot_mounted |
bool | false | true | true | Whether the camera is mounted on the robot |
tcp_offset |
float64 | -10.0 | 10.0 | 0.0 | Offset from TCP along tcp_rotation_axis |
tcp_rotation_axis |
int32 | -1 | 2 | -1 | -1 for off, 0 for x, 1 for y, 2 for z |
Description of run-time parameters¶
The parameter descriptions are given with the corresponding Web GUI names in brackets.
grid_width
(Width)¶
Width of the calibration grid in meters. The width should be given with a very high accuracy, preferably with sub-millimeter accuracy.
Via the REST-API, this parameter can be set as follows.
PUT http://<host>/api/v2/pipelines/0/nodes/rc_hand_eye_calibration/services/parameters?grid_width=<value>
PUT http://<host>/api/v1/nodes/rc_hand_eye_calibration/parameters?grid_width=<value>
grid_height
(Height)¶
Height of the calibration grid in meters. The height should be given with a very high accuracy, preferably with sub-millimeter accuracy.
Via the REST-API, this parameter can be set as follows.
PUT http://<host>/api/v2/pipelines/0/nodes/rc_hand_eye_calibration/services/parameters?grid_height=<value>
PUT http://<host>/api/v1/nodes/rc_hand_eye_calibration/parameters?grid_height=<value>
robot_mounted
(Sensor Mounting)¶
If set to true, the camera is mounted on the robot. If set to false, the camera is mounted statically and the calibration grid is mounted on the robot.
Via the REST-API, this parameter can be set as follows.
PUT http://<host>/api/v2/pipelines/0/nodes/rc_hand_eye_calibration/services/parameters?robot_mounted=<value>
PUT http://<host>/api/v1/nodes/rc_hand_eye_calibration/parameters?robot_mounted=<value>
tcp_offset
(TCP Offset)¶
The signed offset from the TCP to the camera coordinate system (robot-mounted sensor) or the visible surface of the calibration grid (statically mounted sensor) along the TCP rotation axis in meters. This is required if the robot’s movement is constrained and it can rotate its TCP only around one axis (e.g., 4DOF robot).
Via the REST-API, this parameter can be set as follows.
PUT http://<host>/api/v2/pipelines/0/nodes/rc_hand_eye_calibration/services/parameters?tcp_offset=<value>
PUT http://<host>/api/v1/nodes/rc_hand_eye_calibration/parameters?tcp_offset=<value>
tcp_rotation_axis
(TCP Rotation Axis)¶
The axis of the robot frame around which the robot can rotate its TCP. 0 is used for X, 1 for Y and 2 for the Z axis. This is required if the robot’s movement is constrained and it can rotate its TCP only around one axis (e.g., 4DOF robot). -1 means that the robot can rotate its TCP around two independent rotation axes.
tcp_offset
is ignored in this case.Via the REST-API, this parameter can be set as follows.
PUT http://<host>/api/v2/pipelines/0/nodes/rc_hand_eye_calibration/services/parameters?tcp_rotation_axis=<value>
PUT http://<host>/api/v1/nodes/rc_hand_eye_calibration/parameters?tcp_rotation_axis=<value>
Services¶
The REST-API service calls offered to programmatically conduct the hand-eye calibration and to restore this module’s parameters are explained below.
get_calibration
¶
returns the hand-eye calibration currently stored on the rc_visard.
Details
remove_calibration
¶
removes the persistent hand-eye calibration on the rc_visard. After this call the
get_calibration
service reports again that no hand-eye calibration is available. This service call will also delete all the stored calibration poses and corresponding camera images in theslots
.Details
set_pose
¶
allows to provide a robot pose as calibration pose to the hand-eye calibration routine and records the current image of the calibration grid.
Details
get_poses
¶
returns the robot poses that are currently stored for the hand-eye calibration routine.
Details
delete_poses
¶
deletes the calibration poses and corresponding images with the specified
slots
.Details
reset_calibration
¶
deletes all previously provided poses and corresponding images. The last saved calibration result is reloaded. This service might be used to (re-)start the hand-eye calibration from scratch.
Details
calibrate
¶
calculates and returns the hand-eye calibration transformation with the robot poses configured by the
set_pose
service.Details
save_calibration
¶
persistently saves the result of hand-eye calibration to the rc_visard and overwrites the existing one. The stored result can be retrieved any time by the
get_calibration
service. This service call will also delete all the stored calibration poses and corresponding camera images in theslots
.Details
set_calibration
¶
sets the hand-eye calibration transformation with arguments of this call.
Details
reset_defaults
¶
restores and applies the default values for this module’s parameters (“factory reset”). Does not affect the calibration result itself or any of the
slots
saved during calibration. Only parameters such as the grid dimensions and the mount type will be reset.Details