[][src]Function opencv::calib3d::calibrate_robot_world_hand_eye

pub fn calibrate_robot_world_hand_eye(
    r_world2cam: &dyn ToInputArray,
    t_world2cam: &dyn ToInputArray,
    r_base2gripper: &dyn ToInputArray,
    t_base2gripper: &dyn ToInputArray,
    r_base2world: &mut dyn ToOutputArray,
    t_base2world: &mut dyn ToOutputArray,
    r_gripper2cam: &mut dyn ToOutputArray,
    t_gripper2cam: &mut dyn ToOutputArray,
    method: RobotWorldHandEyeCalibrationMethod
) -> Result<()>

Computes Robot-World/Hand-Eye calibration: inline formula and inline formula

Parameters

  • R_world2cam: Rotation part extracted from the homogeneous matrix that transforms a point expressed in the world frame to the camera frame (inline formula). This is a vector (vector<Mat>) that contains the rotation, (3x3) rotation matrices or (3x1) rotation vectors, for all the transformations from world frame to the camera frame.
  • t_world2cam: Translation part extracted from the homogeneous matrix that transforms a point expressed in the world frame to the camera frame (inline formula). This is a vector (vector<Mat>) that contains the (3x1) translation vectors for all the transformations from world frame to the camera frame.
  • R_base2gripper: Rotation part extracted from the homogeneous matrix that transforms a point expressed in the robot base frame to the gripper frame (inline formula). This is a vector (vector<Mat>) that contains the rotation, (3x3) rotation matrices or (3x1) rotation vectors, for all the transformations from robot base frame to the gripper frame.
  • t_base2gripper: Rotation part extracted from the homogeneous matrix that transforms a point expressed in the robot base frame to the gripper frame (inline formula). This is a vector (vector<Mat>) that contains the (3x1) translation vectors for all the transformations from robot base frame to the gripper frame.
  • R_base2world:[out] Estimated (3x3) rotation part extracted from the homogeneous matrix that transforms a point expressed in the robot base frame to the world frame (inline formula).
  • t_base2world:[out] Estimated (3x1) translation part extracted from the homogeneous matrix that transforms a point expressed in the robot base frame to the world frame (inline formula).
  • R_gripper2cam:[out] Estimated (3x3) rotation part extracted from the homogeneous matrix that transforms a point expressed in the gripper frame to the camera frame (inline formula).
  • t_gripper2cam:[out] Estimated (3x1) translation part extracted from the homogeneous matrix that transforms a point expressed in the gripper frame to the camera frame (inline formula).
  • method: One of the implemented Robot-World/Hand-Eye calibration method, see cv::RobotWorldHandEyeCalibrationMethod

The function performs the Robot-World/Hand-Eye calibration using various methods. One approach consists in estimating the rotation then the translation (separable solutions):

  • M. Shah, Solving the robot-world/hand-eye calibration problem using the kronecker product \cite Shah2013SolvingTR

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

  • A. Li, L. Wang, and D. Wu, Simultaneous robot-world and hand-eye calibration using dual-quaternions and kronecker product \cite Li2010SimultaneousRA

The following picture describes the Robot-World/Hand-Eye calibration problem where the transformations between a robot and a world frame and between a robot gripper ("hand") and a camera ("eye") mounted at the robot end-effector have 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 (the world frame) and the camera frame is recorded using for instance a pose estimation method (PnP) from 2D-3D point correspondences block formula

The Robot-World/Hand-Eye calibration procedure returns the following homogeneous transformations block formula block formula

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

  • inline formula
  • inline formula
  • inline formula
  • inline formula

\note At least 3 measurements are required (input vectors size must be greater or equal to 3).

C++ default parameters

  • method: CALIB_ROBOT_WORLD_HAND_EYE_SHAH