1. Introduction
This tutorial focuses estimation of the homogeneous transformation between the robot end-effector and the camera frame in the case of a camera attached to the robot end-effector. This configuration is also called eye-in-hand.
As a use case, we will consider in this tutorial the case of either:
- a Panda robot in its research version from, Franka Emika equipped with an Intel Realsense D435 camera mounted on its end-effector
- or a robot from Universal Robots also equipped with an Intel Realsense D435 camera mounted on its end-effector.
The principle of the extrinsic eye-in-hand calibration is easy to apply to any other robot equipped with any other camera attached to the robot end-effector.
Let us consider:
the homogeneous transformation between the robot reference frame and the robot end-effector
the homogeneous transformation between the camera frame and a calibration grid frame (also called object frame), typically the OpenCV chessboard
the homogeneous transformation between the end-effector and the camera frame. This is the transformation corresponding to the extrinsic eye-in-hand transformation that we have to estimate.
the homogeneous transformation between the robot reference frame and the object frame. This transformation is also estimated.
The calibration process described in this tutorial consists in 3 steps:
- acquiring data consisting in couples of
poses, images of the chessboard and camera intrinsic parameters
- computing the corresponding
pose of the chessboard from the images
- from the basket of
corresponding to couple of poses
the last step is to estimate the
extrinsic transformation.
Note that all the material (source code) described in this tutorial is part of ViSP source code (in apps/calibration/hand-eye folder) and could be found in https://github.com/lagadic/visp/tree/master/apps/calibration/hand-eye.
- Note
- To get good calibration results follow these 2. Recommendations.
2. Prerequisites
2.1. Get intrinsic parameters
In order to compute the pose
from the chessboard image, there is the need to get the camera intrinsic parameters. Depending on the device, these parameters are part of the device SDK or firmware. This is for example the case for our Intel Realsense D435 camera considered in this tutorial. These intrinsic factory parameters could be retrieved using vpRealSense2::getCameraParameters().
If you have an other camera than a Realsense, or if you want to have a better estimation than the factory parameters you may follow Tutorial: Camera intrinsic calibration. Otherwise you can skip this section.
- Note
- In any case, calibrating your camera following Tutorial: Camera intrinsic calibration will allow you to estimate intrinsic parameters, including image distortion (see vpCameraParameters class). When using the intrinsic factory parameters, the model doesn't include image distortion. When a model with distortion is used, the results of hand-eye calibration are better.
2.2. Print a chessboard
Download and print a black and white chessboard OpenCV_Chessboard.pdf.
Glue the chessboard on a flat surface and put it under the camera mounted on the robot end-effector.
3. Extrinsic calibration overview
3.1. Acquire data
The objective here is to complete step 1 by acquiring couples of
poses and the corresponding images of the chessboard. To this end move the camera attached to the robot to different positions. At least 8 to 10 positions are requested. To define a good position you have to imagine a half sphere over the chessboard and select positions that discretise as much as possible all the half sphere surface. For each position you should see all the chessboard as large as possible in the image.
The following image shows a set of 10 camera positions covering the half sphere over the chessboard. Each blue arrow represents camera z-axis pointing to a region close to the chessboard center. The orientation of the frame attached to the chessboard doesn't matter. The chessboard z-axis could be going upward or not.
To acquire images of the chessboard, depending of your device you can follow Tutorial: Image frame grabbing. Images could be saved in jpeg or png format, or any format supported by ViSP.
To get the corresponding
poses, you need to use one of our robot interface like vpRobotFranka::getPosition(vpRobot::END_EFFECTOR_FRAME), vpRobotUniversalRobots::getPosition(vpRobot::END_EFFECTOR_FRAME)... It returns the homogeneous transformation between the robot reference frame and the robot end-effector. The following code snippet shows how to save the pose in yaml format:
int cpt = 1;
std::stringstream ss;
ss << "pose_rPe_" << cpt << ".yaml";
static bool saveYAML(const std::string &filename, const vpArray2D< Type > &A, const char *header="")
Implementation of a pose vector and operations on poses.
To complete this step, you need also to get or calibrate your camera intrinsics in order to obtain its intrinsic parameters. Camera intrinsic parameters need to be saved in an xml file. If you have an Intel RealSense device you can directly get the parameters using vpRealSense2::getCameraParameters() and then save the parameters in an xml file using vpXmlParserCamera::save(). An example is given in visp-acquire-franka-calib-data.cpp or in visp-acquire-universal-robots-calib-data.cpp
- Note
- With vpRealSense2::getCameraParameters() you can only get the parameters without distortion coefficients. If you want the parameters with distortion, you need to achieve a calibration as described in Tutorial: Camera intrinsic calibration.
As an example, in ViSP build folder you will find a dataset in "data-eye-in-hand" folder corresponding to data acquired with a real Panda robot that has a camera attached to its end-effector. These data were acquired with visp-acquire-franka-calib-data.cpp binary described in section 4.1. Panda robot + Realsense.
$ cd $VISP_WS/visp-build/apps/calibration/hand-eye
$ ls data-eye-in-hand
chessboard-data.txt franka_image-2.png franka_image-5.png franka_image-8.png franka_pose_rPe_3.yaml franka_pose_rPe_6.yaml
franka_camera.xml franka_image-3.png franka_image-6.png franka_pose_rPe_1.yaml franka_pose_rPe_4.yaml franka_pose_rPe_7.yaml
franka_image-1.png franka_image-4.png franka_image-7.png franka_pose_rPe_2.yaml franka_pose_rPe_5.yaml franka_pose_rPe_8.yaml
In this dataset, you will find:
- 8 images of the 9x6 chessboard in franka_image-*.png files
- the corresponding pose of the end-effector in the robot reference frame noted
and saved as a pose vector in yaml format in franka_pose_rPe_*.yaml files
- camera intrinsic parameters in franka_camera.xml (this file contains factory intrincic parameters)
- and the size of the chessboard in chessboard-data.txt (9x6 chessboard where each square of the calibration grid is 0.0236 m large).
3.2. Compute chessboard poses
Here we will complete step 2 by computing for each image the corresponding
pose of the chessboard using the camera intrinsic parameters recorded in the xml file.
To this end you can use visp-compute-chessboard-poses binary to compute the different poses of the chessboard with respect to the camera frame.
Considering the dataset presented in previous section, and knowing that the size of the each chessboard square is 0.0236 by 0.0236 meter (modify option --square-size according to your chessboard), to proceed with the dataset you may run:
$ cd $VISP_WS/visp-build/apps/calibration/hand-eye
$ ./visp-compute-chessboard-poses \
--square-size 0.0236 \
--input data-eye-in-hand/franka_image-%d.png \
--intrinsic data-eye-in-hand/franka_camera.xml \
--output data-eye-in-hand/franka_pose_cPo_%d.yaml
It will produce the following results:
Parameters:
Chessboard
Width : 9
Height : 6
Square size [m] : 0.0236
Input images location : data-eye-in-hand/franka_image-%d.png
First frame : 1
Last frame : 8
Camera intrinsics
Param file name [.xml]: data-eye-in-hand/franka_camera.xml
Camera name : Camera
Output camera poses : data-eye-in-hand/franka_pose_cPo_%d.yaml
Interactive mode : yes
Found camera with name: "Camera"
Camera parameters used to compute the pose:
Camera parameters for perspective projection with distortion:
px = 607.5931396 py = 607.5749512
u0 = 323.4628296 v0 = 243.2552948
kud = -0
kdu = 0
Process image: data-eye-in-hand/franka_image-1.png
Save data-eye-in-hand/franka_pose_cPo_1.yaml
Process image: data-eye-in-hand/franka_image-2.png
Save data-eye-in-hand/franka_pose_cPo_2.yaml
Process image: data-eye-in-hand/franka_image-3.png
Save data-eye-in-hand/franka_pose_cPo_3.yaml
Process image: data-eye-in-hand/franka_image-4.png
Save data-eye-in-hand/franka_pose_cPo_4.yaml
Process image: data-eye-in-hand/franka_image-5.png
Save data-eye-in-hand/franka_pose_cPo_5.yaml
Process image: data-eye-in-hand/franka_image-6.png
Save data-eye-in-hand/franka_pose_cPo_6.yaml
Process image: data-eye-in-hand/franka_image-7.png
Save data-eye-in-hand/franka_pose_cPo_7.yaml
Process image: data-eye-in-hand/franka_image-8.png
Save data-eye-in-hand/franka_pose_cPo_8.yaml
- Note
- At this point, you may notice that the camera parameters read from the data-eye-in-hand/franka_camera.xml file do not take image distortion into account, since the kud and kdu parameters are set to zero.
Camera parameters used to compute the pose:
Camera parameters for perspective projection with distortion:
px = 607.5931396 py = 607.5749512
u0 = 323.4628296 v0 = 243.2552948
kud = -0
kdu = 0
-
As mentioned above, the results of eye-in-hand calibration can gain in accuracy when using rather intrinsics that consider also image distortion.
The source code corresponding to the binary is available in visp-compute-chessboard-poses.cpp.
It produces as output the corresponding franka_pose_cPo_8.yaml files that are saved in "data-eye-in-hand" folder. They correspond to the camera to chessboard transformation:
$ ls data-eye-in-hand/franka_pose_cPo_*
data-eye-in-hand/franka_pose_cPo_1.yaml data-eye-in-hand/franka_pose_cPo_4.yaml data-eye-in-hand/franka_pose_cPo_7.yaml
data-eye-in-hand/franka_pose_cPo_2.yaml data-eye-in-hand/franka_pose_cPo_5.yaml data-eye-in-hand/franka_pose_cPo_8.yaml
data-eye-in-hand/franka_pose_cPo_3.yaml data-eye-in-hand/franka_pose_cPo_6.yaml
3.3. Estimate extrinsic transformation
The final step consists now to estimate the end-effector to camera
transformation from the couples of
and
poses.
Complete the calibration running visp-compute-eye-in-hand-calibration binary. It will get the data from the pair of files, franka_pose_rPe_%d.yaml and franka_pose_cPo_%d.yaml located in "data-eye-in-hand" folder.
$ cd $VISP_WS/visp-build/apps/calibration/hand-eye
$ ./visp-compute-eye-in-hand-calibration \
--data-path data-eye-in-hand/ \
--rPe franka_pose_rPe_%d.yaml \
--cPo franka_pose_cPo_%d.yaml \
--output-ePc data-eye-in-hand/franka_ePc.yaml \
--output-rPo data-eye-in-hand/franka_rPo.yaml
The source code corresponding to the binary is available in visp-compute-eye-in-hand-calibration.cpp.
It will produce the following results:
Use data from data-eye-in-hand//data-eye-in-hand/franka_pose_rPe_1.yaml and from data-eye-in-hand/franka_pose_cPo_1.yaml
Use data from data-eye-in-hand//data-eye-in-hand/franka_pose_rPe_2.yaml and from data-eye-in-hand/franka_pose_cPo_2.yaml
Use data from data-eye-in-hand//data-eye-in-hand/franka_pose_rPe_3.yaml and from data-eye-in-hand/franka_pose_cPo_3.yaml
Use data from data-eye-in-hand//data-eye-in-hand/franka_pose_rPe_4.yaml and from data-eye-in-hand/franka_pose_cPo_4.yaml
Use data from data-eye-in-hand//data-eye-in-hand/franka_pose_rPe_5.yaml and from data-eye-in-hand/franka_pose_cPo_5.yaml
Use data from data-eye-in-hand//data-eye-in-hand/franka_pose_rPe_6.yaml and from data-eye-in-hand/franka_pose_cPo_6.yaml
Use data from data-eye-in-hand//data-eye-in-hand/franka_pose_rPe_7.yaml and from data-eye-in-hand/franka_pose_cPo_7.yaml
Use data from data-eye-in-hand//data-eye-in-hand/franka_pose_rPe_8.yaml and from data-eye-in-hand/franka_pose_cPo_8.yaml
Distance theta between rMo/rMc(0) and mean (deg) = 0.525425
Distance theta between rMo/rMc(1) and mean (deg) = 0.285817
Distance theta between rMo/rMc(2) and mean (deg) = 0.300987
Distance theta between rMo/rMc(3) and mean (deg) = 0.285246
Distance theta between rMo/rMc(4) and mean (deg) = 0.637412
Distance theta between rMo/rMc(5) and mean (deg) = 0.46788
Distance theta between rMo/rMc(6) and mean (deg) = 0.475263
Distance theta between rMo/rMc(7) and mean (deg) = 0.531161
Mean residual rMo/rMc(8) - rotation (deg) = 0.455924
Distance d between rMo/rMc(0) and mean (m) = 0.00394385
Distance d between rMo/rMc(1) and mean (m) = 0.00509806
Distance d between rMo/rMc(2) and mean (m) = 0.00459942
Distance d between rMo/rMc(3) and mean (m) = 0.00322695
Distance d between rMo/rMc(4) and mean (m) = 0.00656708
Distance d between rMo/rMc(5) and mean (m) = 0.00604678
Distance d between rMo/rMc(6) and mean (m) = 0.00643622
Distance d between rMo/rMc(7) and mean (m) = 0.00633335
Mean residual rMo/rMc(8) - translation (m) = 0.00541224
Mean residual rMo/rMc(8) - global = 0.00680486
Eye-in-hand calibration succeed
Estimated eMc transformation:
-----------------------------
eMc[4,4]=
-0.0110121 -0.999915 0.0069391 0.0577152
0.999929 -0.0109794 0.00473584 -0.0339249
-0.00465925 0.00699075 0.999965 -0.0422769
0.0 0.0 0.0 1.0
- Corresponding pose vector [tx ty tz tux tuy tuz] in [m] and [rad]: 0.05771519632 -0.03392488515 -0.04227690244 0.001783530191 0.009173747947 1.581782359
- Translation [m]: 0.05771519632 -0.03392488515 -0.04227690244
- Rotation (theta-u representation) [rad]: 0.001783530191 0.009173747947 1.581782359
- Rotation (theta-u representation) [deg]: 0.1021887526 0.5256170397 90.62945329
- Rotation (quaternion representation) [rad]: 0.0008016589017 0.004123404662 0.7109775407 0.7032021697
- Rotation (r-x-y-z representation) [rad]: -0.004735971381 0.006939152848 1.581808946
- Rotation (r-x-y-z representation) [deg]: -0.271351172 0.3975841716 90.63097662
Estimated rMo transformation:
-----------------------------
rMo[4,4]=
0.00556214 -0.999952 0.00811517 0.536486
-0.999928 -0.00564766 -0.0105542 0.123946
0.0105996 -0.00805588 -0.999911 0.0915574
0.0 0.0 0.0 1.0
- Corresponding pose vector [tx ty tz tux tuy tuz] in [m] and [rad]: 0.5364858483 0.123945742 0.09155742609 2.22636085 -2.213916548 0.02071766945
- Translation [m]: 0.5364858483 0.123945742 0.09155742609
- Rotation (theta-u representation) [rad]: 2.22636085 -2.213916548 0.02071766945
- Rotation (theta-u representation) [deg]: 127.5610804 -126.8480744 1.187035021
- Rotation (quaternion representation) [rad]: 0.7090700194 -0.705106654 0.006598336598 0.0008808561157
- Rotation (r-x-y-z representation) [rad]: 3.131037871 0.008115259378 1.565233978
- Rotation (r-x-y-z representation) [deg]: -0.271351172 0.3975841716 90.63097662
Save transformation matrix eMc as an homogeneous matrix in: data-eye-in-hand/franka_ePc.txt
Save transformation matrix eMc as a vpPoseVector in : data-eye-in-hand/franka_ePc.yaml
Save transformation matrix rMo as an homogeneous matrix in: data-eye-in-hand/franka_rPo.txt
Save transformation matrix rMo as a vpPoseVector in : data-eye-in-hand/franka_rPo.yaml
The extrinsic transformation
is saved in franka_ePc.yaml file as a vpPoseVector, with translation in meter and rotation as a
axis-angle vector with values in radians.
Additionally we also save the estimated
transformation in franka_rPo.yaml file.
$ more data-eye-in-hand/franka_ePc.yaml
rows: 6
cols: 1
data:
- [0.0577148]
- [-0.0339261]
- [-0.0422745]
- [0.00178253]
- [0.00917657]
- [1.58178]
The extrinsic transformation is also saved in franka_ePc.txt file that contains the corresponding homogeneous matrix transformation:
$ more data-eye-in-hand/franka_ePc.txt
-0.01100860563 -0.9999153181 0.006940255266 0.05771480338
0.9999285371 -0.01097586361 0.004738265792 -0.03392606387
-0.004661689251 0.006991920994 0.9999646902 -0.04227445451
0 0 0 1
- Note
- Looking at the results, we can see the residual values:
Mean residual rMo(8) - rotation (deg) = 0.456014
Mean residual rMo(8) - translation (m) = 0.00541225
Mean residual rMo(8) - global = 0.00680578
{} It shows that we have an error of 0.45 degrees for rotation and 5.41 millimeters for translation. If, instead of using the factory intrinsic parameters, we had used the estimated parameters including distorsion, the residual would have been smaller and would have enabled us to obtain a more accurate eye-in-hand calibration.
3.4. Camera poses analysis tool
Since ViSP 3.3.1 we provide hand_eye_calibration_show_extrinsics.py python script that allows to display camera poses used to acquire data. Prior to use that script, you need to install scipy and pyyaml:
$ sudo apt install python-pip
$ pip install scipy pyyaml matplotlib
To visualize camera poses:
$ grep px data-eye-in-hand/franka_camera.xml
<px>607.5931396484375</px>
$ python hand_eye_calibration_show_extrinsics.py \
--ndata 8 \
--eMc-yaml data-eye-in-hand/franka_ePc.yaml \
--cPo-file_pattern data-eye-in-hand/franka_pose_cPo_%d.yaml \
--square-size 0.0236 \
--focal-px 607.59
We recall, that a good hand-eye calibration is obtained when the camera poses are covering the surface of a half sphere over the grid.
4. Use cases
4.1. Panda robot + Realsense
In this section we suppose that you have a Panda robot from Franka Emika with a Realsense camera attached to its end-effector.
Panda robot in eye-in hand configuration with a RealSense D435 camera attached to its end-effector.
If not already done, follow 2.8. Configure Ethernet and 2.9. Connect to Franka desk instructions to power on the Panda robot. Then if this is not already done, follow 2.3. Install Franka library and 2.7. Configure and build ViSP.
If not already done, you need also to install 4.1.2. librealsense 2.x and build ViSP to enable vpRealSense2 class usage.
4.1.1 Acquire data
Connect the Realsense D435 camera to the computer, put the chessboard in the camera field of view, enter in apps/calibration/hand-eye folder and run visp-acquire-franka-calib-data binary to acquire the images and the corresponding robot end-effector positions:
$ cd apps/calibration/hand-eye
$ ./visp-acquire-franka-calib-data
By default the robot controller IP is 192.168.1.1. If your Franka has an other IP (let say 192.168.30.10) use "--ip" option like:
$ ./visp-acquire-franka-calib-data --ip 192.168.30.10 --output-folder data-franka
Click with the left mouse button to acquire data. It records the following outputs in data-franka folder:
- franka_camera.xml: XML file that contains the intrinsic camera parameters extracted from camera firmware
- couples of franka_image-<number>.png + franka_pose_rPe-<number>.txt with number starting from 1. franka_pose_rPe-<number>.yaml is the pose of the end-effector expressed in the robot reference frame
, while franka_image-<number>.png is the image captured at the corresponding robot position.
Move the robot to an other position such as the chessboard remains in the image and repeat data acquisition by a left mouse click. We recommend to acquire data at 8 to 10 different robot positions.
A right mouse click ends this step exiting the binary.
This is the output when 8 different positions are considered:
$ ./visp-acquire-franka-calib-data --ip 192.168.30.10 --output-folder data-franka
Image size: 640 x 480
Found camera with name: "Camera"
Save: data-franka/franka_image-1.png and data-franka/franka_pose_rPe_1.yaml
Save: data-franka/franka_image-2.png and data-franka/franka_pose_rPe_2.yaml
Save: data-franka/franka_image-3.png and data-franka/franka_pose_rPe_3.yaml
Save: data-franka/franka_image-4.png and data-franka/franka_pose_rPe_4.yaml
Save: data-franka/franka_image-5.png and data-franka/franka_pose_rPe_5.yaml
Save: data-franka/franka_image-6.png and data-franka/franka_pose_rPe_6.yaml
Save: data-franka/franka_image-7.png and data-franka/franka_pose_rPe_7.yaml
Save: data-franka/franka_image-8.png and data-franka/franka_pose_rPe_8.yaml
The source code corresponding to the binary is available in visp-acquire-franka-calib-data.cpp. If your setup is different, it could be easily adapted to your robot or camera.
4.1.2 Compute chessboard poses
Given the camera intrinsic parameters and the set of images, you can compute the chessboard pose running (adapt the square size parameter to your use case):
$ ./visp-compute-chessboard-poses \
--square-size 0.0262 \
--input data-franka/franka_image-%d.png \
--intrinsic data-franka/franka_camera.xml \
--output data-franka/franka_pose_cPo_%d.yaml
4.1.3 Estimate extrinsic transformation
Finally you can estimate the extrinsic transformation between end-effector and your camera, running:
$ ./visp-compute-eye-in-hand-calibration \
--data-path data-franka/ \
--rPe franka_pose_rPe_%d.yaml \
--cPo franka_pose_cPo_%d.yaml \
--output-ePc data-franka/franka_ePc.yaml \
--output-rPo data-franka/franka_rPo.yaml
It will produce the franka_ePc.yaml file that contains the pose as a vpPoseVector and franka_ePc.txt that contains the corresponding homogeneous matrix transformation:
$ more data-franka/franka_ePc.yaml
rows: 6
cols: 1
data:
- [-0.0351726]
- [-0.0591187]
- [0.015876]
- [-0.00265638]
- [0.00565946]
- [0.0166116]
$ more data-franka/franka_ePc.txt
0.9998460169 -0.01661822717 0.005637104144 -0.03517264821
0.0166031939 0.9998585032 0.002703241732 -0.05911865752
-0.005681229597 -0.002609231545 0.9999804576 0.0158759732
0 0 0 1
4.1.4. Camera poses analysis tool
To visualize camera poses:
$ grep px franka_camera.xml
<px>605.146728515625</px>
$ python hand_eye_calibration_show_extrinsics.py \
--ndata 8 \
--eMc-yaml data-franka/franka_ePc.yaml \
--cPo-file-pattern data-franka/franka_pose_cPo_%d.yaml \
--square-size 0.0262 \
--focal-px 605.146728515625
4.2. UR robot + Realsense
In this section we suppose that you have an Universal Robots robot with a Realsense camera attached to its end-effector.
UR5 robot with a RealSense D435 camera attached to its end-effector.
- Note
- In Tutorial: IBVS with a robot from Universal Robots we provide the link to the FreeCAD camera support model that could be 3D printed.
If not already done, follow Universal Robots visual-sevoing Prerequisites instructions to install ur_rtde 3rdparty and build ViSP to support UR that enables vpRobotUniversalRobots class usage.
If not already done, you need also to install 4.1.2. librealsense 2.x and build ViSP to enable vpRealSense2 class usage.
4.2.1 Acquire data
Connect the Realsense camera to the computer, put the chessboard in the camera field of view, enter in apps/calibration/hand-eye folder and run visp-acquire-universal-robots-calib-data binary to acquire the images and the corresponding robot end-effector positions:
$ cd apps/calibration/hand-eye
$ ./visp-acquire-universal-robots-calib-data
By default the robot controller IP is 192.168.0.100. If your robot from Universal Robots has an other IP (let say 192.168.30.10) use --ip option like:
$ ./visp-acquire-universal-robots-calib-data --ip 192.168.30.10 --output-folder data-ur
Click with the left mouse button to acquire data. It records the following outputs in data-ur folder:
- ur_camera.xml : XML file that contains the intrinsic camera parameters extracted from camera firmware
- couples of ur_image-<number>.png + ur_pose_rPe-<number>.txt with number starting from 1. ur_pose_rPe-<number>.yaml is the pose of the end-effector expressed in the robot reference frame
, while ur_image-<number>.png is the image captured at the corresponding robot position.
With the PolyScope, move the robot to an other position such as the chessboard remains in the image and repeat data acquisition by a left mouse click. We recommend to acquire data at 8 to 10 different robot positions.
A right mouse click ends this step exiting the binary.
This is the output when 8 different positions are considered:
$ ./visp-acquire-universal-robots-calib-data --ip 192.168.30.10 --output-folder data-ur
Image size: 640 x 480
Found camera with name: "Camera"
Save: data-ur/ur_image-1.png and data-ur/ur_pose_rPe_1.yaml
Save: data-ur/ur_image-2.png and data-ur/ur_pose_rPe_2.yaml
Save: data-ur/ur_image-3.png and data-ur/ur_pose_rPe_3.yaml
Save: data-ur/ur_image-4.png and data-ur/ur_pose_rPe_4.yaml
Save: data-ur/ur_image-5.png and data-ur/ur_pose_rPe_5.yaml
Save: data-ur/ur_image-6.png and data-ur/ur_pose_rPe_6.yaml
Save: data-ur/ur_image-7.png and data-ur/ur_pose_rPe_7.yaml
Save: data-ur/ur_image-8.png and data-ur/ur_pose_rPe_8.yaml
The source code corresponding to the binary is available in visp-acquire-universal-robots-calib-data.cpp. If your setup is different, it could be easily adapted to your robot or camera.
4.2.2 Compute chessboard poses
Given the camera intrinsic parameters and the set of images, you can compute the camera pose running:
$ ./visp-compute-chessboard-poses \
--square-size 0.0262 \
--input data-ur/ur_image-%d.png \
--intrinsic data-ur/ur_camera.xml \
--output data-ur/ur_pose_cPo_%d.yaml
4.2.3: Estimate extrinsic transformation
Finally you can estimate the extrinsic transformation between end-effector and you camera, running:
$ ./visp-compute-eye-in-hand-calibration \
--data-path data-ur/ \
--rPe ur_pose_rPe_%d.yaml \
--cPo ur_pose_cPo_%d.yaml \
--output-ePc data-ur/ur_ePc.yaml \
--output-rPo data-ur/ur_rPo.yaml
It will produce the ur_ePc.yaml that contains the pose as a vpPoseVector and ur_ePc.txt that contains the corresponding homogeneous matrix transformation:
$ more data-ur/ur_ePc.yaml
rows: 6
cols: 1
data:
- [-0.0351726]
- [-0.0591187]
- [0.015876]
- [-0.00265638]
- [0.00565946]
- [0.0166116]
$ more data-ur/ur_ePc.txt
0.9998460169 -0.01661822717 0.005637104144 -0.03517264821
0.0166031939 0.9998585032 0.002703241732 -0.05911865752
-0.005681229597 -0.002609231545 0.9999804576 0.0158759732
0 0 0 1
4.2.4. Cameta poses analysis tool
To visualize camera poses:
$ grep px ur_camera.xml
<px>605.146728515625</px>
$ python hand_eye_calibration_show_extrinsics.py \
--ndata 8 \
--eMc-yaml data-ur/ur_ePc.yaml \
--cPo-file-pattern data-ur/ur_pose_cPo_%d.yaml \
--square-size 0.0262 \
--focal-px 605.146728515625
5. Next tutorial
You are now ready to try a visual servoing control law:
You may also be interested in this other Tutorial: Camera eye-to-hand extrinsic calibration.