Visual Servoing Platform
version 3.2.0 under development (2019-01-22)
|
#include <visp3/vision/vpHandEyeCalibration.h>
Static Public Member Functions | |
static int | calibrate (const std::vector< vpHomogeneousMatrix > &cMo, const std::vector< vpHomogeneousMatrix > &rMe, vpHomogeneousMatrix &eMc) |
Tool for hand-eye calibration.
Definition at line 63 of file vpHandEyeCalibration.h.
|
static |
Compute extrinsic camera parameters : the constant transformation from the effector to the camera frames (eMc).
[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) |
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().