Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
vpHandEyeCalibration Class Reference

#include <vpHandEyeCalibration.h>

Static Public Member Functions

static int calibrate (const std::vector< vpHomogeneousMatrix > &cMo, const std::vector< vpHomogeneousMatrix > &rMe, vpHomogeneousMatrix &eMc, vpHomogeneousMatrix &rMo)
static int calibrate (const std::vector< vpHomogeneousMatrix > &cMo, const std::vector< vpHomogeneousMatrix > &rMe, vpHomogeneousMatrix &eMc)

Detailed Description

Tool for hand-eye calibration. This class is able to consider eye-in-hand and eye-to-hand configurations.

Let us consider:

  • $^r{\bf M}_e$ the homogeneous transformation between the robot reference frame and the robot end-effector,
  • $^c{\bf M}_o$ the homogeneous transformation between the camera frame and an object frame attached to the robot end-effector,
  • $^r{\bf M}_c$ the homogeneous transformation between the robot reference frame and the camera frame,
  • $^e{\bf M}_o$ the homogeneous transformation between the robot end-effector frame and the object frame attached to the end-effector.

The hand-eye calibration process implemented in this class allows from the basket of $\{^r{\bf M}_e, ^c{\bf M}_o\}_i$ corresponding to couple of poses $ i $ to estimate:

Definition at line 73 of file vpHandEyeCalibration.h.

Member Function Documentation

◆ calibrate() [1/2]

int vpHandEyeCalibration::calibrate ( const std::vector< vpHomogeneousMatrix > & cMo,
const std::vector< vpHomogeneousMatrix > & rMe,
vpHomogeneousMatrix & eMc )
static

Perform hand-eye calibration:

  • For the eye-in hand configuration, compute the constant transformations from the end effector to the camera frames (eMc), and from the robot reference to the object frames (rMo).
  • For the eye-to hand configuration, compute the constant transformations from the end effector to the object frames (eMo), and from the robot reference to the camera frames (rMo).
Parameters
[in]cMo: Vector of homogeneous matrices representing the transformation between the camera and the object for the eye-in-hand configuration and the inverse transformation for the eye-to-hand configuration (oMc).
[in]rMe: Vector of homogeneous matrices representing the corresponding transformation between the end effector and robot reference frame. Must be the same size as cMo.
[out]eMc: Homogeneous matrix representing the transformation between the effector and the camera in the eye-in-hand configuration and between the effector and the object in the eye-to-hand configuration.
Returns
0 if calibration succeed, -1 if the system is not full rank, 1 if the algorithm doesn't converge.

Definition at line 851 of file vpHandEyeCalibration.cpp.

References calibrate(), and vpHomogeneousMatrix::eye().

◆ calibrate() [2/2]

int vpHandEyeCalibration::calibrate ( const std::vector< vpHomogeneousMatrix > & cMo,
const std::vector< vpHomogeneousMatrix > & rMe,
vpHomogeneousMatrix & eMc,
vpHomogeneousMatrix & rMo )
static

Perform hand-eye calibration:

  • For the eye-in hand configuration, compute the constant transformations from the end effector to the camera frames (eMc), and from the robot reference to the object frames (rMo).
  • For the eye-to hand configuration, compute the constant transformations from the end effector to the object frames (eMo), and from the robot reference to the camera frames (rMo).
Parameters
[in]cMo: Vector of homogeneous matrices representing the transformation between the camera and the object for the eye-in-hand configuration and the inverse transformation for the eye-to-hand configuration (oMc).
[in]rMe: Vector of homogeneous matrices representing the corresponding transformation between the end effector and robot reference frame. Must be the same size as cMo.
[out]eMc: Homogeneous matrix representing the transformation between the effector and the camera in the eye-in-hand configuration and between the effector and the object in the eye-to-hand configuration.
[out]rMo: Homogeneous matrix representing the transformation between the robot reference and the object in the eye-in-hand configuration and between the robot reference and the camera in the eye-to-hand configuration.
Returns
0 if calibration succeed, -1 if the system is not full rank, 1 if the algorithm doesn't converge.
Examples
catchCalibHandEye.cpp, visp-compute-eye-in-hand-calibration.cpp, and visp-compute-eye-to-hand-calibration.cpp.

Definition at line 871 of file vpHandEyeCalibration.cpp.

References vpMath::deg(), vpException::dimensionError, vpHomogeneousMatrix::eye(), and vpHomogeneousMatrix::insert().

Referenced by calibrate().