[][src]Function opencv::calib3d::calibrate_hand_eye

pub fn calibrate_hand_eye(
    r_gripper2base: &dyn ToInputArray,
    t_gripper2base: &dyn ToInputArray,
    r_target2cam: &dyn ToInputArray,
    t_target2cam: &dyn ToInputArray,
    r_cam2gripper: &mut dyn ToOutputArray,
    t_cam2gripper: &mut dyn ToOutputArray,
    method: HandEyeCalibrationMethod
) -> Result<()>

Computes Hand-Eye calibration: inline formula

Parameters

  • R_gripper2base: Rotation part extracted from the homogeneous matrix that transforms a point expressed in the gripper frame to the robot base frame (inline formula). This is a vector (vector<Mat>) that contains the rotation matrices for all the transformations from gripper frame to robot base frame.
  • t_gripper2base: Translation part extracted from the homogeneous matrix that transforms a point expressed in the gripper frame to the robot base frame (inline formula). This is a vector (vector<Mat>) that contains the translation vectors for all the transformations from gripper frame to robot base frame.
  • R_target2cam: Rotation part extracted from the homogeneous matrix that transforms a point expressed in the target frame to the camera frame (inline formula). This is a vector (vector<Mat>) that contains the rotation matrices for all the transformations from calibration target frame to camera frame.
  • t_target2cam: Rotation part extracted from the homogeneous matrix that transforms a point expressed in the target frame to the camera frame (inline formula). This is a vector (vector<Mat>) that contains the translation vectors for all the transformations from calibration target frame to camera frame.
  • R_cam2gripper: [out] Estimated rotation part extracted from the homogeneous matrix that transforms a point expressed in the camera frame to the gripper frame (inline formula).
  • t_cam2gripper: [out] Estimated translation part extracted from the homogeneous matrix that transforms a point expressed in the camera frame to the gripper frame (inline formula).
  • method: One of the implemented Hand-Eye calibration method, see cv::HandEyeCalibrationMethod

The function performs the Hand-Eye calibration using various methods. One approach consists in estimating the rotation then the translation (separable solutions) and the following methods are implemented:

  • R. Tsai, R. Lenz A New Technique for Fully Autonomous and Efficient 3D Robotics Hand/EyeCalibration \cite Tsai89
  • F. Park, B. Martin Robot Sensor Calibration: Solving AX = XB on the Euclidean Group \cite Park94
  • R. Horaud, F. Dornaika Hand-Eye Calibration \cite Horaud95

Another approach consists in estimating simultaneously the rotation and the translation (simultaneous solutions), with the following implemented method:

  • N. Andreff, R. Horaud, B. Espiau On-line Hand-Eye Calibration \cite Andreff99
  • K. Daniilidis Hand-Eye Calibration Using Dual Quaternions \cite Daniilidis98

The following picture describes the Hand-Eye calibration problem where the transformation between a camera ("eye") mounted on a robot gripper ("hand") has to be estimated.

The calibration procedure is the following:

  • a static calibration pattern is used to estimate the transformation between the target frame and the camera frame
  • the robot gripper is moved in order to acquire several poses
  • for each pose, the homogeneous transformation between the gripper frame and the robot base frame is recorded using for instance the robot kinematics block formula
  • for each pose, the homogeneous transformation between the calibration target frame and the camera frame is recorded using for instance a pose estimation method (PnP) from 2D-3D point correspondences block formula

The Hand-Eye calibration procedure returns the following homogeneous transformation block formula

This problem is also known as solving the inline formula equation: block formula

\note Additional information can be found on this website. \note A minimum of 2 motions with non parallel rotation axes are necessary to determine the hand-eye transformation. So at least 3 different poses are required, but it is strongly recommended to use many more poses.

C++ default parameters

  • method: CALIB_HAND_EYE_TSAI