| 配置 | 相机位置 | 标定板位置 | 机器人 动作 |
|---|---|---|---|
| 眼在手外 (Eye-to-Hand) | 固定不动 | 在机器人末端,随之运动 | 带着标定板在相机视野内移动 |
| 眼在手上 (Eye-in-Hand) | 在机器人末端,随之运动 | 固定不动 (在桌面上) | 带着相机去观察标定板 |
眼在手外(Eye-to-Hand)标定数学原理:标定板是固定在机械臂末端
关键约束条件
在"眼在手外"的标定过程中,标定板固定在末端法兰:
相机:固定不动。
标定板:固定在机器人末端,随机器人运动。即$$\bf{T}_{end}^{board}$$是常数
\\bf{T}_{end}\^{board}$$是常数。因为标定板刚性安装在法兰上,它相对于末端的变换永远不变
眼在手外标定的本质是寻找一个固定的变换$$\bf{X}$$(即$$\bf{T}_{base }^{camera}$$,相机在机械臂基座坐标下的位姿):
\\bf{T}_{base}\^{board_i}=T_{base}\^{end_i} \\cdot T_{end_i}\^{board_i}=T_{base}\^{camera} \\cdot T_{camera}\^{board_i}
采样多个样本:
\\begin{bmatrix} \\bf{T}_{base}\^{board_1}=T_{base}\^{end_1} \\cdot T_{end_1}\^{board_1}=T_{base}\^{camera} \\cdot T_{camera}\^{board_1} \\\\\\\\ \\bf{T}_{base}\^{board_2}=T_{base}\^{end_2} \\cdot T_{end_2}\^{board_2}=T_{base}\^{camera} \\cdot T_{camera}\^{board_2} \\\\\\\\ \\bf{T}_{base}\^{board_2}=T_{base}\^{end_3} \\cdot T_{end_3}\^{board_3}=T_{base}\^{camera} \\cdot T_{camera}\^{board_3} \\\\\\\\ \\cdots \\end{bmatrix}
由于在标定过程中,标定板是固定在机械臂末端的,机械臂基座不动,相机固定不动
所以$$\bf{T}_{base}^{camera}$$是一个固定常量矩阵,也就是我们要求的标定矩阵
且$$\bf{T}{end_1}^{board_1} = T{end_2}^{board_2} = T_{end_3}^{board_3}$$也是一个固定常量矩阵
我们选取机器人运动的两个不同位姿(位姿1和位姿2):
\\begin{cases} \\bf{T}_{base}\^{board_1}=T_{base}\^{end_1} \\cdot T_{end_1}\^{board_1}=T_{base}\^{camera} \\cdot T_{camera}\^{board_1} \\\\\\\\ \\bf{T}_{base}\^{board_2}=T_{base}\^{end_2} \\cdot T_{end_2}\^{board_2}=T_{base}\^{camera} \\cdot T_{camera}\^{board_2} \\end{cases}
\\begin{cases} \\bf{T}_{end_1}\^{board_1}=\\left(T_{base}\^{end_1}\\right)\^{-1} \\cdot T_{base}\^{camera} \\cdot T_{camera}\^{board_1} \\\\\\\\ \\bf{T}_{end_2}\^{board_2}=\\left(T_{base}\^{end_2}\\right)\^{-1} \\cdot T_{base}\^{camera} \\cdot T_{camera}\^{board_2} \\end{cases}
由于$$\bf{T}{end_1}^{board_1} = T{end_2}^{board_2}$$,令$$\bf{T}_{base}^{camera}=\bf{X}$$:
\\left(\\bf{T}_{base}\^{end_1}\\right)\^{-1} \\cdot \\bf{X} \\cdot T_{camera}\^{board_1}=\\left(T_{base}\^{end_2}\\right)\^{-1} \\cdot \\bf{X} \\cdot T_{camera}\^{board_2}
\\bf{T}_{base}\^{end_2} \\cdot \\left(\\bf{T}_{base}\^{end_1}\\right)\^{-1} \\cdot \\bf{X} = \\bf{X} \\cdot T_{camera}\^{board_2} \\cdot \\left(T_{camera}\^{board_1}\\right)\^{-1}
形容$$\bf{A}\bf{X} = \bf{X} \bf{B}$$
\\begin{cases} \\bf{A}= \\bf{T}_{base}\^{end_2} \\cdot \\left(\\bf{T}_{base}\^{end_1}\\right)\^{-1} \\\\ \\bf{B}=T_{camera}\^{board_2} \\cdot \\left(T_{camera}\^{board_1}\\right)\^{-1} \\end{cases}
- 机械臂法兰末端运动( $$\bf{A}$$):
-
机械臂末端法兰从位姿1移动到位姿2,末端法兰相对于基座的变换变化量。
\\bf{A} = T_{base}\^{end_2} \\cdot \\left(T_{base}\^{end_1}\\right)\^{-1}
(这个数据可以直接从 机器人 控制器读取并计算)
- 相机的观测 ( $$\bf{B}$$):
-
标定板在相机眼中的相对运动
\\bf{B} = T_{camera}\^{board_2} \\cdot \\left(T_{camera}\^{board_1}\\right)\^{-1}
(这个数据通过相机拍摄标定板,利用 PnP 算法或视觉库计算得到)
- 建立方程:
\\underbrace{\\bf{T}_{base}\^{end_2} \\cdot \\left(\\bf{T}_{base}\^{end_1}\\right)\^{-1}}_{\\text{机械臂相对运动}} \\cdot \\underbrace{\\bf{T}_{base}\^{camera}}_{\\text{待求}} = \\underbrace{\\bf{T}_{base}\^{camera}}_{\\text{待求}} \\cdot \\underbrace{\\bf{T}_{camera}\^{board_2} \\cdot \\left(\\bf{T}_{camera}\^{board_1}\\right)\^{-1}}_{\\text{相机相对运动}}
具体计算步骤
要解出这个$$\bf{X}$$,不能只算一次,通常需要采集多组数据(例如 10-20 组)来消除噪声
第一步:数据采集
-
固定标定板:标定板刚性固定在机械臂末端法兰上(棋盘格或圆点板)
-
移动 机器人:控制机器人移动到$$$$个不同的位置和姿态
-
记录数据:
-
记录每一帧的机器人末端位姿 $$\bf{T}_{base}^{end}$$(从控制器读取)
-
拍摄图像,并计算每一帧标定板在相机坐标系下的位姿 $$\bf{T}_{camera}^{board}$$(使用 OpenCV 的
solvePnP或 Halcon 等视觉算法)
-
第二步:构建方程组
对于每一对相邻的运动(例如从第$$$$帧到第$$i+$$帧),构建一个$$\bf{A}_i X = X B_i$$方程
第三步:求解$$\bf{X}$$
这是一个经典的矩阵方程,通常使用最小二乘法求解
使用现成库:在实际工程中,你不需要手写 SVD 求解器,可以直接调用成熟的库
代码实现示例 (Python + OpenCV)
OpenCV 提供了 cv2.calibrateHandEye 函数,可以直接计算 $$\bf{T}_{end}^{camera}$$(在函数参数中对应 R_cam2gripper 和 t_cam2gripper,注意方向可能需要取逆,具体取决于你定义的 $$$$ 是哪个方向)。
import cv2 import numpy as np # 假设你已经采集了 N 组数据 # R_gripper2base_list: 机器人末端到基座的旋转矩阵列表 (R_be) # t_gripper2base_list: 机器人末端到基座的平移向量列表 (t_be) # R_target2cam_list: 标定板到相机的旋转矩阵列表 (R_tc) # t_target2cam_list: 标定板到相机的平移向量列表 (t_tc) # 1. 准备数据 (这里需要转成 OpenCV 要求的格式,通常是列表) # 注意:OpenCV 的函数通常求解的是 T_gripper_cam (即 T_end_camera) # 但输入参数需要仔细对应方向。 # 下方代码演示的是求解 T_cam2gripper (相机->末端),如果需要 T_end->cam 需取逆 R_cam2gripper, t_cam2gripper = cv2.calibrateHandEye( R_gripper2base_list, # 机器人:末端->基座 t_gripper2base_list, R_target2cam_list, # 视觉:标定板->相机 t_target2cam_list, method=cv2.CALIB_HAND_EYE_TSAI # 常用 Tsai 算法 ) # 2. 组合成齐次矩阵 T_cam2gripper T_cam2gripper = np.block([ [R_cam2gripper, t_cam2gripper.reshape(3, 1)], [np.zeros((1, 3)), np.array([[1]])] ]) # 3. 如果你需要的是 T_end_camera (即 T_gripper2cam),则求逆 T_end_camera = np.linalg.inv(T_cam2gripper) print("计算得到的 T_end_camera:") print(T_end_camera)
眼在手上(Eye-in-Hand)标定数学原理:标定板固定在桌面
关键约束条件
在"眼在手上"的标定过程中,标定板固定在外部环境中:
相机:固定在机器人末端,随机器人运动,所以$$\bf{T}_{end}^{camera}$$是一个固定常量矩阵
标定板:固定在外部环境(如工作台)中,静止不动,即$$\bf{T}_{base}^{board}$$是一个固定常量矩阵
\\bf{T}_{base}\^{board}$$是一个固定常量矩阵。因为标定板刚性固定在外部,它相对于基座的变换永远不变
眼在手上标定的本质是寻找一个固定的变换 $$\bf{X$$(即$$\bf{T}{end}^{camera}$$,相机在末端法兰坐标系下的位姿),使得无论机器人怎么动,标定板在基座坐标系下的位置始终保持一致,即$$\bf{T}{base}^{board_1}=\bf{T}{base}^{board_2}=\cdots=\bf{T}{base}^{board_i}$$
\\bf{T}_{base}\^{board_i} = T_{base}\^{end_i} \\cdot T_{end_i}\^{camera_i} \\cdot T_{camera_i}\^{board_i}
采样多个样本:
\\begin{cases} \\bf{T}_{base}\^{board_1}=T_{base}\^{end_1} \\cdot T_{end_1}\^{camera_1} \\cdot T_{camera_1}\^{board_1} \\\\\\\\ \\bf{T}_{base}\^{board_2}=T_{base}\^{end_2} \\cdot T_{end_2}\^{camera_2} \\cdot T_{camera_2}\^{board_2} \\\\\\\\ \\bf{T}_{base}\^{board_3}=T_{base}\^{end_3} \\cdot T_{end_3}\^{camera_3} \\cdot T_{camera_3}\^{board_3} \\\\ \\cdots \\end{cases}
由于在标定过程中标定板是固定在外部(如桌面)的,机械臂基座不动。 所以$$\bf{T}_{base}^{board}$$是一个固定常量矩阵
且$$\bf{T}_{end}^{camera}$$也是一个固定常量矩阵(相机安装在末端,相对位置不变,即我们要求的标定矩阵)
我们选取机器人运动的两个不同位姿(位姿1和位姿2):
\\begin{cases} \\bf{T}_{base}\^{board_1}=T_{base}\^{end_1} \\cdot T_{end_1}\^{camera_1} \\cdot T_{camera_1}\^{board_1} \\\\\\\\ \\bf{T}_{base}\^{board_2}=T_{base}\^{end_2} \\cdot T_{end_2}\^{camera_2} \\cdot T_{camera_2}\^{board_2} \\end{cases}
由于$$\bf{T}{base}^{board_1}=\bf{T}{base}^{board_2}$$,所以:
\\bf{T}_{base}\^{end_1} \\cdot T_{end_1}\^{camera_1} \\cdot T_{camera_1}\^{board_1} = T_{base}\^{end_2} \\cdot T_{end_2}\^{camera_2} \\cdot T_{camera_2}\^{board_2}
令$$\bf{T}{end_1}^{camera_1}=T{end_2}^{camera_2}=X$$:
\\underbrace{\\left(\\bf{T}_{base}\^{end_2}\\right)\^{-1} \\cdot \\bf{T}_{base}\^{end_1}}_{\\bf{A}} \\cdot \\mathbf{X} = \\mathbf{X} \\cdot \\underbrace{\\bf{T}_{camera_2}\^{board_2} \\cdot \\left(T_{camera_1}\^{board_1}\\right)\^{-1}}_{\\bf{B}}
这就构成了 $$\bf{A}\bf{X} = \bf{X} \bf{B$$ 的形式
-
机械臂相对运动 ( $$\bf{A$$):$$\bf{A} = (T_{base}^{end_2})^{-1} \cdot T_{base}^{end_1}$$ (从位姿2变到位姿1)
-
相机观测相对运动 ( $$\bf{B$$):$$\bf{B} = T_{camera_2}^{board_2} \cdot (T_{camera_1}^{board_1})^{-1}$$(从位姿1变到位姿2,注意顺序反转)
- 机械臂法兰末端运动 ( $$\bf{A$$):
机械臂末端法兰从位姿2移动到位姿1,末端法兰相对于基座的变换变化量(这个数据可以直接从机械臂控制器读取并计算)
- 相机的观测 ( $$\bf{B$$):
标定板在相机眼中的相对运动(注意:因为相机动了,所以看到的标定板反向动了)(这个数据通过相机拍摄标定板,利用 PnP 算法或视觉库计算得到)
- 建立方程:
\\underbrace{(\\bf{T}_{base}\^{end_2})\^{-1} \\cdot T_{base}\^{end_1}}_{\\text{机械臂相对运动}} \\cdot \\underbrace{\\bf{T}_{end}\^{camera}}_{\\text{待求}} = \\underbrace{\\bf{T}_{end}\^{camera}}_{\\text{待求}} \\cdot \\underbrace{\\bf{T}_{camera}\^{board_2} \\cdot (T_{camera}\^{board_1})\^{-1}}_{\\text{相机相对运动}}
具体计算步骤
要解出这个$$\bf{X$$,不能只算一次,通常需要采集多组数据(例如 10-20 组)来消除噪声
第一步:数据采集
-
固定标定板:在桌面上固定一个标定板(棋盘格或圆点板)
-
移动 机器人:控制机器人移动到$$$$个不同的位置和姿态(相机跟着动)
-
记录数据:
-
记录每一帧的机器人末端位姿 $$\bf{T}_{base}^{end$$(从控制器读取)
-
拍摄图像,并计算每一帧标定板在相机坐标系下的位姿 $$\bf{T}_{camera}^{board$$(使用 OpenCV 的 solvePnP 或 Halcon 等视觉算法)
-
第二步:构建方程组
对于每一对相邻的运动(例如从第$$$$帧到第$$i+$$帧),构建一个$$\bf{A}i X = X B$$方程
第三步:求解$$\bf{X$$
这是一个经典的矩阵方程,通常使用最小二乘法求解
使用现成库:在实际工程中,你不需要手写 SVD 求解器,可以直接调用成熟的库。
代码实现示例 (Python + OpenCV)
OpenCV 提供了 cv2.calibrateHandEye 函数。
import cv2 import numpy as np # 假设你已经采集了 N 组数据 # R_gripper2base_list: 机器人末端到基座的旋转矩阵列表 (R_be) # t_gripper2base_list: 机器人末端到基座的平移向量列表 (t_be) # R_target2cam_list: 标定板到相机的旋转矩阵列表 (R_tc) # t_target2cam_list: 标定板到相机的平移向量列表 (t_tc) # 1. 准备数据 # 注意:OpenCV 的 calibrateHandEye 求解的是 T_gripper_cam (即 T_end_camera) # 输入参数需要严格对应: # R_gripper2base: T_base_end 的旋转 # R_target2cam: T_cam_target 的旋转 (注意 OpenCV 这里通常需要传入 T_target_cam 或 T_cam_target,需查阅具体版本文档,通常是 T_cam_target) R_cam2gripper, t_cam2gripper = cv2.calibrateHandEye( R_gripper2base_list, # 机器人:末端->基座 (T_base_end) t_gripper2base_list, R_target2cam_list, # 视觉:标定板->相机 (T_cam_board) t_target2cam_list, method=cv2.CALIB_HAND_EYE_TSAI ) # 2. 组合成齐次矩阵 # 得到的是 T_cam_gripper (相机->末端) T_cam_gripper = np.block([ [R_cam2gripper, t_cam2gripper.reshape(3, 1)], [np.zeros((1, 3)), np.array()] ]) # 3. 如果你需要的是 T_end_camera (即 T_gripper2cam),则求逆 T_end_camera = np.linalg.inv(T_cam_gripper) print("计算得到的 T_end_camera (相机在末端坐标系下的位姿):") print(T_end_camera)