Skip to content

Commit 417d7a3

Browse files
committed
Add Robot-World/Hand-Eye calibration function.
1 parent ba147d2 commit 417d7a3

File tree

5 files changed

+980
-310
lines changed

5 files changed

+980
-310
lines changed

doc/opencv.bib

Lines changed: 17 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -217,7 +217,7 @@ @article{Chaumette06
217217
hal_id = {inria-00350283},
218218
hal_version = {v1},
219219
}
220-
@article{Collins14
220+
@article{Collins14,
221221
year = {2014},
222222
issn = {0920-5691},
223223
journal = {International Journal of Computer Vision},
@@ -612,6 +612,14 @@ @article{Louhichi07
612612
number = {8},
613613
publisher = {IOP Publishing Ltd}
614614
}
615+
@article{Li2010SimultaneousRA,
616+
title = {Simultaneous robot-world and hand-eye calibration using dual-quaternions and Kronecker product},
617+
author = {Aiguo Li and Lin Wang and Defeng Wu},
618+
journal = {International Journal of Physical Sciences},
619+
year = {2010},
620+
volume = {5},
621+
pages = {1530-1536}
622+
}
615623
@article{LibSVM,
616624
author = {Chang, Chih-Chung and Lin, Chih-Jen},
617625
title = {LIBSVM: a library for support vector machines},
@@ -922,6 +930,14 @@ @article{SS00
922930
number = {2},
923931
publisher = {Springer}
924932
}
933+
@article{Shah2013SolvingTR,
934+
title = {Solving the Robot-World/Hand-Eye Calibration Problem Using the Kronecker Product},
935+
author = {Mili Shah},
936+
journal = {Journal of Mechanisms and Robotics},
937+
year = {2013},
938+
volume = {5},
939+
pages = {031007}
940+
}
925941
@inproceedings{Shi94,
926942
author = {Shi, Jianbo and Tomasi, Carlo},
927943
title = {Good features to track},
23.4 KB
Loading

modules/calib3d/include/opencv2/calib3d.hpp

Lines changed: 170 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -535,6 +535,12 @@ enum HandEyeCalibrationMethod
535535
CALIB_HAND_EYE_DANIILIDIS = 4 //!< Hand-Eye Calibration Using Dual Quaternions @cite Daniilidis98
536536
};
537537

538+
enum RobotWorldHandEyeCalibrationMethod
539+
{
540+
CALIB_ROBOT_WORLD_HAND_EYE_SHAH = 0, //!< Solving the robot-world/hand-eye calibration problem using the kronecker product @cite Shah2013SolvingTR
541+
CALIB_ROBOT_WORLD_HAND_EYE_LI = 1 //!< Simultaneous robot-world and hand-eye calibration using dual-quaternions and kronecker product @cite Li2010SimultaneousRA
542+
};
543+
538544
enum SamplingMethod { SAMPLING_UNIFORM, SAMPLING_PROGRESSIVE_NAPSAC, SAMPLING_NAPSAC,
539545
SAMPLING_PROSAC };
540546
enum LocalOptimMethod {LOCAL_OPTIM_NULL, LOCAL_OPTIM_INNER_LO, LOCAL_OPTIM_INNER_AND_ITER_LO,
@@ -2288,12 +2294,16 @@ rotation then the translation (separable solutions) and the following methods ar
22882294
- R. Horaud, F. Dornaika Hand-Eye Calibration \cite Horaud95
22892295
22902296
Another approach consists in estimating simultaneously the rotation and the translation (simultaneous solutions),
2291-
with the following implemented method:
2297+
with the following implemented methods:
22922298
- N. Andreff, R. Horaud, B. Espiau On-line Hand-Eye Calibration \cite Andreff99
22932299
- K. Daniilidis Hand-Eye Calibration Using Dual Quaternions \cite Daniilidis98
22942300
22952301
The following picture describes the Hand-Eye calibration problem where the transformation between a camera ("eye")
2296-
mounted on a robot gripper ("hand") has to be estimated.
2302+
mounted on a robot gripper ("hand") has to be estimated. This configuration is called eye-in-hand.
2303+
2304+
The eye-to-hand configuration consists in a static camera observing a calibration pattern mounted on the robot
2305+
end-effector. The transformation from the camera to the robot base frame can then be estimated by inputting
2306+
the suitable transformations to the function, see below.
22972307
22982308
![](pics/hand-eye_figure.png)
22992309
@@ -2366,6 +2376,7 @@ The Hand-Eye calibration procedure returns the following homogeneous transformat
23662376
\f]
23672377
23682378
This problem is also known as solving the \f$\mathbf{A}\mathbf{X}=\mathbf{X}\mathbf{B}\f$ equation:
2379+
- for an eye-in-hand configuration
23692380
\f[
23702381
\begin{align*}
23712382
^{b}{\textrm{T}_g}^{(1)} \hspace{0.2em} ^{g}\textrm{T}_c \hspace{0.2em} ^{c}{\textrm{T}_t}^{(1)} &=
@@ -2378,6 +2389,19 @@ This problem is also known as solving the \f$\mathbf{A}\mathbf{X}=\mathbf{X}\mat
23782389
\end{align*}
23792390
\f]
23802391
2392+
- for an eye-to-hand configuration
2393+
\f[
2394+
\begin{align*}
2395+
^{g}{\textrm{T}_b}^{(1)} \hspace{0.2em} ^{b}\textrm{T}_c \hspace{0.2em} ^{c}{\textrm{T}_t}^{(1)} &=
2396+
\hspace{0.1em} ^{g}{\textrm{T}_b}^{(2)} \hspace{0.2em} ^{b}\textrm{T}_c \hspace{0.2em} ^{c}{\textrm{T}_t}^{(2)} \\
2397+
2398+
(^{g}{\textrm{T}_b}^{(2)})^{-1} \hspace{0.2em} ^{g}{\textrm{T}_b}^{(1)} \hspace{0.2em} ^{b}\textrm{T}_c &=
2399+
\hspace{0.1em} ^{b}\textrm{T}_c \hspace{0.2em} ^{c}{\textrm{T}_t}^{(2)} (^{c}{\textrm{T}_t}^{(1)})^{-1} \\
2400+
2401+
\textrm{A}_i \textrm{X} &= \textrm{X} \textrm{B}_i \\
2402+
\end{align*}
2403+
\f]
2404+
23812405
\note
23822406
Additional information can be found on this [website](http://campar.in.tum.de/Chair/HandEyeCalibration).
23832407
\note
@@ -2390,6 +2414,150 @@ CV_EXPORTS_W void calibrateHandEye( InputArrayOfArrays R_gripper2base, InputArra
23902414
OutputArray R_cam2gripper, OutputArray t_cam2gripper,
23912415
HandEyeCalibrationMethod method=CALIB_HAND_EYE_TSAI );
23922416

2417+
/** @brief Computes Robot-World/Hand-Eye calibration: \f$_{}^{w}\textrm{T}_b\f$ and \f$_{}^{c}\textrm{T}_g\f$
2418+
2419+
@param[in] R_world2cam Rotation part extracted from the homogeneous matrix that transforms a point
2420+
expressed in the world frame to the camera frame (\f$_{}^{c}\textrm{T}_w\f$).
2421+
This is a vector (`vector<Mat>`) that contains the rotation, `(3x3)` rotation matrices or `(3x1)` rotation vectors,
2422+
for all the transformations from world frame to the camera frame.
2423+
@param[in] t_world2cam Translation part extracted from the homogeneous matrix that transforms a point
2424+
expressed in the world frame to the camera frame (\f$_{}^{c}\textrm{T}_w\f$).
2425+
This is a vector (`vector<Mat>`) that contains the `(3x1)` translation vectors for all the transformations
2426+
from world frame to the camera frame.
2427+
@param[in] R_base2gripper Rotation part extracted from the homogeneous matrix that transforms a point
2428+
expressed in the robot base frame to the gripper frame (\f$_{}^{g}\textrm{T}_b\f$).
2429+
This is a vector (`vector<Mat>`) that contains the rotation, `(3x3)` rotation matrices or `(3x1)` rotation vectors,
2430+
for all the transformations from robot base frame to the gripper frame.
2431+
@param[in] t_base2gripper Rotation part extracted from the homogeneous matrix that transforms a point
2432+
expressed in the robot base frame to the gripper frame (\f$_{}^{g}\textrm{T}_b\f$).
2433+
This is a vector (`vector<Mat>`) that contains the `(3x1)` translation vectors for all the transformations
2434+
from robot base frame to the gripper frame.
2435+
@param[out] R_base2world Estimated `(3x3)` rotation part extracted from the homogeneous matrix that transforms a point
2436+
expressed in the robot base frame to the world frame (\f$_{}^{w}\textrm{T}_b\f$).
2437+
@param[out] t_base2world Estimated `(3x1)` translation part extracted from the homogeneous matrix that transforms a point
2438+
expressed in the robot base frame to the world frame (\f$_{}^{w}\textrm{T}_b\f$).
2439+
@param[out] R_gripper2cam Estimated `(3x3)` rotation part extracted from the homogeneous matrix that transforms a point
2440+
expressed in the gripper frame to the camera frame (\f$_{}^{c}\textrm{T}_g\f$).
2441+
@param[out] t_gripper2cam Estimated `(3x1)` translation part extracted from the homogeneous matrix that transforms a point
2442+
expressed in the gripper frame to the camera frame (\f$_{}^{c}\textrm{T}_g\f$).
2443+
@param[in] method One of the implemented Robot-World/Hand-Eye calibration method, see cv::RobotWorldHandEyeCalibrationMethod
2444+
2445+
The function performs the Robot-World/Hand-Eye calibration using various methods. One approach consists in estimating the
2446+
rotation then the translation (separable solutions):
2447+
- M. Shah, Solving the robot-world/hand-eye calibration problem using the kronecker product \cite Shah2013SolvingTR
2448+
2449+
Another approach consists in estimating simultaneously the rotation and the translation (simultaneous solutions),
2450+
with the following implemented method:
2451+
- A. Li, L. Wang, and D. Wu, Simultaneous robot-world and hand-eye calibration using dual-quaternions and kronecker product \cite Li2010SimultaneousRA
2452+
2453+
The following picture describes the Robot-World/Hand-Eye calibration problem where the transformations between a robot and a world frame
2454+
and between a robot gripper ("hand") and a camera ("eye") mounted at the robot end-effector have to be estimated.
2455+
2456+
![](pics/robot-world_hand-eye_figure.png)
2457+
2458+
The calibration procedure is the following:
2459+
- a static calibration pattern is used to estimate the transformation between the target frame
2460+
and the camera frame
2461+
- the robot gripper is moved in order to acquire several poses
2462+
- for each pose, the homogeneous transformation between the gripper frame and the robot base frame is recorded using for
2463+
instance the robot kinematics
2464+
\f[
2465+
\begin{bmatrix}
2466+
X_g\\
2467+
Y_g\\
2468+
Z_g\\
2469+
1
2470+
\end{bmatrix}
2471+
=
2472+
\begin{bmatrix}
2473+
_{}^{g}\textrm{R}_b & _{}^{g}\textrm{t}_b \\
2474+
0_{1 \times 3} & 1
2475+
\end{bmatrix}
2476+
\begin{bmatrix}
2477+
X_b\\
2478+
Y_b\\
2479+
Z_b\\
2480+
1
2481+
\end{bmatrix}
2482+
\f]
2483+
- for each pose, the homogeneous transformation between the calibration target frame (the world frame) and the camera frame is recorded using
2484+
for instance a pose estimation method (PnP) from 2D-3D point correspondences
2485+
\f[
2486+
\begin{bmatrix}
2487+
X_c\\
2488+
Y_c\\
2489+
Z_c\\
2490+
1
2491+
\end{bmatrix}
2492+
=
2493+
\begin{bmatrix}
2494+
_{}^{c}\textrm{R}_w & _{}^{c}\textrm{t}_w \\
2495+
0_{1 \times 3} & 1
2496+
\end{bmatrix}
2497+
\begin{bmatrix}
2498+
X_w\\
2499+
Y_w\\
2500+
Z_w\\
2501+
1
2502+
\end{bmatrix}
2503+
\f]
2504+
2505+
The Robot-World/Hand-Eye calibration procedure returns the following homogeneous transformations
2506+
\f[
2507+
\begin{bmatrix}
2508+
X_w\\
2509+
Y_w\\
2510+
Z_w\\
2511+
1
2512+
\end{bmatrix}
2513+
=
2514+
\begin{bmatrix}
2515+
_{}^{w}\textrm{R}_b & _{}^{w}\textrm{t}_b \\
2516+
0_{1 \times 3} & 1
2517+
\end{bmatrix}
2518+
\begin{bmatrix}
2519+
X_b\\
2520+
Y_b\\
2521+
Z_b\\
2522+
1
2523+
\end{bmatrix}
2524+
\f]
2525+
\f[
2526+
\begin{bmatrix}
2527+
X_c\\
2528+
Y_c\\
2529+
Z_c\\
2530+
1
2531+
\end{bmatrix}
2532+
=
2533+
\begin{bmatrix}
2534+
_{}^{c}\textrm{R}_g & _{}^{c}\textrm{t}_g \\
2535+
0_{1 \times 3} & 1
2536+
\end{bmatrix}
2537+
\begin{bmatrix}
2538+
X_g\\
2539+
Y_g\\
2540+
Z_g\\
2541+
1
2542+
\end{bmatrix}
2543+
\f]
2544+
2545+
This problem is also known as solving the \f$\mathbf{A}\mathbf{X}=\mathbf{Z}\mathbf{B}\f$ equation, with:
2546+
- \f$\mathbf{A} \Leftrightarrow \hspace{0.1em} _{}^{c}\textrm{T}_w\f$
2547+
- \f$\mathbf{X} \Leftrightarrow \hspace{0.1em} _{}^{w}\textrm{T}_b\f$
2548+
- \f$\mathbf{Z} \Leftrightarrow \hspace{0.1em} _{}^{c}\textrm{T}_g\f$
2549+
- \f$\mathbf{B} \Leftrightarrow \hspace{0.1em} _{}^{g}\textrm{T}_b\f$
2550+
2551+
\note
2552+
At least 3 measurements are required (input vectors size must be greater or equal to 3).
2553+
2554+
*/
2555+
CV_EXPORTS_W void calibrateRobotWorldHandEye( InputArrayOfArrays R_world2cam, InputArrayOfArrays t_world2cam,
2556+
InputArrayOfArrays R_base2gripper, InputArrayOfArrays t_base2gripper,
2557+
OutputArray R_base2world, OutputArray t_base2world,
2558+
OutputArray R_gripper2cam, OutputArray t_gripper2cam,
2559+
RobotWorldHandEyeCalibrationMethod method=CALIB_ROBOT_WORLD_HAND_EYE_SHAH );
2560+
23932561
/** @brief Converts points from Euclidean to homogeneous space.
23942562
23952563
@param src Input vector of N-dimensional points.

0 commit comments

Comments
 (0)