![]() |
Visual Servoing Platform version 3.7.0
|
#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) |
Tool for hand-eye calibration. This class is able to consider eye-in-hand and eye-to-hand configurations.
Let us consider:
The hand-eye calibration process implemented in this class allows from the basket of
corresponding to couple of poses
to estimate:
Definition at line 73 of file vpHandEyeCalibration.h.
|
static |
Perform hand-eye calibration:
| [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. |
Definition at line 851 of file vpHandEyeCalibration.cpp.
References calibrate(), and vpHomogeneousMatrix::eye().
|
static |
Perform hand-eye calibration:
| [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. |
Definition at line 871 of file vpHandEyeCalibration.cpp.
References vpMath::deg(), vpException::dimensionError, vpHomogeneousMatrix::eye(), and vpHomogeneousMatrix::insert().
Referenced by calibrate().