目录
[1. 核心原理](#1. 核心原理)
[2. 棋盘格标定实操步骤(OpenCV/ROS 通用)](#2. 棋盘格标定实操步骤(OpenCV/ROS 通用))
[3. 棋盘格优缺点](#3. 棋盘格优缺点)
[二、ChArUco 标定板(棋盘格 + ArUco 标记融合)](#二、ChArUco 标定板(棋盘格 + ArUco 标记融合))
[1. 原理](#1. 原理)
[2. ChArUco 标定实现步骤](#2. ChArUco 标定实现步骤)
[3. ChArUco 对比棋盘格总结](#3. ChArUco 对比棋盘格总结)
[三、手眼标定(Eye-in-Hand / Eye-to-Hand)](#三、手眼标定(Eye-in-Hand / Eye-to-Hand))
[1. 两大经典构型](#1. 两大经典构型)
[2. 数学统一理解](#2. 数学统一理解)
[3. 完整手眼标定分步流程(ChArUco 板实操)](#3. 完整手眼标定分步流程(ChArUco 板实操))
[4. 棋盘格 vs ChArUco 做手眼的区别](#4. 棋盘格 vs ChArUco 做手眼的区别)
[5. 常见踩坑点](#5. 常见踩坑点)
[6. ChArUco 做相机标定 + ChArUco 位姿估计 + 手眼标定(眼在手上)实例代码](#6. ChArUco 做相机标定 + ChArUco 位姿估计 + 手眼标定(眼在手上)实例代码)
[1. 手眼标定的通用前提](#1. 手眼标定的通用前提)
[2. 眼在手上](#2. 眼在手上)
[1. 场景定义](#1. 场景定义)
[2. 眼在手上的采集流程](#2. 眼在手上的采集流程)
[3. 眼在手上的操作逻辑,按人能照着做的方式说](#3. 眼在手上的操作逻辑,按人能照着做的方式说)
[4. 眼在手上的注意点](#4. 眼在手上的注意点)
[3. 眼在手外(Eye-to-Hand)](#3. 眼在手外(Eye-to-Hand))
[1. 场景定义](#1. 场景定义)
[2. 眼在手外的采集流程](#2. 眼在手外的采集流程)
[3. 眼在手外的操作逻辑](#3. 眼在手外的操作逻辑)
[4. 眼在手外的注意点](#4. 眼在手外的注意点)
[4. 两者最关键的区别](#4. 两者最关键的区别)
[5. 按这个理解采集数据](#5. 按这个理解采集数据)
一、张正友相机标定(棋盘格)
1. 核心原理
张正友标定是平面棋盘格两步标定法,介于纯线性标定、复杂非线性三维标定之间,精度高、操作简单,工业视觉标配。



2. 棋盘格标定实操步骤(OpenCV/ROS 通用)
- 打印棋盘格 标准黑白棋盘,记录格子实际物理边长(单位 mm/m,必须精准);平整贴在硬板上无形变。
- 多角度拍摄 20~30 张图片
- 棋盘倾斜、平移、旋转各个姿态;覆盖画面左上、右上、中下全区域;
- 远近搭配,不能只拍同一距离同一角度;画面不能过曝、模糊。
- 角点批量检测 findChessboardCorners → cornerSubPix 亚像素细化,过滤检测失败的图片。
- 运行标定求解 calibrateCamera () 一次性输出:内参 K、畸变系数 dist、每张图像外参 R/t、整体重投影误差。
- 验证矫正 initUndistortRectifyMap 生成映射表,undistort 矫正图像,看棋盘直线是否恢复笔直。
3. 棋盘格优缺点
✅ 优势:制作简单、识别稳定、算法成熟、OpenCV 原生完美支持
❌ 缺陷:只能整板识别,遮挡一小块整张失效;角点数量固定;无法区分棋盘朝向;近距离边缘角点易检测失败
二、ChArUco 标定板(棋盘格 + ArUco 标记融合)
1. 原理
ChArUco = 棋盘内角点 + 分散 ArUco 二维码标记
- 格子交点保留棋盘格高精度亚像素角点;
- 每个 ArUco 码自带唯一 ID,能独立识别、判断旋转朝向、抗遮挡;
- 本质依然套用张正友标定数学框架,只是角点来源换成 ChArUco 角点,求解 K、dist 逻辑完全一致。
独特优势原理
- 局部遮挡:哪怕一半板子被挡住,剩余 ArUco 标记依旧能提取有效角点参与标定;
- 姿态判定:ArUco ID 可以区分板子正反面、旋转角度,不会出现姿态歧义;
- 适配大视场 / 远距离:ArUco 标记远距离辨识度远高于纯棋盘格;
- 可做逐帧位姿估计:单张图片就能高精度算出板子相对相机 R/t,纯棋盘格单张只能求 H,不能单独定位。
2. ChArUco 标定实现步骤
- 生成 ChArUco 板文件 指定行列格子数、方块边长、ArUco 标记边长、ArUco 字典(DICT_4X4_50 常用),生成 PDF 打印。 注意:标记方块尺寸必须小于棋盘格子,嵌入在格子内部。
- 拍摄采集图像(15~25 张即可,比棋盘容错更高)
- 检测流程: detectMarkers 识别所有 ArUco 码 → interpolateCornersCharuco 提取融合亚像素角点
- 标定函数 calibrateCameraCharuco,输出内参、畸变、外参、重投影误差
- 位姿求解:solvePnPCharuco,单张图快速获取板子 6D 位姿
3. ChArUco 对比棋盘格总结
| 类型 | 抗遮挡 | 姿态识别 | 远距离 | 制作难度 | 标定精度 |
|---|---|---|---|---|---|
| 棋盘格 | 差 | 无朝向 | 一般 | 极低 | 极高 |
| ChArUco | 强 | 自带 ID 判朝向 | 优秀 | 略高 | 接近棋盘格 |
机器人手眼场景优先 ChArUco,容错性强很多。
三、手眼标定(Eye-in-Hand / Eye-to-Hand)
1. 两大经典构型
2. 数学统一理解

3. 完整手眼标定分步流程(ChArUco 板实操)
- 相机完成张正友内参 + 畸变标定,保存 K、dist(手眼必须先用相机标定结果,无矫正位姿误差巨大);
- 固定 ChArUco 板:
- Eye-in-Hand:板子锁死在机器人工作台(世界静止)
- Eye-to-Hand:板子锁死在机械臂末端法兰


4. 棋盘格 vs ChArUco 做手眼的区别
- 棋盘格 只能整张识别,稍微遮挡就丢一组数据;姿态模糊时 solvePnP 容易解出翻转错误位姿;适合无遮挡、光照稳定的封闭工位。
- ChArUco(工业首选) 局部标记就能算出完整板子 6D 位姿;抗遮挡、光照波动、轻微模糊;姿态无歧义;现场调试采集成功率高很多,机械臂现场标定标配。
5. 常见踩坑点
- 未做相机内参标定直接手眼:位姿漂移严重;
- 姿态变化太小、几乎同角度采集:矩阵奇异,解严重不准;
- 标定板松动有位移:每组 B 矩阵全部带误差;
- 机械臂零点、减速器间隙带来本体位姿本身有微小偏差;
- 图像畸变不矫正,远距离点位姿偏移放大。
6. ChArUco 做相机标定 + ChArUco 位姿估计 + 手眼标定(眼在手上)实例代码
import os
import json
import glob
from pathlib import Path
import cv2
import numpy as np
# ============================================================
# 工具函数
# ============================================================
def invert_T(T: np.ndarray) -> np.ndarray:
"""
把 4x4 齐次变换矩阵求逆。
T:
[[R, t],
[0, 1]]
"""
T = np.asarray(T, dtype=np.float64)
assert T.shape == (4, 4), "T 必须是 4x4 矩阵"
R = T[:3, :3]
t = T[:3, 3].reshape(3, 1)
T_inv = np.eye(4, dtype=np.float64)
T_inv[:3, :3] = R.T
T_inv[:3, 3] = (-R.T @ t).ravel()
return T_inv
def T_to_rt(T: np.ndarray):
"""
4x4 矩阵 -> R, t
"""
T = np.asarray(T, dtype=np.float64)
assert T.shape == (4, 4), "T 必须是 4x4 矩阵"
R = T[:3, :3].copy()
t = T[:3, 3].reshape(3, 1).copy()
return R, t
def load_robot_poses_json(json_path: str):
"""
读取机器人位姿文件。
约定 JSON 格式如下(顺序必须和图片顺序一致):
{
"poses": [
[[...4x4...]],
[[...4x4...]],
...
]
}
这里默认输入的是 base_T_gripper(机器人基座到末端)的矩阵。
如果你存的是 gripper_T_base,可以在外部改一下,不要重复求逆。
"""
with open(json_path, "r", encoding="utf-8") as f:
data = json.load(f)
poses = data["poses"]
poses = [np.array(p, dtype=np.float64) for p in poses]
for T in poses:
assert T.shape == (4, 4), "每个 pose 必须是 4x4 矩阵"
return poses
def create_charuco_board(squares_x, squares_y, square_length, marker_length, dict_id):
"""
创建 ChArUco 板。
squares_x / squares_y: 棋盘格数量
square_length: 棋盘格边长
marker_length: ArUco 标记边长,必须小于 square_length
dict_id: 例如 cv2.aruco.DICT_4X4_50
"""
dictionary = cv2.aruco.getPredefinedDictionary(dict_id)
# 不同 OpenCV 版本这个构造方式一般可用;
# 如果你的版本不兼容,可以改成 CharucoBoard.create(...)
board = cv2.aruco.CharucoBoard(
(squares_x, squares_y),
square_length,
marker_length,
dictionary
)
return board, dictionary
# ============================================================
# 1) ChArUco 相机内参标定
# ============================================================
def calibrate_camera_charuco(
image_dir: str,
squares_x: int,
squares_y: int,
square_length: float,
marker_length: float,
dict_id=cv2.aruco.DICT_4X4_50,
show=False
):
"""
使用 ChArUco 图像进行相机标定。
返回:
rms, camera_matrix, dist_coeffs, rvecs, tvecs, board
"""
board, dictionary = create_charuco_board(
squares_x, squares_y, square_length, marker_length, dict_id
)
# ArUco 检测参数
detector_params = cv2.aruco.DetectorParameters()
# 收集每一张图的 ChArUco 角点和 ID
all_charuco_corners = []
all_charuco_ids = []
image_size = None
image_paths = sorted(
glob.glob(os.path.join(image_dir, "*.png")) +
glob.glob(os.path.join(image_dir, "*.jpg")) +
glob.glob(os.path.join(image_dir, "*.jpeg")) +
glob.glob(os.path.join(image_dir, "*.bmp"))
)
if len(image_paths) == 0:
raise FileNotFoundError(f"目录里没有找到图片: {image_dir}")
for img_path in image_paths:
img = cv2.imread(img_path)
if img is None:
print(f"[跳过] 无法读取图像: {img_path}")
continue
gray = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY)
if image_size is None:
image_size = (gray.shape[1], gray.shape[0])
# 第一步:先检测 ArUco 标记
marker_corners, marker_ids, rejected = cv2.aruco.detectMarkers(
gray, dictionary, parameters=detector_params
)
if marker_ids is None or len(marker_ids) == 0:
print(f"[跳过] 未检测到 ArUco 标记: {os.path.basename(img_path)}")
continue
# 第二步:由 ArUco 标记插值得到 ChArUco 角点
retval, charuco_corners, charuco_ids = cv2.aruco.interpolateCornersCharuco(
marker_corners, marker_ids, gray, board
)
# 角点太少就不参与标定
if charuco_ids is None or len(charuco_ids) < 4:
print(f"[跳过] ChArUco 角点过少: {os.path.basename(img_path)}")
continue
all_charuco_corners.append(charuco_corners)
all_charuco_ids.append(charuco_ids)
if show:
vis = img.copy()
cv2.aruco.drawDetectedMarkers(vis, marker_corners, marker_ids)
cv2.aruco.drawDetectedCornersCharuco(vis, charuco_corners, charuco_ids)
cv2.imshow("charuco_detect", vis)
cv2.waitKey(200)
print(f"[OK] {os.path.basename(img_path)}: 角点数 = {len(charuco_ids)}")
if show:
cv2.destroyAllWindows()
if len(all_charuco_corners) < 5:
raise RuntimeError("有效标定图像太少,建议至少 5 张以上有效 ChArUco 图像")
# 第三步:标定相机内参和畸变
rms, camera_matrix, dist_coeffs, rvecs, tvecs = cv2.aruco.calibrateCameraCharuco(
all_charuco_corners,
all_charuco_ids,
board,
image_size,
None,
None
)
print("\n========== 相机标定结果 ==========")
print("RMS 重投影误差:", rms)
print("Camera Matrix:\n", camera_matrix)
print("Dist Coeffs:\n", dist_coeffs.ravel())
return rms, camera_matrix, dist_coeffs, rvecs, tvecs, board
# ============================================================
# 2) 单张图估计 ChArUco 板相对相机位姿
# ============================================================
def estimate_charuco_pose(
image_bgr,
board,
dictionary,
camera_matrix,
dist_coeffs
):
"""
输入一张图,输出 ChArUco 板相对相机的位姿。
返回:
valid, rvec, tvec, vis_image
"""
gray = cv2.cvtColor(image_bgr, cv2.COLOR_BGR2GRAY)
detector_params = cv2.aruco.DetectorParameters()
marker_corners, marker_ids, rejected = cv2.aruco.detectMarkers(
gray, dictionary, parameters=detector_params
)
if marker_ids is None or len(marker_ids) == 0:
return False, None, None, image_bgr
retval, charuco_corners, charuco_ids = cv2.aruco.interpolateCornersCharuco(
marker_corners, marker_ids, gray, board
)
if charuco_ids is None or len(charuco_ids) < 4:
return False, None, None, image_bgr
# 直接估计板子的 6D 位姿
rvec = np.zeros((3, 1), dtype=np.float64)
tvec = np.zeros((3, 1), dtype=np.float64)
valid = cv2.aruco.estimatePoseCharucoBoard(
charuco_corners, charuco_ids, board,
camera_matrix, dist_coeffs,
rvec, tvec
)
vis = image_bgr.copy()
cv2.aruco.drawDetectedMarkers(vis, marker_corners, marker_ids)
cv2.aruco.drawDetectedCornersCharuco(vis, charuco_corners, charuco_ids)
if valid:
# 画坐标轴,方便肉眼检查
axis_len = 0.5 * min(board.getChessboardSize()) * board.getSquareLength()
cv2.drawFrameAxes(vis, camera_matrix, dist_coeffs, rvec, tvec, axis_len)
return valid, rvec, tvec, vis
# ============================================================
# 3) 手眼标定(Eye-in-Hand 示例)
# ============================================================
def calibrate_eye_in_hand(
image_dir: str,
robot_pose_json: str,
squares_x: int,
squares_y: int,
square_length: float,
marker_length: float,
dict_id=cv2.aruco.DICT_4X4_50,
show=False,
output_calib_json="camera_calib_result.json"
):
"""
Eye-in-Hand 场景示例:
- 相机安装在机械臂末端
- ChArUco 板固定在工作台上
输入:
image_dir: 标定图像目录
robot_pose_json: 与图像一一对应的机器人位姿
默认每个 pose 是 base_T_gripper
squares_x, squares_y, square_length, marker_length: ChArUco 板参数
输出:
camera 内参、畸变、手眼矩阵 cam_T_gripper
"""
# 先做相机内参标定
rms, K, dist, rvecs, tvecs, board = calibrate_camera_charuco(
image_dir=image_dir,
squares_x=squares_x,
squares_y=squares_y,
square_length=square_length,
marker_length=marker_length,
dict_id=dict_id,
show=False
)
# 重新读取一次,逐帧做位姿估计
board, dictionary = create_charuco_board(
squares_x, squares_y, square_length, marker_length, dict_id
)
detector_params = cv2.aruco.DetectorParameters()
image_paths = sorted(
glob.glob(os.path.join(image_dir, "*.png")) +
glob.glob(os.path.join(image_dir, "*.jpg")) +
glob.glob(os.path.join(image_dir, "*.jpeg")) +
glob.glob(os.path.join(image_dir, "*.bmp"))
)
robot_poses_base_T_gripper = load_robot_poses_json(robot_pose_json)
if len(image_paths) != len(robot_poses_base_T_gripper):
raise ValueError(
f"图片数量({len(image_paths)})和机器人位姿数量({len(robot_poses_base_T_gripper)})不一致"
)
R_gripper2base = []
t_gripper2base = []
R_target2cam = []
t_target2cam = []
for idx, img_path in enumerate(image_paths):
img = cv2.imread(img_path)
if img is None:
print(f"[跳过] 无法读取图像: {img_path}")
continue
# 机器人通常给的是 base_T_gripper,
# 而 calibrateHandEye 需要 gripper2base,所以这里先取逆。
base_T_gripper = robot_poses_base_T_gripper[idx]
gripper_T_base = invert_T(base_T_gripper)
Rg2b, tg2b = T_to_rt(gripper_T_base)
R_gripper2base.append(Rg2b)
t_gripper2base.append(tg2b)
valid, rvec, tvec, vis = estimate_charuco_pose(
img, board, dictionary, K, dist
)
if not valid:
print(f"[跳过] 该帧没能稳定估计板子位姿: {os.path.basename(img_path)}")
# 为了保证配对一致,前面已经先把机器人位姿 append 了,
# 这里需要删掉刚加入的这一组。
R_gripper2base.pop()
t_gripper2base.pop()
continue
# estimatePoseCharucoBoard 得到的是"板子到相机"的位姿,
# 正好对应 calibrateHandEye 里的 target2cam
Rt2c, tt2c = T_to_rt(np.vstack([
np.hstack([cv2.Rodrigues(rvec)[0], tvec]),
np.array([0, 0, 0, 1], dtype=np.float64)
]))
R_target2cam.append(Rt2c)
t_target2cam.append(tt2c)
if show:
cv2.imshow("pose_vis", vis)
cv2.waitKey(200)
print(f"[OK] {os.path.basename(img_path)}: 位姿有效")
if show:
cv2.destroyAllWindows()
if len(R_gripper2base) < 5:
raise RuntimeError("有效配对数据太少,建议至少准备 5 组以上有效样本")
# 进行手眼标定
# OpenCV 文档中的参数顺序就是:
# R_gripper2base, t_gripper2base, R_target2cam, t_target2cam
# 输出:
# R_cam2gripper, t_cam2gripper
R_cam2gripper, t_cam2gripper = cv2.calibrateHandEye(
R_gripper2base,
t_gripper2base,
R_target2cam,
t_target2cam,
method=cv2.CALIB_HAND_EYE_TSAI
)
print("\n========== 手眼标定结果 ==========")
print("R_cam2gripper:\n", R_cam2gripper)
print("t_cam2gripper:\n", t_cam2gripper.ravel())
# 保存相机内参与手眼结果
result = {
"camera_matrix": K.tolist(),
"dist_coeffs": dist.reshape(-1).tolist(),
"rms": float(rms),
"R_cam2gripper": R_cam2gripper.tolist(),
"t_cam2gripper": t_cam2gripper.reshape(-1).tolist(),
}
with open(output_calib_json, "w", encoding="utf-8") as f:
json.dump(result, f, ensure_ascii=False, indent=2)
print(f"\n结果已保存到: {output_calib_json}")
return K, dist, R_cam2gripper, t_cam2gripper
# ============================================================
# 4) 主程序示例
# ============================================================
if __name__ == "__main__":
# ------------------------------
# 你需要改的参数
# ------------------------------
IMAGE_DIR = r"./charuco_images"
ROBOT_POSE_JSON = r"./robot_poses.json"
# ChArUco 板参数
# 注意:单位必须统一,比如都用 mm 或都用 m
SQUARES_X = 7
SQUARES_Y = 5
SQUARE_LENGTH = 30.0 # 例如 30mm
MARKER_LENGTH = 22.0 # 必须小于 square_length
# 1) 只做相机标定:
# rms, K, dist, rvecs, tvecs, board = calibrate_camera_charuco(
# IMAGE_DIR, SQUARES_X, SQUARES_Y, SQUARE_LENGTH, MARKER_LENGTH,
# dict_id=cv2.aruco.DICT_4X4_50, show=True
# )
# 2) 做完整 eye-in-hand 手眼标定:
K, dist, R_cam2gripper, t_cam2gripper = calibrate_eye_in_hand(
image_dir=IMAGE_DIR,
robot_pose_json=ROBOT_POSE_JSON,
squares_x=SQUARES_X,
squares_y=SQUARES_Y,
square_length=SQUARE_LENGTH,
marker_length=MARKER_LENGTH,
dict_id=cv2.aruco.DICT_4X4_50,
show=False,
output_calib_json="calibration_result.json"
)
四、手眼标定详细流程
1. 手眼标定的通用前提
不管哪一种安装方式,先满足这几个条件:
- 先完成相机内参标定
也就是先知道相机矩阵和畸变参数,否则板子位姿会不准。 - 准备一个固定标定板
常用棋盘格、ChArUco、AprilTag 板。工业里 ChArUco 很常见,因为鲁棒性更好。 - 采集多组同步数据
每一组都要包含:- 一帧图像
- 这一帧对应时刻的机器人位姿
- 位姿变化要足够丰富
不要只在一个平面附近转动。要有不同角度、不同位置、一定的旋转幅度。
这样才能让求解更稳定。
2. 眼在手上
1. 场景定义
- 相机固定在机器人末端执行器上
- 标定板固定在工作台或环境中
- 机器人动,相机也跟着动
你最终要得到的是:
- 相机相对于末端执行器的外参
- 或者反过来,末端执行器相对于相机的变换
2. 眼在手上的采集流程
第一步:固定标定板
把标定板牢固放在桌面或工装上,后续不要移动。
第二步:相机装到末端
相机安装在机械臂末端,确保安装牢固,不要有松动。
第三步:标定相机内参
先用棋盘格或 ChArUco 做相机内参标定,得到:
camera_matrixdist_coeffs
第四步:采集多组数据
让机器人带着相机移动到多个位置和姿态,每到一个姿态都记录两类数据:
- 当前图像
- 当前机器人位姿
这里机器人位姿通常是:
base_T_gripper,即机器人基座到末端的位姿
每一帧图像中,再去检测标定板,求出:
target_T_cam或cam_T_target
注意这里要统一定义。OpenCV 手眼标定通常需要的是:
- 机器人端:
gripper2base - 标定板端:
target2cam
第五步:每张图估计标定板位姿
对每张图做标定板检测,得到标定板相对于相机的位姿。
如果用 ChArUco,一般流程是:
- 检测 ArUco marker
- 插值得到 ChArUco 角点
solvePnP或estimatePoseCharucoBoard求位姿
第六步:整理成手眼标定输入
把每一组数据整理成:
R_gripper2base, t_gripper2baseR_target2cam, t_target2cam
然后喂给手眼标定函数。
第七步:求解手眼外参
求出的结果通常是:
cam_T_gripper
它表示"相机坐标系相对于末端执行器"的固定关系。
3. 眼在手上的操作逻辑,按人能照着做的方式说
你可以把它理解成下面这条线:
- 标定板不动
- 机器人拿着相机去看板子
- 每到一个姿态,就拍一张图
- 同时记录机器人末端位姿
- 从图像里算出板子相对相机的位姿
- 把所有姿态一起送进手眼算法
- 得到"相机装在末端上的准确外参"
4. 眼在手上的注意点
- 机器人姿态变化要明显,不能太接近
- 标定板在画面里要尽量清楚,不能总是只看到一小块
- 相机和末端之间不能有松动
- 图像和机器人数据要严格一一对应
- 采集时尽量让标定板出现在画面不同区域
3. 眼在手外(Eye-to-Hand)
1. 场景定义
- 相机固定在外部,不跟随机器人动
- 机器人在相机视野中运动
- 标定板通常固定在机器人末端,或者固定在工作空间中,具体看方案
这里常见有两种变体:
变体 A:标定板固定在末端
相机固定,标定板装在机器人末端上,机器人带着板子运动。
变体 B:标定板固定在环境中
相机固定,板子固定不动,机器人运动到不同位置参与标定。
这种情况下还要额外处理机器人与板子之间的关系。
工业里更常见的是根据系统设计来选用其中一种,但本质都是求固定外参。
2. 眼在手外的采集流程
第一步:固定相机
把相机固定在支架、龙门架或工位上,确保视角不会变化。
第二步:标定相机内参
同样先做内参标定。
第三步:确定标定板安装方式
这里要分清楚:
情况 1:板子装在机器人末端;那机器人动,板子动,相机固定。
情况 2:板子固定在环境中;那机器人动,板子不动,相机也不动。
这两种方式的数学关系不一样,采集时一定要先明确。
第四步:采集多组数据
每一组都记录:
- 图像
- 机器人位姿
如果标定板装在末端,那么你还需要知道:
- 末端相对于基座的位姿
如果板子固定在环境中,那么还要明确:
- 标定板相对于基座或工作台的固定位姿
第五步:图像中估计标定板位姿
每张图检测标定板,得到标定板相对于相机的位姿。
第六步:整理变换关系
眼在手外时,经常会把问题整理成:
- 相机到基座的固定外参
- 或者标定板到基座的固定外参
取决于你给手眼算法的定义。
第七步:求解固定关系
把所有采集到的数据代入手眼求解,得到:
base_T_cam- 或
cam_T_base
最终你就知道"固定相机在机器人坐标系里的准确位置"。
3. 眼在手外的操作逻辑
可以理解成:
- 相机固定在外部
- 机器人在视野内运动
- 每到一个姿态,拍图并记录机器人位姿
- 从图像中算出标定板位姿
- 通过多个姿态联合求解
- 得到相机相对于机器人基座的外参
4. 眼在手外的注意点
- 相机必须固定牢靠
- 如果板子固定在环境中,要保证板子坐标定义稳定
- 机器人运动范围要足够大
- 图像中的标定板不能总是很小
- 数据采集时位姿变化要明显,否则解会不稳定
4. 两者最关键的区别
眼在手上
- 相机跟着末端动
- 要求的是"相机相对于末端"的关系
- 常用于抓取、跟踪、末端视觉引导
眼在手外
- 相机固定不动
- 要求的是"相机相对于机器人基座"的关系
- 常用于工作站监控、全局定位、视觉引导
5. 按这个理解采集数据
眼在手上采集清单
每组数据都要有:
- 一张图像
- 当前机器人末端位姿
- 标定板检测结果
最后求:
cam_T_gripper
眼在手外采集清单
每组数据都要有:
- 一张图像
- 当前机器人位姿
- 标定板检测结果
- 还要明确板子是固定还是装在末端
最后求:
cam_T_base或base_T_cam
