跳转至

相机标定与选型

概述

相机标定(Camera Calibration)是确定相机内部参数和镜头畸变系数的过程,是所有精确视觉测量的前提。本节介绍针孔相机模型、标定方法、畸变校正,以及根据应用场景选择合适相机的指南。

针孔相机模型

投影方程

针孔模型将3D世界点投影到2D图像平面:

\[ \begin{bmatrix} u \\ v \\ 1 \end{bmatrix} = \frac{1}{Z} K [R|t] \begin{bmatrix} X \\ Y \\ Z \\ 1 \end{bmatrix} \]

其中:

  • \((u, v)\):像素坐标
  • \((X, Y, Z)\):世界坐标
  • \(K\):相机内参矩阵
  • \([R|t]\):外参矩阵(旋转+平移)

内参矩阵

\[ K = \begin{bmatrix} f_x & 0 & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1 \end{bmatrix} \]
参数 含义 单位
\(f_x, f_y\) x/y方向焦距 像素
\(c_x, c_y\) 主点(光轴与图像平面的交点) 像素

焦距从mm转像素:

\[ f_x = \frac{f_{\text{mm}} \times \text{width}_{\text{pixel}}}{\text{sensor\_width}_{\text{mm}}} \]

IMX219内参估算

焦距3.04mm,传感器宽3.68mm,图像宽1920像素:

\[f_x = \frac{3.04 \times 1920}{3.68} = 1585.7 \text{ pixels}\]

外参矩阵

\[ [R|t] = \begin{bmatrix} r_{11} & r_{12} & r_{13} & t_x \\ r_{21} & r_{22} & r_{23} & t_y \\ r_{31} & r_{32} & r_{33} & t_z \end{bmatrix} \]
  • \(R\)(3x3旋转矩阵):相机相对世界坐标系的朝向
  • \(t\)(3x1平移向量):相机在世界坐标系中的位置

完整投影过程

