Example of hand-eye calibration to estimate extrinsic camera parameters, ie hand-eye homogeneous transformation corresponding to the transformation between the robot end-effector and the camera.
#include <iomanip>
#include <sstream>
#include <stdio.h>
#include <vector>
#include <visp3/core/vpConfig.h>
#include <visp3/core/vpDebug.h>
#include <visp3/core/vpExponentialMap.h>
#include <visp3/core/vpIoTools.h>
#include <visp3/io/vpParseArgv.h>
#include <visp3/vision/vpHandEyeCalibration.h>
int main()
{
#if (defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_EIGEN3) || defined(VISP_HAVE_OPENCV))
#if defined(ENABLE_VISP_NAMESPACE)
#endif
try {
const unsigned int N = 6;
std::vector<vpHomogeneousMatrix> cMo(N);
std::vector<vpHomogeneousMatrix> wMe(N);
std::cout << "Simulated hand-eye transformation: eMc " << std::endl;
std::cout << eMc << std::endl;
<< std::endl;
for (unsigned int i = 0; i < N; i++) {
v_c = 0;
if (i == 0) {
cMo[0].buildFrom(0, 0, 0.5, 0, 0, 0);
wMe[0].buildFrom(0, 0, 0, 0, 0, 0);
}
else if (i == 1)
v_c[3] = M_PI / 8;
else if (i == 2)
v_c[4] = M_PI / 8;
else if (i == 3)
v_c[5] = M_PI / 10;
else if (i == 4)
v_c[0] = 0.5;
else if (i == 5)
v_c[1] = 0.8;
if (i > 0) {
cMo[i] = cMc.
inverse() * cMo[i - 1];
wMe[i] = wMe[i - 1] * eMc * cMc * eMc.
inverse();
}
}
if (1) {
for (unsigned int i = 0; i < N; i++) {
wMo = wMe[i] * eMc * cMo[i];
std::cout << std::endl << "wMo[" << i << "] " << std::endl;
std::cout << wMo << std::endl;
std::cout << "cMo[" << i << "] " << std::endl;
std::cout << cMo[i] << std::endl;
std::cout << "wMe[" << i << "] " << std::endl;
std::cout << wMe[i] << std::endl;
}
}
if (ret == 0) {
std::cout << std::endl << "** Hand-eye calibration succeed" << std::endl;
std::cout << std::endl << "** Hand-eye (eMc) transformation estimated:" << std::endl;
std::cout << eMc << std::endl;
std::cout <<
"** Corresponding pose vector: " <<
vpPoseVector(eMc).
t() << std::endl;
std::cout << std::endl
<< "** Translation [m]: " << eMc[0][3] << " " << eMc[1][3] << " " << eMc[2][3] << std::endl;
std::cout <<
"** Rotation (theta-u representation) [rad]: " << erc.
t() << std::endl;
std::cout <<
"** Rotation (theta-u representation) [deg]: " <<
vpMath::deg(erc[0]) <<
" " <<
vpMath::deg(erc[1])
std::cout <<
"** Rotation (quaternion representation) [rad]: " << quaternion.
t() << std::endl;
}
else {
std::cout << std::endl << "** Hand-eye calibration failed" << std::endl;
std::cout << std::endl
<< "Check your input data and ensure they are covering the half sphere over the chessboard."
<< std::endl;
std::cout << std::endl
<< "See https://visp-doc.inria.fr/doxygen/visp-daily/tutorial-calibration-extrinsic.html" << std::endl;
}
return EXIT_SUCCESS;
}
std::cout << "Catch an exception: " << e << std::endl;
return EXIT_FAILURE;
}
#else
std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl;
return EXIT_SUCCESS;
#endif
}
Implementation of column vector and the associated operations.
error that can be emitted by ViSP classes.
static vpHomogeneousMatrix direct(const vpColVector &v)
static int calibrate(const std::vector< vpHomogeneousMatrix > &cMo, const std::vector< vpHomogeneousMatrix > &rMe, vpHomogeneousMatrix &eMc)
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpRotationMatrix getRotationMatrix() const
vpHomogeneousMatrix & buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpHomogeneousMatrix inverse() const
void extract(vpRotationMatrix &R) const
static double rad(double deg)
static double deg(double rad)
Implementation of a pose vector and operations on poses.
Implementation of a rotation vector as quaternion angle minimal representation.
Implementation of a rotation vector as axis-angle minimal representation.
Class that consider the case of a translation vector.