Visual Servoing Platform  version 3.2.0 under development (2019-01-22)
vpHandEyeCalibration Class Reference

#include <visp3/vision/vpHandEyeCalibration.h>

Static Public Member Functions

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

Detailed Description

Tool for hand-eye calibration.

Definition at line 63 of file vpHandEyeCalibration.h.

Member Function Documentation

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

Compute extrinsic camera parameters : the constant transformation from the effector to the camera frames (eMc).

Parameters
[in]cMo: vector of homogeneous matrices representing the transformation between the camera and the scene.
[in]rMe: vector of homogeneous matrices representing the transformation between the effector (where the camera is fixed) and the reference coordinates (base of the manipulator). Must be the same size as cMo.
[out]eMc: homogeneous matrix representing the transformation between the effector and the camera (output)
Returns
0 if calibration succeed, -1 if the system is not full rank, 1 if the algorithm doesn't converge.
Examples:
calibrate-hand-eye.cpp, and tutorial-hand-eye-calibration.cpp.

Definition at line 837 of file vpHandEyeCalibration.cpp.

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

Referenced by vpCalibration::calibrationTsai(), and vpCalibration::computeCalibrationTsai().