\[ \begin{bmatrix} x' \\ y' \\ z' \end{bmatrix} = [R|t] \begin{bmatrix} X_w \\ Y_w \\ Z_w \\ 1 \end{bmatrix} \quad \rightarrow \quad \begin{bmatrix} u \\ v \end{bmatrix} = \begin{bmatrix} f_x \frac{x'}{z'} + c_x \\ f_y \frac{y'}{z'} + c_y \end{bmatrix} \]

镜头畸变

畸变类型

实际镜头会引入畸变,主要有两类:

径向畸变(Radial Distortion)

\[ \begin{aligned} x_{\text{distorted}} &= x(1 + k_1 r^2 + k_2 r^4 + k_3 r^6) \\ y_{\text{distorted}} &= y(1 + k_1 r^2 + k_2 r^4 + k_3 r^6) \end{aligned} \]

其中 \(r^2 = x^2 + y^2\)\((x, y)\) 是归一化图像坐标。

切向畸变(Tangential Distortion)

\[ \begin{aligned} x_{\text{distorted}} &= x + 2p_1 xy + p_2(r^2 + 2x^2) \\ y_{\text{distorted}} &= y + p_1(r^2 + 2y^2) + 2p_2 xy \end{aligned} \]

畸变系数

OpenCV使用5个(或更多)畸变系数:

\[ D = [k_1, k_2, p_1, p_2, k_3] \]
系数 类型 影响
\(k_1\) 径向 主要畸变项(最重要)
\(k_2\) 径向 二次修正
\(k_3\) 径向 高次修正(广角镜头需要)
\(p_1\) 切向 镜头与传感器不平行
\(p_2\) 切向 镜头与传感器不平行

畸变可视化

正常网格:         桶形畸变(k1<0):      枕形畸变(k1>0):
┌──┬──┬──┬──┐    ╭──┬──┬──┬──╮       ┌──┬──┬──┬──┐
├──┼──┼──┼──┤    ├──┼──┼──┼──┤       │╲ │  │  │╱ │
├──┼──┼──┼──┤    ├──┼──┼──┼──┤       │ ╲│  │  │╱ │
├──┼──┼──┼──┤    ├──┼──┼──┼──┤       │ ╱│  │  │╲ │
└──┴──┴──┴──┘    ╰──┴──┴──┴──╯       └──┴──┴──┴──┘
广角镜头常见        长焦镜头偶尔

Zhang标定法

原理

张正友标定法(Zhang's Method)使用平面标定板(如棋盘格)从多张不同角度的照片中估计相机内参和畸变系数。

基本思路

  1. 棋盘格上的角点世界坐标已知(\(Z=0\)平面)
  2. 检测角点在图像中的像素坐标
  3. 每张图片提供一个单应性矩阵 \(H\)
  4. 从多个 \(H\) 中求解内参 \(K\) 和畸变系数

标定步骤

import cv2
import numpy as np
import glob

# 1. 准备棋盘格参数
CHECKERBOARD = (9, 6)  # 内角点数
SQUARE_SIZE = 0.025    # 格子大小(米)

# 3D世界坐标
objp = np.zeros((CHECKERBOARD[0]*CHECKERBOARD[1], 3), np.float32)
objp[:, :2] = np.mgrid[0:CHECKERBOARD[0], 0:CHECKERBOARD[1]].T.reshape(-1, 2)
objp *= SQUARE_SIZE

obj_points = []  # 3D点
img_points = []  # 2D点

# 2. 检测角点
images = glob.glob('calibration_images/*.jpg')
for fname in images:
    img = cv2.imread(fname)
    gray = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY)

    ret, corners = cv2.findChessboardCorners(
        gray, CHECKERBOARD,
        cv2.CALIB_CB_ADAPTIVE_THRESH + cv2.CALIB_CB_NORMALIZE_IMAGE
    )

    if ret:
        # 亚像素精化
        corners = cv2.cornerSubPix(
            gray, corners, (11, 11), (-1, -1),
            (cv2.TERM_CRITERIA_EPS + cv2.TERM_CRITERIA_MAX_ITER, 30, 0.001)
        )
        obj_points.append(objp)
        img_points.append(corners)

# 3. 标定
ret, K, D, rvecs, tvecs = cv2.calibrateCamera(
    obj_points, img_points, gray.shape[::-1], None, None
)

print(f"内参矩阵 K:\n{K}")
print(f"畸变系数 D: {D.ravel()}")
print(f"重投影误差: {ret:.4f} pixels")

# 4. 保存标定结果
np.savez('calibration.npz', K=K, D=D)

标定质量评估

重投影误差(Reprojection Error)

\[ \text{RMS} = \sqrt{\frac{1}{N} \sum_{i=1}^{N} \|\mathbf{p}_i - \hat{\mathbf{p}}_i\|^2} \]
重投影误差 质量
< 0.3 pixel 优秀
0.3 - 0.5 pixel 良好
0.5 - 1.0 pixel 可接受
> 1.0 pixel 需要重新标定

标定最佳实践

提高标定精度的技巧

  1. 至少20张图片,从不同角度和距离拍摄
  2. 棋盘格应覆盖图像的各个区域(包括边缘和角落)
  3. 包含多种倾斜角度(不只是正对相机)
  4. 使用平整的标定板(打印并粘贴在平面上)
  5. 确保图片清晰(无运动模糊)
  6. 标定板应占图像面积的20-80%

去畸变

图像去畸变

# 方法1:直接去畸变(简单但每帧计算)
undistorted = cv2.undistort(img, K, D)

# 方法2:预计算映射表(推荐,只计算一次)
new_K, roi = cv2.getOptimalNewCameraMatrix(K, D, (w, h), alpha=0)
map1, map2 = cv2.initUndistortRectifyMap(K, D, None, new_K, (w, h), cv2.CV_16SC2)

# 对每帧应用映射
undistorted = cv2.remap(img, map1, map2, cv2.INTER_LINEAR)

点去畸变

# 将畸变图像上的点转为去畸变坐标
points_distorted = np.array([[100, 200], [300, 400]], dtype=np.float32)
points_distorted = points_distorted.reshape(-1, 1, 2)

points_undistorted = cv2.undistortPoints(
    points_distorted, K, D, P=new_K
)

视场角(FOV)计算

从内参计算FOV

\[ \text{FOV}_H = 2 \arctan\left(\frac{w}{2f_x}\right), \quad \text{FOV}_V = 2 \arctan\left(\frac{h}{2f_y}\right) \]
import numpy as np

def compute_fov(K, image_size):
    fx, fy = K[0, 0], K[1, 1]
    w, h = image_size

    fov_h = 2 * np.degrees(np.arctan(w / (2 * fx)))
    fov_v = 2 * np.degrees(np.arctan(h / (2 * fy)))
    fov_d = 2 * np.degrees(np.arctan(
        np.sqrt(w**2 + h**2) / (2 * np.sqrt(fx * fy))
    ))

    return fov_h, fov_v, fov_d

fov_h, fov_v, fov_d = compute_fov(K, (1920, 1080))
print(f"水平FOV: {fov_h:.1f}°, 垂直FOV: {fov_v:.1f}°, 对角FOV: {fov_d:.1f}°")

FOV与覆盖范围

在距离 \(d\) 处的覆盖范围:

\[ W = 2d \tan\left(\frac{\text{FOV}_H}{2}\right), \quad H = 2d \tan\left(\frac{\text{FOV}_V}{2}\right) \]
FOV 1m处覆盖 3m处覆盖 5m处覆盖
60° 1.15m 3.46m 5.77m
90° 2.00m 6.00m 10.0m
120° 3.46m 10.4m 17.3m

双目标定

# 双目标定
ret, K_left, D_left, K_right, D_right, R, T, E, F = cv2.stereoCalibrate(
    obj_points, img_points_left, img_points_right,
    K_left, D_left, K_right, D_right,
    gray.shape[::-1],
    flags=cv2.CALIB_FIX_INTRINSIC  # 固定已标定的内参
)

print(f"基线长度: {np.linalg.norm(T):.4f}m")
print(f"双目标定误差: {ret:.4f} pixels")

手眼标定

机器人手眼标定求解相机与机器人末端之间的变换 \(T_{CE}\)

\[ A_i X = X B_i \]

其中 \(A_i\) 是机器人末端的相对运动,\(B_i\) 是相机观测到的相对运动,\(X = T_{CE}\)

# OpenCV手眼标定
R_target2cam = [rvecs]  # 标定板到相机的旋转
t_target2cam = [tvecs]  # 标定板到相机的平移
R_gripper2base = [...]  # 机器人末端到基座的旋转
t_gripper2base = [...]  # 机器人末端到基座的平移

R_cam2gripper, t_cam2gripper = cv2.calibrateHandEye(
    R_gripper2base, t_gripper2base,
    R_target2cam, t_target2cam,
    method=cv2.CALIB_HAND_EYE_TSAI
)

选型指南

按应用场景选择

应用场景 关键需求 推荐相机 理由
室内SLAM 深度+IMU RealSense D435i 主动立体+IMU
室外SLAM 防水、室外深度 ZED 2i IP66+被动双目
机械臂抓取 近距离精度 RealSense D405 7cm起、高精度
高速VIO 全局快门+IMU OV9281 + IMU 全局快门无运动畸变
目标检测 高分辨率RGB IMX477 + 镜头 12.3MP、可换镜头
夜视 低光性能 IMX462 星光级CMOS
全方位感知 360°覆盖 4x鱼眼方案 无死角
高速场景 μs时间分辨率 DAVIS346 事件相机
教学原型 低成本 RPi Camera V2 $25入门

选型决策流程

graph TD
    A[视觉任务] --> B{预算?}
    B -->|<$50| C[RPi Camera V2/V3]
    B -->|$50-200| D{需要深度?}
    B -->|$200-500| E{特殊需求?}
    B -->|>$500| F[工业相机/事件相机]

    D -->|否| G[IMX477 + 镜头]
    D -->|是| H[OAK-D Lite]

    E -->|室外防水| I[ZED 2i]
    E -->|近距离精度| J[RealSense D405]
    E -->|通用| K[RealSense D435i]
    E -->|远距离| L[RealSense D455]

关键参数清单

选型时需要确认的参数:

参数 问题
分辨率 需要多细的检测粒度?
帧率 机器人速度和控制频率要求?
FOV 需要覆盖多大范围?
深度范围 最近和最远的工作距离?
深度精度 定位/抓取的精度要求?
接口 CSI(低延迟)还是USB(灵活)?
快门 高速运动需要全局快门?
环境 室内/室外/防水/温度范围?
功耗 电池供电的预算?
尺寸重量 安装空间限制?
软件生态 ROS2驱动、SDK成熟度?

参见:标定与系统集成 了解更多关于实际部署中的标定流程。

在线标定与自标定

为什么需要在线标定

  • 相机参数可能随温度变化
  • 物理冲击可能改变安装位姿
  • 长期运行后镜头和结构可能松动

自标定方法

方法 原理 精度 适用
运动自标定 从图像序列恢复内参 无标定板时
消失点标定 利用场景中的平行线 结构化环境
标记物标定 AprilTag/ArUco 可放置标记物时
连续优化 SLAM中联合优化内参 长时间运行
# ArUco标记物检测与位姿估计
import cv2

aruco_dict = cv2.aruco.getPredefinedDictionary(cv2.aruco.DICT_4X4_50)
parameters = cv2.aruco.DetectorParameters()
detector = cv2.aruco.ArucoDetector(aruco_dict, parameters)

corners, ids, rejected = detector.detectMarkers(image)

if ids is not None:
    # 估计标记物位姿
    rvecs, tvecs, _ = cv2.aruco.estimatePoseSingleMarkers(
        corners, marker_size, K, D
    )
    for rvec, tvec in zip(rvecs, tvecs):
        cv2.drawFrameAxes(image, K, D, rvec, tvec, marker_size/2)

小结

  1. 针孔模型是相机投影的基本数学框架
  2. 张正友标定法是最常用的标定方法,需要20+张多角度图片
  3. 重投影误差<0.5px是良好标定的指标
  4. 预计算映射表是实时去畸变的最佳实践
  5. 选型需综合考虑分辨率、帧率、FOV、深度、接口、环境等因素
  6. 手眼标定是机械臂视觉的必要步骤

参考资料

  • Zhang, Z. "A Flexible New Technique for Camera Calibration" IEEE TPAMI, 2000
  • Hartley, R., & Zisserman, A. Multiple View Geometry in Computer Vision
  • OpenCV Camera Calibration Tutorial: https://docs.opencv.org/
  • Tsai, R. Y., & Lenz, R. K. "A New Technique for Fully Autonomous and Efficient 3D Robotics Hand/Eye Calibration"

评论 #