14.Calibration模块详解

第十四部分:Calibration标定模块详解

免责声明

本文档仅供学习和技术研究使用,内容基于 Apollo 开源项目的公开资料和代码分析整理而成。文档中的技术实现细节、架构设计等内容可能随 Apollo 项目更新而变化。使用本文档所述技术方案时,请以 Apollo 官方最新文档为准。

声明事项:

  • 本文档不构成任何商业使用建议
  • 涉及自动驾驶技术的应用需遵守当地法律法规
  • 作者不对因使用本文档内容产生的任何后果承担责任
  • Apollo 为百度公司注册商标,本文档为非官方技术解析

1. 标定模块概述

1.1 标定的重要性

在自动驾驶系统中,**标定(Calibration)**是确保传感器数据准确性和一致性的关键环节。标定分为两大类:

  1. 内参标定(Intrinsic Calibration)

    • 传感器自身的物理特性
    • 例如:相机焦距、畸变系数、激光雷达角度误差
  2. 外参标定(Extrinsic Calibration)

    • 传感器之间的相对位置和姿态
    • 例如:相机相对于激光雷达的位置、IMU相对于车体的位置

1.2 Apollo标定模块架构

复制代码
Apollo Calibration System
├── Calibration Data (配置数据层)
│   ├── camera_params/      # 相机内外参
│   ├── lidar_params/       # 激光雷达标定
│   ├── radar_params/       # 雷达外参
│   ├── gnss_params/        # GNSS/IMU标定
│   └── vehicle_params/     # 车辆参数
│
├── Drivers Layer (驱动层标定)
│   ├── Velodyne Calibration
│   │   ├── Intrinsic Calibration    # 内标定
│   │   └── Online Calibration       # 在线标定
│   └── LSLidar Calibration
│
├── Perception Layer (感知层标定)
│   ├── Camera Calibrator
│   │   └── LaneLineCalibrator       # 基于车道线的在线标定
│   └── Calibration Service
│       └── OnlineCalibrationService # 在线标定服务
│
└── Tools Layer (工具层)
    ├── sensor_calibration/          # 传感器标定工具
    ├── vehicle_calibration/         # 车辆标定工具
    └── adataset/                    # 数据集转换工具

1.3 支持的标定类型

标定类型 子类型 主要参数 精度要求
LiDAR标定 内参标定 角度校正、距离校正 < 1cm
外参标定 3D位置、旋转矩阵 < 2cm
相机标定 内参标定 焦距、畸变系数 < 0.5 pixel
外参标定 相对位姿 < 2cm
GNSS/IMU标定 天线杆臂 3D偏移量 < 5cm
IMU外参 旋转矩阵 < 1°
雷达标定 外参标定 3D位置、姿态 < 5cm
车辆标定 动力学标定 控制响应曲线 < 5%

1.4 标定模块文件结构

复制代码
modules/calibration/
├── data/                              # 标定数据目录(159个文件)
│   ├── kitti_140/                     # KITTI数据集标定
│   │   ├── camera_params/
│   │   ├── lidar_params/
│   │   ├── gnss_params/
│   │   └── vehicle_params/
│   ├── mkz_121/                       # MKZ标准配置
│   │   ├── camera_params/
│   │   ├── lidar_params/
│   │   ├── radar_params/
│   │   ├── gnss_params/
│   │   └── vehicle_params/
│   ├── mkz_example/                   # MKZ仿真示例
│   ├── mkz_lgsvl_321/                # MKZ LGSVL仿真
│   ├── nuscenes_165/                 # nuScenes数据集
│   └── nuscenes_occ/                 # nuScenes占用网格
├── README.md
└── BUILD

2. 激光雷达标定

2.1 激光雷达内参标定

激光雷达内参描述了每条激光线束的物理特性和校正参数。

2.1.1 LaserCorrection数据结构
cpp 复制代码
// 文件: modules/drivers/lidar/velodyne/parser/calibration.h:43-65

struct LaserCorrection {
  // ========== 基本校正参数 ==========
  float rot_correction;              // 旋转校正(弧度)
  float vert_correction;             // 垂直角度校正(弧度)
  float dist_correction;             // 距离校正(米)
  float dist_correction_x;           // X轴距离校正
  float dist_correction_y;           // Y轴距离校正
  float vert_offset_correction;      // 垂直偏移校正
  float horiz_offset_correction;     // 水平偏移校正

  // ========== 强度校正参数 ==========
  int max_intensity;                 // 最大强度值
  int min_intensity;                 // 最小强度值

  // ========== 焦点参数 ==========
  float focal_distance;              // 焦点距离
  float focal_slope;                 // 焦点斜率
  float focal_offset;                // 焦点偏移(计算得出)

  // ========== 缓存的三角函数值 ==========
  float cos_rot_correction;          // cos(rot_correction)
  float sin_rot_correction;          // sin(rot_correction)
  float cos_vert_correction;         // cos(vert_correction)
  float sin_vert_correction;         // sin(vert_correction)

  int laser_ring;                    // 激光环编号
};

参数说明

  1. 旋转校正(rot_correction)

    • 补偿激光发射器的安装角度误差
    • 单位:弧度
    • 典型值:-0.1 到 0.1 弧度
  2. 垂直角度校正(vert_correction)

    • 每条激光线束的垂直角度
    • 单位:弧度
    • 示例(VLP-16):-15°到15°之间均匀分布
  3. 距离校正(dist_correction)

    • 补偿激光测距的系统误差
    • 单位:米
    • 典型值:0 到 2米
  4. 焦点参数

    • 用于补偿近距离测量的非线性误差
    • focal_offset = 256 * (1 - focal_distance/13100)²
2.1.2 Calibration类实现
cpp 复制代码
// 文件: modules/drivers/lidar/velodyne/parser/calibration.h:68-82

class Calibration {
 public:
  std::map<int, LaserCorrection> laser_corrections_;  // 激光校正映射表
  int num_lasers_;                                    // 激光线束数量
  bool initialized_;                                  // 是否已初始化

  Calibration() : initialized_(false) {}

  explicit Calibration(const std::string& calibration_file) {
    read(calibration_file);  // 从文件读取标定参数
  }

  void read(const std::string& calibration_file);   // 读取YAML标定文件
  void write(const std::string& calibration_file);  // 写入YAML标定文件
};
2.1.3 标定文件解析
cpp 复制代码
// 文件: modules/drivers/lidar/velodyne/parser/calibration.cc:71-112

void operator>>(const YAML::Node& node,
                std::pair<int, LaserCorrection>& correction) {
  // 1. 读取基本参数
  node[LASER_ID] >> correction.first;
  node[ROT_CORRECTION] >> correction.second.rot_correction;
  node[VERT_CORRECTION] >> correction.second.vert_correction;
  node[DIST_CORRECTION] >> correction.second.dist_correction;
  node[DIST_CORRECTION_X] >> correction.second.dist_correction_x;
  node[DIST_CORRECTION_Y] >> correction.second.dist_correction_y;
  node[VERT_OFFSET_CORRECTION] >> correction.second.vert_offset_correction;

  // 2. 读取可选参数(带默认值)
  if (node[HORIZ_OFFSET_CORRECTION]) {
    node[HORIZ_OFFSET_CORRECTION] >> correction.second.horiz_offset_correction;
  } else {
    correction.second.horiz_offset_correction = 0.0;
  }

  if (node[MAX_INTENSITY]) {
    node[MAX_INTENSITY] >> correction.second.max_intensity;
  } else {
    correction.second.max_intensity = 255;
  }

  if (node[MIN_INTENSITY]) {
    node[MIN_INTENSITY] >> correction.second.min_intensity;
  } else {
    correction.second.min_intensity = 0;
  }

  node[FOCAL_DISTANCE] >> correction.second.focal_distance;
  node[FOCAL_SLOPE] >> correction.second.focal_slope;

  // 3. 计算缓存值(提升运行时性能)
  correction.second.cos_rot_correction = cosf(correction.second.rot_correction);
  correction.second.sin_rot_correction = sinf(correction.second.rot_correction);
  correction.second.cos_vert_correction = cosf(correction.second.vert_correction);
  correction.second.sin_vert_correction = sinf(correction.second.vert_correction);

  // 4. 计算焦点偏移
  correction.second.focal_offset =
      256.0f * static_cast<float>(std::pow(
                   1 - correction.second.focal_distance / 13100.0f, 2));

  correction.second.laser_ring = 0;  // 初始化环编号
}
2.1.4 激光环排序算法
cpp 复制代码
// 文件: modules/drivers/lidar/velodyne/parser/calibration.cc:136-157

// 按垂直角度从小到大排序,为每条激光分配ring编号
double next_angle = -std::numeric_limits<double>::infinity();

for (int ring = 0; ring < num_lasers; ++ring) {
  // 找到下一个最小的垂直角度
  double min_seen = std::numeric_limits<double>::infinity();
  int next_index = num_lasers;

  for (int j = 0; j < num_lasers; ++j) {
    double angle = calibration.laser_corrections_[j].vert_correction;

    // 寻找大于next_angle但小于当前最小值的角度
    if (next_angle < angle && angle < min_seen) {
      min_seen = angle;
      next_index = j;
    }
  }

  if (next_index < num_lasers) {
    // 为该激光分配ring编号
    calibration.laser_corrections_[next_index].laser_ring = ring;
    next_angle = min_seen;
  }
}

算法说明

  • 目的:按垂直角度从低到高为激光线束分配连续的ring编号
  • 复杂度:O(N²),N为激光线束数量
  • 结果:ring 0 = 最低角度,ring N-1 = 最高角度
2.1.5 VLP-16标定文件示例
yaml 复制代码
# 文件: modules/drivers/lidar/velodyne/params/VLP16_calibration.yaml
num_lasers: 16

lasers:
  # 激光0: 垂直角度 -15°
  - laser_id: 0
    rot_correction: 0.0
    vert_correction: -0.2617993877991494    # -15° in radians
    dist_correction: 0.0
    dist_correction_x: 0.0
    dist_correction_y: 0.0
    vert_offset_correction: 0.0
    horiz_offset_correction: 0.0
    focal_distance: 0.0
    focal_slope: 0.0
    min_intensity: 0
    max_intensity: 255

  # 激光1: 垂直角度 +1°
  - laser_id: 1
    rot_correction: 0.0
    vert_correction: 0.017453292519943295   # +1° in radians
    dist_correction: 0.0
    # ... 其他参数

  # ... 激光2-15

  # 激光15: 垂直角度 +15°
  - laser_id: 15
    rot_correction: 0.0
    vert_correction: 0.2617993877991494     # +15° in radians
    dist_correction: 0.0
    # ... 其他参数

VLP-16垂直角度分布

复制代码
Ring 15: +15°  ─┐
Ring 13: +13°   │
Ring 11: +11°   │
Ring  9: +9°    │ 上半球
Ring  7: +7°    │
Ring  5: +5°    │
Ring  3: +3°    │
Ring  1: +1°   ─┤ 水平线
Ring  0: -1°   ─┤
Ring  2: -3°    │
Ring  4: -5°    │
Ring  6: -7°    │ 下半球
Ring  8: -9°    │
Ring 10: -11°   │
Ring 12: -13°   │
Ring 14: -15°  ─┘

2.2 激光雷达外参标定

外参标定定义了激光雷达相对于车辆坐标系或其他传感器的位置和姿态。

2.2.1 外参数据格式
yaml 复制代码
# 文件: modules/calibration/data/mkz_121/lidar_params/velodyne64_novatel_extrinsics.yaml

header:
  seq: 0
  frame_id: novatel           # 参考坐标系(GNSS/INS)
  stamp:
    secs: 0
    nsecs: 0

child_frame_id: velodyne64    # 子坐标系(激光雷达)

transform:
  # 旋转部分(四元数表示)
  rotation:
    w: 0.9999619230641713     # 四元数实部
    x: 0.006948662107438382   # 四元数虚部x
    y: -0.002807286701094224  # 四元数虚部y
    z: 0.004812271181365884   # 四元数虚部z

  # 平移部分(米)
  translation:
    x: 0.0                    # X轴偏移
    y: 0.0                    # Y轴偏移
    z: 1.5                    # Z轴偏移(激光雷达高度)

坐标变换公式

设激光雷达坐标系中的点为 Plidar=[xl,yl,zl]TP_{lidar} = [x_l, y_l, z_l]^TPlidar=[xl,yl,zl]T,车体坐标系中的点为 PvehicleP_{vehicle}Pvehicle,则:

Pvehicle=R⋅Plidar+T P_{vehicle} = R \cdot P_{lidar} + T Pvehicle=R⋅Plidar+T

其中:

  • RRR:旋转矩阵(由四元数转换而来)
  • TTT:平移向量 [tx,ty,tz]T[t_x, t_y, t_z]^T[tx,ty,tz]T

四元数转旋转矩阵

R=[1−2(y2+z2)2(xy−wz)2(xz+wy)2(xy+wz)1−2(x2+z2)2(yz−wx)2(xz−wy)2(yz+wx)1−2(x2+y2)] R = \begin{bmatrix} 1-2(y^2+z^2) & 2(xy-wz) & 2(xz+wy) \\ 2(xy+wz) & 1-2(x^2+z^2) & 2(yz-wx) \\ 2(xz-wy) & 2(yz+wx) & 1-2(x^2+y^2) \end{bmatrix} R= 1−2(y2+z2)2(xy+wz)2(xz−wy)2(xy−wz)1−2(x2+z2)2(yz+wx)2(xz+wy)2(yz−wx)1−2(x2+y2)

2.2.2 外参标定方法

方法1:手动测量法

  1. 使用卷尺和水平仪测量激光雷达相对于车辆参考点的位置
  2. 使用角度测量工具测量旋转角度
  3. 手动填写标定文件

优点 :简单快速
缺点:精度低(误差±5cm)

方法2:自动标定法(ICP配准)

  1. 采集包含明显特征的场景(建筑物、标志牌)
  2. 使用ICP(Iterative Closest Point)算法配准点云
  3. 优化旋转和平移参数
  4. 自动生成标定文件

优点 :精度高(误差±1cm)
缺点:需要特殊场景和计算资源

2.3 在线标定

在线标定允许激光雷达在运行时从数据流中提取标定参数。

2.3.1 OnlineCalibration类
cpp 复制代码
// 文件: modules/drivers/lidar/velodyne/parser/online_calibration.h

class OnlineCalibration {
 public:
  OnlineCalibration() = default;

  // 从Velodyne数据包中提取标定信息
  bool decode(const velodyne_msgs::VelodynePacket& pkt);

  // 获取标定结果
  Calibration getCalibration() const { return calibration_; }

  bool isCalibrated() const { return calibrated_; }

 private:
  Calibration calibration_;
  bool calibrated_ = false;

  // 解析HDL-64E S2/S3的标定数据
  void parseHDL64Calibration(const uint8_t* data);

  // 解析VLP-16的标定数据
  void parseVLP16Calibration(const uint8_t* data);
};

工作原理

  1. Velodyne激光雷达在每次旋转周期会发送标定数据包
  2. 标定数据包嵌入在正常数据流中
  3. 解析器自动识别并提取标定参数
  4. 更新内部标定对象

优势

  • 无需手动加载标定文件
  • 自动适应激光雷达型号
  • 实时更新标定参数(支持热插拔)

3. 相机标定

3.1 相机内参标定

相机内参描述了相机的光学特性和成像模型。

3.1.1 针孔相机模型

标准针孔模型

uv1\]=K\[X/ZY/Z1\] \\begin{bmatrix} u \\\\ v \\\\ 1 \\end{bmatrix} = K \\begin{bmatrix} X/Z \\\\ Y/Z \\\\ 1 \\end{bmatrix} uv1 =K X/ZY/Z1 其中,KKK 为相机内参矩阵: K=\[fx0cx0fycy001\] K = \\begin{bmatrix} f_x \& 0 \& c_x \\\\ 0 \& f_y \& c_y \\\\ 0 \& 0 \& 1 \\end{bmatrix} K= fx000fy0cxcy1 参数说明: * fx,fyf_x, f_yfx,fy:X和Y方向的焦距(像素单位) * cx,cyc_x, c_ycx,cy:主点坐标(光轴与图像平面交点) * (u,v)(u, v)(u,v):图像像素坐标 * (X,Y,Z)(X, Y, Z)(X,Y,Z):相机坐标系中的3D点坐标 ##### 3.1.2 畸变模型 实际镜头存在畸变,需要建模和校正。 **径向畸变(Radial Distortion)**: xdistorted=x(1+k1r2+k2r4+k3r6+k4r8)ydistorted=y(1+k1r2+k2r4+k3r6+k4r8) \\begin{aligned} x_{distorted} \&= x(1 + k_1 r\^2 + k_2 r\^4 + k_3 r\^6 + k_4 r\^8) \\\\ y_{distorted} \&= y(1 + k_1 r\^2 + k_2 r\^4 + k_3 r\^6 + k_4 r\^8) \\end{aligned} xdistortedydistorted=x(1+k1r2+k2r4+k3r6+k4r8)=y(1+k1r2+k2r4+k3r6+k4r8) 其中 r2=x2+y2r\^2 = x\^2 + y\^2r2=x2+y2 **切向畸变(Tangential Distortion)**: xdistorted=x+\[2p1xy+p2(r2+2x2)\]ydistorted=y+\[p1(r2+2y2)+2p2xy\] \\begin{aligned} x_{distorted} \&= x + \[2p_1 xy + p_2(r\^2 + 2x\^2)\] \\\\ y_{distorted} \&= y + \[p_1(r\^2 + 2y\^2) + 2p_2 xy\] \\end{aligned} xdistortedydistorted=x+\[2p1xy+p2(r2+2x2)\]=y+\[p1(r2+2y2)+2p2xy

完整畸变模型

Apollo使用8参数畸变模型(plumb_bob):

D=[k1,k2,p1,p2,k3,k4,k5,k6] D = [k_1, k_2, p_1, p_2, k_3, k_4, k_5, k_6] D=[k1,k2,p1,p2,k3,k4,k5,k6]

  • k1,k2,k3,k4,k5,k6k_1, k_2, k_3, k_4, k_5, k_6k1,k2,k3,k4,k5,k6:径向畸变系数
  • p1,p2p_1, p_2p1,p2:切向畸变系数
3.1.3 相机内参文件示例
yaml 复制代码
# 文件: modules/calibration/data/mkz_121/camera_params/front_6mm_intrinsics.yaml

header:
  seq: 0
  stamp:
    secs: 0
    nsecs: 0
  frame_id: front_6mm          # 相机标识

# 图像尺寸
height: 1080                   # 图像高度(像素)
width: 1920                    # 图像宽度(像素)

# 畸变模型类型
distortion_model: plumb_bob    # 8参数畸变模型

# 畸变系数 [k1, k2, p1, p2, k3, k4, k5, k6]
D: [-0.544499, 0.276915, -0.001540, 0.005511, 0.0, 0.0, 0.0, 0.0]

# 内参矩阵 K (3x3,按行展开)
# K = [fx  0  cx]
#     [ 0 fy  cy]
#     [ 0  0   1]
K: [1992.669891, 0.0, 937.768962,
    0.0, 1990.404142, 453.083499,
    0.0, 0.0, 1.0]

# 整流矩阵 R (3x3,用于双目相机)
R: [1.0, 0.0, 0.0,
    0.0, 1.0, 0.0,
    0.0, 0.0, 1.0]

# 投影矩阵 P (3x4)
# P = [fx' 0  cx' Tx]
#     [ 0 fy' cy' Ty]
#     [ 0  0   1   0]
P: [1703.447510, 0.0, 943.254273, 0.0,
    0.0, 1896.693115, 444.134985, 0.0,
    0.0, 0.0, 1.0, 0.0]

# 图像分块参数
binning_x: 0
binning_y: 0

# 感兴趣区域(ROI)
roi:
  x_offset: 0
  y_offset: 0
  height: 0
  width: 0
  do_rectify: False

参数解释

  1. 内参矩阵K

    • fx=1992.67f_x = 1992.67fx=1992.67:X方向焦距(像素)
    • fy=1990.40f_y = 1990.40fy=1990.40:Y方向焦距(像素)
    • cx=937.77c_x = 937.77cx=937.77:主点X坐标(图像中心附近)
    • cy=453.08c_y = 453.08cy=453.08:主点Y坐标
  2. 畸变系数D

    • k1=−0.544499k_1 = -0.544499k1=−0.544499:强桶形畸变(负值)
    • k2=0.276915k_2 = 0.276915k2=0.276915:高阶校正
    • p1=−0.001540p_1 = -0.001540p1=−0.001540:切向畸变(X方向)
    • p2=0.005511p_2 = 0.005511p2=0.005511:切向畸变(Y方向)
  3. 投影矩阵P

    • 校正后的内参矩阵
    • 用于去畸变后的图像投影
3.1.4 内参标定方法

方法1:张正友标定法(棋盘格)

  1. 准备工作

    • 打印黑白棋盘格标定板(例如:9x6格,每格50mm)
    • 确保标定板平整
  2. 数据采集

    • 从不同角度和距离拍摄标定板(20-30张图像)
    • 覆盖图像的所有区域
    • 确保标定板在图像中清晰可见
  3. 角点检测

    python 复制代码
    import cv2
    # 检测棋盘格角点
    ret, corners = cv2.findChessboardCorners(gray, (9, 6), None)
  4. 标定计算

    python 复制代码
    # 使用OpenCV标定
    ret, K, D, rvecs, tvecs = cv2.calibrateCamera(
        object_points,   # 3D世界坐标
        image_points,    # 2D图像坐标
        image_size,      # 图像尺寸
        None, None
    )
  5. 结果评估

    • 重投影误差 < 0.5 pixel:优秀
    • 重投影误差 0.5-1.0 pixel:良好
    • 重投影误差 > 1.0 pixel:需要重新标定
3.1.5 张正友标定法完整算法推导

张正友标定法(Zhang's Calibration Method)是计算机视觉中最经典的相机标定算法,由微软研究院张正友博士于1998年提出。

数学模型:

世界坐标系中的3D点 M=[X,Y,Z]TM = [X, Y, Z]^TM=[X,Y,Z]T 投影到图像坐标系的2D点 m=[u,v]Tm = [u, v]^Tm=[u,v]T:

s[uv1]=K[R∣t][XYZ1] s \begin{bmatrix} u \\ v \\ 1 \end{bmatrix} = K [R | t] \begin{bmatrix} X \\ Y \\ Z \\ 1 \end{bmatrix} s uv1 =K[R∣t] XYZ1

其中:

  • KKK: 相机内参矩阵 3×33 \times 33×3
  • R∣t\]\[R \| t\]\[R∣t\]: 外参(旋转矩阵 + 平移向量) 3×43 \\times 43×4

算法核心思想 :

使用平面标定板(棋盘格),通过多个视角图像,先线性估计内参初值,再进行非线性优化。

步骤1: 单应性矩阵(Homography)估计

对于标定板上的平面点,假设 Z=0Z = 0Z=0(标定板在世界坐标系的XYXYXY平面),则:

s[uv1]=K[r1r2t][XY1]=H[XY1] s \begin{bmatrix} u \\ v \\ 1 \end{bmatrix} = K [r_1 \quad r_2 \quad t] \begin{bmatrix} X \\ Y \\ 1 \end{bmatrix} = H \begin{bmatrix} X \\ Y \\ 1 \end{bmatrix} s uv1 =K[r1r2t] XY1 =H XY1

其中 H=K[r1r2t]H = K [r_1 \quad r_2 \quad t]H=K[r1r2t] 是 3×33 \times 33×3 单应性矩阵,r1,r2r_1, r_2r1,r2 是旋转矩阵RRR的前两列。

使用DLT(直接线性变换)求解 HHH。对于每个点对 (Xi,Yi)↔(ui,vi)(X_i, Y_i) \leftrightarrow (u_i, v_i)(Xi,Yi)↔(ui,vi),有:

uivi1\]×H\[XiYi1\]=0 \\begin{bmatrix} u_i \\\\ v_i \\\\ 1 \\end{bmatrix} \\times H \\begin{bmatrix} X_i \\\\ Y_i \\\\ 1 \\end{bmatrix} = 0 uivi1 ×H XiYi1 =0 展开后得到2个线性方程(第3个方程线性相关): −Xih1T−Yih2T−h3T+ui(Xih7T+Yih8T+h9T)=0Xih1T+Yih2T+h3T⋅0−vi(Xih7T+Yih8T+h9T)=0 \\begin{aligned} -X_i h_1\^T - Y_i h_2\^T - h_3\^T + u_i(X_i h_7\^T + Y_i h_8\^T + h_9\^T) \&= 0 \\\\ X_i h_1\^T + Y_i h_2\^T + h_3\^T \\cdot 0 - v_i(X_i h_7\^T + Y_i h_8\^T + h_9\^T) \&= 0 \\end{aligned} −Xih1T−Yih2T−h3T+ui(Xih7T+Yih8T+h9T)Xih1T+Yih2T+h3T⋅0−vi(Xih7T+Yih8T+h9T)=0=0 其中 hiTh_i\^ThiT 是HHH矩阵的第iii个元素。 对于NNN个点,构建 2N×92N \\times 92N×9 的矩阵方程 Ah=0Ah = 0Ah=0,通过SVD分解求解最小奇异值对应的右奇异向量。 ```cpp // 文件: modules/perception/common/lib/calibrator/common/homography_estimator.cc // 从点对估计单应性矩阵 (DLT算法) bool EstimateHomography( const std::vector& src_points, // 世界坐标(X,Y) const std::vector& dst_points, // 图像坐标(u,v) Eigen::Matrix3d* H) { // 输出:单应性矩阵 const int n = src_points.size(); if (n < 4) return false; // 至少需要4个点 // 1. 数据归一化(提高数值稳定性) Eigen::Matrix3d T_src, T_dst; std::vector src_normalized, dst_normalized; NormalizePoints(src_points, &src_normalized, &T_src); NormalizePoints(dst_points, &dst_normalized, &T_dst); // 2. 构建约束矩阵 A (2n x 9) Eigen::MatrixXd A(2 * n, 9); for (int i = 0; i < n; ++i) { double X = src_normalized[i].x(); double Y = src_normalized[i].y(); double u = dst_normalized[i].x(); double v = dst_normalized[i].y(); // 第一个方程: -X -Y -1 0 0 0 uX uY u A.row(2*i) << -X, -Y, -1, 0, 0, 0, u*X, u*Y, u; // 第二个方程: 0 0 0 -X -Y -1 vX vY v A.row(2*i+1) << 0, 0, 0, -X, -Y, -1, v*X, v*Y, v; } // 3. SVD分解求解 Ah = 0 Eigen::JacobiSVD svd(A, Eigen::ComputeFullV); Eigen::VectorXd h = svd.matrixV().col(8); // 最小奇异值对应的右奇异向量 // 4. 重塑为3x3矩阵 Eigen::Matrix3d H_normalized; H_normalized << h(0), h(1), h(2), h(3), h(4), h(5), h(6), h(7), h(8); // 5. 反归一化 *H = T_dst.inverse() * H_normalized * T_src; return true; } // 点归一化(将点平移到原点,缩放到[-1,1]范围) void NormalizePoints(const std::vector& points, std::vector* normalized_points, Eigen::Matrix3d* T) { // 计算质心 Eigen::Vector2d centroid(0, 0); for (const auto& pt : points) { centroid += pt; } centroid /= points.size(); // 计算平均距离 double mean_dist = 0.0; for (const auto& pt : points) { mean_dist += (pt - centroid).norm(); } mean_dist /= points.size(); // 归一化变换矩阵 double scale = std::sqrt(2.0) / mean_dist; *T << scale, 0, -scale * centroid.x(), 0, scale, -scale * centroid.y(), 0, 0, 1; // 应用变换 normalized_points->clear(); for (const auto& pt : points) { Eigen::Vector3d pt_homo(pt.x(), pt.y(), 1.0); Eigen::Vector3d pt_normalized = (*T) * pt_homo; normalized_points->emplace_back(pt_normalized.x(), pt_normalized.y()); } } ``` **步骤2: 内参矩阵初始估计** 利用旋转矩阵的正交性约束条件: * r1Tr2=0r_1\^T r_2 = 0r1Tr2=0 (正交) * ∥r1∥=∥r2∥=1\\\|r_1\\\| = \\\|r_2\\\| = 1∥r1∥=∥r2∥=1 (单位长度) 设 H=\[h1h2h3\]=K\[r1r2t\]H = \[h_1 \\quad h_2 \\quad h_3\] = K \[r_1 \\quad r_2 \\quad t\]H=\[h1h2h3\]=K\[r1r2t\],则: r1=K−1h1r2=K−1h2 \\begin{aligned} r_1 \&= K\^{-1} h_1 \\\\ r_2 \&= K\^{-1} h_2 \\end{aligned} r1r2=K−1h1=K−1h2 代入正交性约束: h1TK−TK−1h2=0h1TK−TK−1h1=h2TK−TK−1h2 \\begin{aligned} h_1\^T K\^{-T} K\^{-1} h_2 \&= 0 \\\\ h_1\^T K\^{-T} K\^{-1} h_1 \&= h_2\^T K\^{-T} K\^{-1} h_2 \\end{aligned} h1TK−TK−1h2h1TK−TK−1h1=0=h2TK−TK−1h2 定义 B=K−TK−1B = K\^{-T} K\^{-1}B=K−TK−1 (对称矩阵,6个自由度): B=\[B11B12B13B12B22B23B13B23B33\]=\[1/fx20−cx/fx201/fy2−cy/fy2−cx/fx2−cy/fy2cx2/fx2+cy2/fy2+1\] B = \\begin{bmatrix} B_{11} \& B_{12} \& B_{13} \\\\ B_{12} \& B_{22} \& B_{23} \\\\ B_{13} \& B_{23} \& B_{33} \\end{bmatrix} = \\begin{bmatrix} 1/f_x\^2 \& 0 \& -c_x/f_x\^2 \\\\ 0 \& 1/f_y\^2 \& -c_y/f_y\^2 \\\\ -c_x/f_x\^2 \& -c_y/f_y\^2 \& c_x\^2/f_x\^2 + c_y\^2/f_y\^2 + 1 \\end{bmatrix} B= B11B12B13B12B22B23B13B23B33 = 1/fx20−cx/fx201/fy2−cy/fy2−cx/fx2−cy/fy2cx2/fx2+cy2/fy2+1 将 BBB 展开为6维向量 b=\[B11,B12,B22,B13,B23,B33\]Tb = \[B_{11}, B_{12}, B_{22}, B_{13}, B_{23}, B_{33}\]\^Tb=\[B11,B12,B22,B13,B23,B33\]T。 定义: vij=\[hi1hj1,hi1hj2+hi2hj1,hi2hj2,hi3hj1+hi1hj3,hi3hj2+hi2hj3,hi3hj3\]T v_{ij} = \[h_{i1} h_{j1}, h_{i1} h_{j2} + h_{i2} h_{j1}, h_{i2} h_{j2}, h_{i3} h_{j1} + h_{i1} h_{j3}, h_{i3} h_{j2} + h_{i2} h_{j3}, h_{i3} h_{j3}\]\^T vij=\[hi1hj1,hi1hj2+hi2hj1,hi2hj2,hi3hj1+hi1hj3,hi3hj2+hi2hj3,hi3hj3\]T 则约束方程可以写为: hiTBhj=vijTb h_i\^T B h_j = v_{ij}\^T b hiTBhj=vijTb 对于每张图像,有2个约束: \[v12T(v11−v22)T\]b=0 \\begin{bmatrix} v_{12}\^T \\\\ (v_{11} - v_{22})\^T \\end{bmatrix} b = 0 \[v12T(v11−v22)T\]b=0 NNN张图像提供 2N2N2N 个约束,至少需要3张图像(2N≥62N \\geq 62N≥6)。 ```cpp // 从多个单应性矩阵估计内参 bool EstimateIntrinsicFromHomographies( const std::vector& homographies, Eigen::Matrix3d* K) { const int n = homographies.size(); if (n < 3) return false; // 至少需要3张图像 // 1. 构建约束矩阵 V (2n x 6) Eigen::MatrixXd V(2 * n, 6); for (int i = 0; i < n; ++i) { const Eigen::Matrix3d& H = homographies[i]; // 提取列向量 Eigen::Vector3d h1 = H.col(0); Eigen::Vector3d h2 = H.col(1); // 计算 v_12 Eigen::VectorXd v12(6); v12 << h1(0)*h2(0), h1(0)*h2(1) + h1(1)*h2(0), h1(1)*h2(1), h1(2)*h2(0) + h1(0)*h2(2), h1(2)*h2(1) + h1(1)*h2(2), h1(2)*h2(2); // 计算 v_11 - v_22 Eigen::VectorXd v11(6); v11 << h1(0)*h1(0), h1(0)*h1(1) + h1(1)*h1(0), h1(1)*h1(1), h1(2)*h1(0) + h1(0)*h1(2), h1(2)*h1(1) + h1(1)*h1(2), h1(2)*h1(2); Eigen::VectorXd v22(6); v22 << h2(0)*h2(0), h2(0)*h2(1) + h2(1)*h2(0), h2(1)*h2(1), h2(2)*h2(0) + h2(0)*h2(2), h2(2)*h2(1) + h2(1)*h2(2), h2(2)*h2(2); V.row(2*i) = v12.transpose(); V.row(2*i+1) = (v11 - v22).transpose(); } // 2. SVD分解求解 Vb = 0 Eigen::JacobiSVD svd(V, Eigen::ComputeFullV); Eigen::VectorXd b = svd.matrixV().col(5); // 最小奇异值对应的向量 // 3. 从 b 恢复内参矩阵 // b = [B11, B12, B22, B13, B23, B33]^T double B11 = b(0); double B12 = b(1); double B22 = b(2); double B13 = b(3); double B23 = b(4); double B33 = b(5); // Cholesky分解恢复K: B = K^{-T} K^{-1} // 根据 B 的结构推导内参 double v0 = (B12*B13 - B11*B23) / (B11*B22 - B12*B12); double lambda = B33 - (B13*B13 + v0*(B12*B13 - B11*B23)) / B11; double fx = std::sqrt(lambda / B11); double fy = std::sqrt(lambda * B11 / (B11*B22 - B12*B12)); double skew = -B12 * fx * fx * fy / lambda; // 通常接近0 double u0 = skew * v0 / fy - B13 * fx * fx / lambda; // 构建内参矩阵 *K << fx, skew, u0, 0, fy, v0, 0, 0, 1; // 验证: K^{-T} K^{-1} 应该等于 B Eigen::Matrix3d K_inv = K->inverse(); Eigen::Matrix3d B_check = K_inv.transpose() * K_inv; AINFO << "B矩阵验证误差: " << (B_check - Eigen::Matrix3d({{B11,B12,B13},{B12,B22,B23},{B13,B23,B33}})).norm(); return true; } ``` **步骤3: 外参估计** 已知 H=K\[r1r2t\]H = K \[r_1 \\quad r_2 \\quad t\]H=K\[r1r2t\] 和 KKK,恢复外参: λ=1/∥K−1h1∥r1=λK−1h1r2=λK−1h2r3=r1×r2t=λK−1h3 \\begin{aligned} \\lambda \&= 1 / \\\|K\^{-1} h_1\\\| \\\\ r_1 \&= \\lambda K\^{-1} h_1 \\\\ r_2 \&= \\lambda K\^{-1} h_2 \\\\ r_3 \&= r_1 \\times r_2 \\\\ t \&= \\lambda K\^{-1} h_3 \\end{aligned} λr1r2r3t=1/∥K−1h1∥=λK−1h1=λK−1h2=r1×r2=λK−1h3 由于噪声存在,\[r1r2r3\]\[r_1 \\quad r_2 \\quad r_3\]\[r1r2r3\] 可能不是严格的旋转矩阵(不正交),需要投影到SO(3)流形: ```cpp // 从单应性矩阵和内参恢复外参 void EstimateExtrinsicFromHomography( const Eigen::Matrix3d& H, const Eigen::Matrix3d& K, Eigen::Matrix3d* R, Eigen::Vector3d* t) { Eigen::Matrix3d K_inv = K.inverse(); // 提取列向量 Eigen::Vector3d h1 = H.col(0); Eigen::Vector3d h2 = H.col(1); Eigen::Vector3d h3 = H.col(2); // 计算缩放因子 (由于 ||r1|| = 1) double lambda = 1.0 / (K_inv * h1).norm(); // 恢复旋转矩阵和平移向量 Eigen::Vector3d r1 = lambda * K_inv * h1; Eigen::Vector3d r2 = lambda * K_inv * h2; Eigen::Vector3d r3 = r1.cross(r2); // 叉乘保证正交 *t = lambda * K_inv * h3; // 组装旋转矩阵 (可能由于噪声不是严格正交) Eigen::Matrix3d R_approx; R_approx << r1, r2, r3; // 使用SVD投影到SO(3) (最近的正交矩阵) Eigen::JacobiSVD svd(R_approx, Eigen::ComputeFullU | Eigen::ComputeFullV); *R = svd.matrixU() * svd.matrixV().transpose(); // 确保行列式为+1 (旋转而非镜像) if (R->determinant() < 0) { *R = -(*R); *t = -(*t); } } ``` **步骤4: 畸变系数估计与非线性优化** 考虑径向畸变和切向畸变,真实像素坐标 (u\^,v\^)(\\hat{u}, \\hat{v})(u\^,v\^) 与理想像素坐标 (u,v)(u, v)(u,v) 的关系: r2=(u−cxfx)2+(v−cyfy)2u\^=u+(u−cx)\[k1r2+k2r4+k3r6\]+\[2p1(u−cx)(v−cy)+p2(r2+2(u−cx)2)\]v\^=v+(v−cy)\[k1r2+k2r4+k3r6\]+\[p1(r2+2(v−cy)2)+2p2(u−cx)(v−cy)\] \\begin{aligned} r\^2 \&= \\left(\\frac{u - c_x}{f_x}\\right)\^2 + \\left(\\frac{v - c_y}{f_y}\\right)\^2 \\\\ \\hat{u} \&= u + (u - c_x)\[k_1 r\^2 + k_2 r\^4 + k_3 r\^6\] + \[2p_1(u-c_x)(v-c_y) + p_2(r\^2 + 2(u-c_x)\^2)\] \\\\ \\hat{v} \&= v + (v - c_y)\[k_1 r\^2 + k_2 r\^4 + k_3 r\^6\] + \[p_1(r\^2 + 2(v-c_y)\^2) + 2p_2(u-c_x)(v-c_y)\] \\end{aligned} r2u\^v\^=(fxu−cx)2+(fyv−cy)2=u+(u−cx)\[k1r2+k2r4+k3r6\]+\[2p1(u−cx)(v−cy)+p2(r2+2(u−cx)2)\]=v+(v−cy)\[k1r2+k2r4+k3r6\]+\[p1(r2+2(v−cy)2)+2p2(u−cx)(v−cy)

使用Levenberg-Marquardt算法最小化重投影误差:

min⁡K,D,{Ri,ti}∑i=1N∑j=1M∥mij−m^(Mj,K,D,Ri,ti)∥2 \min_{K, D, \{R_i, t_i\}} \sum_{i=1}^{N} \sum_{j=1}^{M} \| m_{ij} - \hat{m}(M_j, K, D, R_i, t_i) \|^2 K,D,{Ri,ti}mini=1∑Nj=1∑M∥mij−m^(Mj,K,D,Ri,ti)∥2

其中:

  • NNN: 图像数量
  • MMM: 每张图像的角点数量
  • mijm_{ij}mij: 观测到的2D像素坐标
  • m^\hat{m}m^: 重投影的2D坐标

Apollo使用Ceres Solver进行优化:

cpp 复制代码
// 使用Ceres Solver优化所有参数

void RefineAllParameters(
    const std::vector<std::vector<Eigen::Vector3d>>& object_points,  // N张图像,每张M个3D点
    const std::vector<std::vector<Eigen::Vector2d>>& image_points,   // N张图像,每张M个2D点
    Eigen::Matrix3d* K,
    std::vector<Eigen::Matrix3d>* rotations,
    std::vector<Eigen::Vector3d>* translations,
    Eigen::VectorXd* distortion_coeffs) {  // [k1, k2, p1, p2, k3]

  const int num_images = object_points.size();

  // 初始化畸变系数为0
  *distortion_coeffs = Eigen::VectorXd::Zero(5);

  // 创建Ceres问题
  ceres::Problem problem;

  // 参数块1: 内参 [fx, fy, cx, cy]
  double intrinsics[4] = {(*K)(0,0), (*K)(1,1), (*K)(0,2), (*K)(1,2)};
  problem.AddParameterBlock(intrinsics, 4);

  // 参数块2: 畸变系数 [k1, k2, p1, p2, k3]
  double distortion[5] = {0, 0, 0, 0, 0};
  problem.AddParameterBlock(distortion, 5);

  // 参数块3: 每张图像的外参 [rx, ry, rz, tx, ty, tz]
  std::vector<double*> extrinsics_data(num_images);
  for (int i = 0; i < num_images; ++i) {
    double* extrinsic = new double[6];

    // 旋转矩阵转旋转向量 (Rodrigues公式)
    Eigen::AngleAxisd angle_axis((*rotations)[i]);
    Eigen::Vector3d rvec = angle_axis.angle() * angle_axis.axis();
    extrinsic[0] = rvec(0);
    extrinsic[1] = rvec(1);
    extrinsic[2] = rvec(2);
    extrinsic[3] = (*translations)[i](0);
    extrinsic[4] = (*translations)[i](1);
    extrinsic[5] = (*translations)[i](2);

    extrinsics_data[i] = extrinsic;
    problem.AddParameterBlock(extrinsic, 6);
  }

  // 添加重投影误差残差
  for (int i = 0; i < num_images; ++i) {
    const auto& obj_pts = object_points[i];
    const auto& img_pts = image_points[i];

    for (size_t j = 0; j < obj_pts.size(); ++j) {
      // 创建代价函数
      ceres::CostFunction* cost_function =
          ReprojectionError::Create(obj_pts[j], img_pts[j]);

      problem.AddResidualBlock(cost_function,
                               new ceres::HuberLoss(1.0),  // 鲁棒损失函数(抑制离群点)
                               intrinsics,
                               distortion,
                               extrinsics_data[i]);
    }
  }

  // 配置求解器
  ceres::Solver::Options options;
  options.linear_solver_type = ceres::SPARSE_SCHUR;  // 适合BA问题
  options.minimizer_progress_to_stdout = false;
  options.max_num_iterations = 100;
  options.function_tolerance = 1e-6;
  options.parameter_tolerance = 1e-8;

  ceres::Solver::Summary summary;
  ceres::Solve(options, &problem, &summary);

  AINFO << summary.BriefReport();

  // 提取优化后的参数
  (*K)(0,0) = intrinsics[0];  // fx
  (*K)(1,1) = intrinsics[1];  // fy
  (*K)(0,2) = intrinsics[2];  // cx
  (*K)(1,2) = intrinsics[3];  // cy

  for (int i = 0; i < 5; ++i) {
    (*distortion_coeffs)(i) = distortion[i];
  }

  // 更新外参
  for (int i = 0; i < num_images; ++i) {
    Eigen::Vector3d rvec(extrinsics_data[i][0], extrinsics_data[i][1], extrinsics_data[i][2]);
    double theta = rvec.norm();
    if (theta < 1e-10) {
      (*rotations)[i] = Eigen::Matrix3d::Identity();
    } else {
      Eigen::Vector3d axis = rvec / theta;
      Eigen::AngleAxisd angle_axis(theta, axis);
      (*rotations)[i] = angle_axis.toRotationMatrix();
    }
    (*translations)[i] << extrinsics_data[i][3], extrinsics_data[i][4], extrinsics_data[i][5];
  }

  // 清理内存
  for (auto* ptr : extrinsics_data) {
    delete[] ptr;
  }
}

// 重投影误差代价函数
struct ReprojectionError {
  ReprojectionError(const Eigen::Vector3d& object_point,
                    const Eigen::Vector2d& image_point)
      : object_point_(object_point), image_point_(image_point) {}

  template <typename T>
  bool operator()(const T* const intrinsics,    // [fx, fy, cx, cy]
                  const T* const distortion,    // [k1, k2, p1, p2, k3]
                  const T* const extrinsic,     // [rx, ry, rz, tx, ty, tz]
                  T* residuals) const {

    // 1. 旋转和平移 (Rodrigues公式)
    T p[3];
    ceres::AngleAxisRotatePoint(extrinsic, object_point_.data(), p);
    p[0] += extrinsic[3];  // tx
    p[1] += extrinsic[4];  // ty
    p[2] += extrinsic[5];  // tz

    // 2. 投影到归一化平面
    T xn = p[0] / p[2];
    T yn = p[1] / p[2];

    // 3. 畸变校正
    T r2 = xn*xn + yn*yn;
    T r4 = r2 * r2;
    T r6 = r4 * r2;

    // 径向畸变
    T radial = T(1.0) + distortion[0]*r2 + distortion[1]*r4 + distortion[4]*r6;

    // 切向畸变
    T xd = xn * radial + T(2.0)*distortion[2]*xn*yn + distortion[3]*(r2 + T(2.0)*xn*xn);
    T yd = yn * radial + distortion[2]*(r2 + T(2.0)*yn*yn) + T(2.0)*distortion[3]*xn*yn;

    // 4. 投影到像素坐标
    T predicted_u = intrinsics[0] * xd + intrinsics[2];  // fx * xd + cx
    T predicted_v = intrinsics[1] * yd + intrinsics[3];  // fy * yd + cy

    // 5. 计算残差
    residuals[0] = predicted_u - T(image_point_.x());
    residuals[1] = predicted_v - T(image_point_.y());

    return true;
  }

  static ceres::CostFunction* Create(const Eigen::Vector3d& object_point,
                                      const Eigen::Vector2d& image_point) {
    return new ceres::AutoDiffCostFunction<ReprojectionError, 2, 4, 5, 6>(
        new ReprojectionError(object_point, image_point));
  }

 private:
  Eigen::Vector3d object_point_;
  Eigen::Vector2d image_point_;
};

完整标定流程封装:

cpp 复制代码
// 完整的张正友标定实现

class ZhangCalibration {
 public:
  struct CalibrationResult {
    Eigen::Matrix3d K;                        // 内参矩阵
    Eigen::VectorXd distortion_coeffs;        // 畸变系数 [k1,k2,p1,p2,k3]
    std::vector<Eigen::Matrix3d> rotations;   // 每张图像的旋转矩阵
    std::vector<Eigen::Vector3d> translations;// 每张图像的平移向量
    double rms_error;                         // RMS重投影误差
    std::vector<double> per_view_errors;      // 每张图像的误差
  };

  static bool Calibrate(
      const std::vector<std::vector<Eigen::Vector3d>>& object_points,
      const std::vector<std::vector<Eigen::Vector2d>>& image_points,
      const cv::Size& image_size,
      CalibrationResult* result) {

    const int num_images = object_points.size();
    if (num_images < 3) {
      AERROR << "至少需要3张标定图像,当前: " << num_images;
      return false;
    }

    AINFO << "======== 开始张正友标定 ========";
    AINFO << "图像数量: " << num_images;
    AINFO << "图像尺寸: " << image_size.width << "x" << image_size.height;

    // ========== 步骤1: 估计单应性矩阵 ==========
    AINFO << "步骤1: 估计单应性矩阵...";
    std::vector<Eigen::Matrix3d> homographies(num_images);

    for (int i = 0; i < num_images; ++i) {
      std::vector<Eigen::Vector2d> src_points, dst_points;

      // 提取标定板上的2D坐标(X,Y)
      for (const auto& pt : object_points[i]) {
        src_points.emplace_back(pt.x(), pt.y());
      }
      dst_points = image_points[i];

      if (!EstimateHomography(src_points, dst_points, &homographies[i])) {
        AERROR << "单应性矩阵估计失败: 图像 " << i;
        return false;
      }
    }
    AINFO << "单应性矩阵估计完成";

    // ========== 步骤2: 估计内参矩阵 ==========
    AINFO << "步骤2: 估计内参矩阵...";
    if (!EstimateIntrinsicFromHomographies(homographies, &result->K)) {
      AERROR << "内参矩阵估计失败";
      return false;
    }

    AINFO << "初始内参估计:\n" << result->K;
    AINFO << "  fx = " << result->K(0,0) << ", fy = " << result->K(1,1);
    AINFO << "  cx = " << result->K(0,2) << ", cy = " << result->K(1,2);

    // ========== 步骤3: 估计外参 ==========
    AINFO << "步骤3: 估计外参...";
    result->rotations.resize(num_images);
    result->translations.resize(num_images);

    for (int i = 0; i < num_images; ++i) {
      EstimateExtrinsicFromHomography(homographies[i],
                                      result->K,
                                      &result->rotations[i],
                                      &result->translations[i]);
    }
    AINFO << "外参估计完成";

    // ========== 步骤4: 非线性优化 ==========
    AINFO << "步骤4: 非线性优化...";
    RefineAllParameters(object_points,
                        image_points,
                        &result->K,
                        &result->rotations,
                        &result->translations,
                        &result->distortion_coeffs);

    AINFO << "优化后内参:\n" << result->K;
    AINFO << "  fx = " << result->K(0,0) << ", fy = " << result->K(1,1);
    AINFO << "  cx = " << result->K(0,2) << ", cy = " << result->K(1,2);
    AINFO << "畸变系数: " << result->distortion_coeffs.transpose();

    // ========== 步骤5: 计算重投影误差 ==========
    AINFO << "步骤5: 计算重投影误差...";
    double total_error = 0.0;
    int total_points = 0;
    result->per_view_errors.resize(num_images);

    for (int i = 0; i < num_images; ++i) {
      double view_error = 0.0;

      for (size_t j = 0; j < object_points[i].size(); ++j) {
        Eigen::Vector2d projected = ProjectPoint(object_points[i][j],
                                                 result->K,
                                                 result->rotations[i],
                                                 result->translations[i],
                                                 result->distortion_coeffs);

        double error = (projected - image_points[i][j]).norm();
        view_error += error * error;
        total_error += error * error;
        total_points++;
      }

      result->per_view_errors[i] = std::sqrt(view_error / object_points[i].size());
      AINFO << "  图像 " << i << " RMS误差: " << result->per_view_errors[i] << " pixels";
    }

    result->rms_error = std::sqrt(total_error / total_points);
    AINFO << "======== 标定完成 ========";
    AINFO << "总RMS重投影误差: " << result->rms_error << " pixels";

    // 评估标定质量
    if (result->rms_error < 0.3) {
      AINFO << "标定质量: 优秀";
    } else if (result->rms_error < 0.5) {
      AINFO << "标定质量: 良好";
    } else if (result->rms_error < 1.0) {
      AINFO << "标定质量: 一般";
    } else {
      AWARN << "标定质量: 较差,建议重新标定";
    }

    return true;
  }

 private:
  // 投影3D点到2D图像 (带畸变)
  static Eigen::Vector2d ProjectPoint(
      const Eigen::Vector3d& object_point,
      const Eigen::Matrix3d& K,
      const Eigen::Matrix3d& R,
      const Eigen::Vector3d& t,
      const Eigen::VectorXd& distortion) {

    // 1. 刚体变换
    Eigen::Vector3d p = R * object_point + t;

    // 2. 投影到归一化平面
    double xn = p.x() / p.z();
    double yn = p.y() / p.z();

    // 3. 畸变校正
    double r2 = xn*xn + yn*yn;
    double r4 = r2 * r2;
    double r6 = r4 * r2;

    double radial = 1.0 + distortion(0)*r2 + distortion(1)*r4 + distortion(4)*r6;
    double xd = xn * radial + 2.0*distortion(2)*xn*yn + distortion(3)*(r2 + 2.0*xn*xn);
    double yd = yn * radial + distortion(2)*(r2 + 2.0*yn*yn) + 2.0*distortion(3)*xn*yn;

    // 4. 投影到像素坐标
    double u = K(0,0) * xd + K(0,2);
    double v = K(1,1) * yd + K(1,2);

    return Eigen::Vector2d(u, v);
  }
};

性能指标:

指标 典型值 优秀值 说明
RMS重投影误差 < 1.0 pixel < 0.3 pixel 所有点的平均误差
标定图像数量 15-20张 25-30张 更多图像提高鲁棒性
角点检测成功率 > 95% > 99% 失败图像应剔除
标定时间 < 30秒 < 10秒 包含优化时间
焦距精度 ±5 pixels ±2 pixels fx, fy估计精度
主点精度 ±10 pixels ±3 pixels cx, cy估计精度

方法2:在线标定(基于场景特征)

  • 使用道路车道线、建筑物边缘等自然特征
  • 实时优化内参(见3.3节)

3.2 相机外参标定

外参标定定义了相机相对于其他传感器(通常是激光雷达)的位置和姿态。

3.2.1 外参文件示例
yaml 复制代码
# 文件: modules/calibration/data/mkz_121/camera_params/front_6mm_extrinsics.yaml

header:
  seq: 0
  frame_id: velodyne64        # 参考坐标系(激光雷达)
  stamp:
    nsecs: 0
    secs: 0

child_frame_id: front_6mm     # 子坐标系(相机)

transform:
  # 旋转(四元数)
  rotation:
    w: 0.5                    # 90°绕多个轴的复合旋转
    x: -0.5
    y: 0.5
    z: -0.5

  # 平移(米)
  translation:
    x: 0.67                   # 相机在激光雷达前方67cm
    y: -0.1                   # 相机在激光雷达左侧10cm
    z: -0.52                  # 相机在激光雷达下方52cm

坐标系约定

复制代码
Velodyne LiDAR坐标系:        Camera坐标系:
    z↑ (向上)                     z→ (光轴向前)
    |                             |
    |                            /
    |____→ x (向前)             x↓ (向下)
   /                            |
  y (向左)                      ←y (向左)

坐标变换

Pcamera=Rlidarcamera⋅Plidar+Tlidarcamera P_{camera} = R_{lidar}^{camera} \cdot P_{lidar} + T_{lidar}^{camera} Pcamera=Rlidarcamera⋅Plidar+Tlidarcamera

3.2.2 相机-激光雷达外参标定方法

方法1:标定板法

  1. 准备工作

    • 制作带有反光标记的标定板
    • 标定板在激光雷达和相机中都清晰可见
  2. 数据采集

    • 将标定板放置在不同位置(5-10个位置)
    • 同时采集相机图像和激光雷达点云
  3. 特征提取

    • 相机:提取标定板角点
    • 激光雷达:提取标定板平面点云
  4. 外参优化

    • 建立3D-3D对应关系
    • 使用ICP或PnP算法求解外参
    • 最小化重投影误差

方法2:自然特征法

  1. 采集数据

    • 在包含丰富几何特征的环境中采集数据
    • 例如:建筑物边缘、电线杆、路沿
  2. 特征匹配

    • 相机:提取图像边缘特征
    • 激光雷达:提取点云边缘特征
  3. 外参优化

    • 最大化相机特征与激光雷达特征的对齐程度
    • 迭代优化旋转和平移参数

3.3 基于车道线的在线标定

Apollo实现了基于车道线检测的相机俯仰角在线标定算法。

3.3.1 LaneBasedCalibrator类
cpp 复制代码
// 文件: modules/perception/common/lib/calibrator/laneline/lane_based_calibrator.h:75-150

class LaneBasedCalibrator {
 public:
  static const int kMaxNrHistoryFrames = 1000;  // 最大历史帧数

  LaneBasedCalibrator() { vp_buffer_.clear(); }
  ~LaneBasedCalibrator() { ClearUp(); }

  // 初始化标定器
  void Init(const LocalCalibratorInitOptions& options,
            const CalibratorParams* params = nullptr);

  // 主函数:处理每一帧,返回是否得到有效估计
  bool Process(const EgoLane& lane,         // 车道线检测结果
               const float& velocity,        // 车辆速度
               const float& yaw_rate,        // 偏航角速率
               const float& time_diff);      // 时间差

  // 获取俯仰角估计
  float get_pitch_estimation() const { return pitch_estimation_; }

  // 获取消失点对应的图像行
  float get_vanishing_row() const { return vanishing_row_; }

 private:
  // 判断车辆是否直线行驶
  bool IsTravelingStraight(const float& vehicle_yaw_changed) const {
    float abs_yaw = static_cast<float>(fabs(vehicle_yaw_changed));
    return abs_yaw < params_.max_allowed_yaw_angle_in_radian;
  }

  // 从车道线计算消失点
  bool GetVanishingPoint(const EgoLane& lane, VanishingPoint* v_point);

  // 从消失点计算俯仰角
  bool GetPitchFromVanishingPoint(const VanishingPoint& vp, float* pitch) const;

  // 添加俯仰角到直方图
  bool AddPitchToHistogram(float pitch);

 private:
  int image_width_ = 0;
  int image_height_ = 0;
  float k_mat_[9] = {0};                    // 相机内参矩阵
  float pitch_cur_ = 0.0f;                  // 当前帧俯仰角
  float pitch_estimation_ = 0.0f;           // 俯仰角估计值
  float vanishing_row_ = 0.0f;              // 消失点行号
  float accumulated_straight_driving_in_meter_ = 0.0f;  // 累积直行距离

  HistogramEstimator pitch_histogram_;      // 俯仰角直方图估计器
  std::deque<VanishingPoint> vp_buffer_;    // 消失点缓冲区
  CalibratorParams params_;                 // 标定参数
};
3.3.2 标定器参数
cpp 复制代码
// 文件: lane_based_calibrator.h:38-64

struct CalibratorParams {
  int min_nr_pts_laneline;  // 车道线最少点数(默认:20)

  float sampling_lane_point_rate;  // 车道点采样率(默认:0.5)

  // 最大偏航角(弧度)
  float max_allowed_yaw_angle_in_radian;  // 默认:0.05(约3°)

  // 更新标定的最小距离(米)
  float min_distance_to_update_calibration_in_meter;  // 默认:50m

  // 需要的最小直行距离(米)
  float min_required_straight_driving_distance_in_meter;  // 默认:200m

  HistogramEstimatorParams hist_estimator_params;  // 直方图估计器参数
};

// 默认参数值
const float kYawRateDefault = 0.0f;            // 默认偏航角速率
const float kVelocityDefault = 8.333f;         // 默认速度 8.333 m/s (30 km/h)
const float kTimeDiffDefault = 0.067f;         // 默认时间差 0.067s (15FPS)
3.3.3 基于消失点的俯仰角估计原理

理论基础

在道路场景中,平行的车道线在图像中会交于一点,称为消失点(Vanishing Point)。消失点的位置与相机俯仰角密切相关。

算法流程

  1. 检测车道线

    • 使用车道线检测算法(见第二部分感知模块)
    • 获取左右车道线的像素坐标
  2. 计算消失点

    cpp 复制代码
    bool GetVanishingPoint(const EgoLane& lane, VanishingPoint* v_point) {
      // 1. 从左右车道线各选择两个点
      float line_seg_l[4];  // 左车道线段 [x1, y1, x2, y2]
      float line_seg_r[4];  // 右车道线段
    
      SelectTwoPointsFromLineForVanishingPoint(lane.left_line, line_seg_l);
      SelectTwoPointsFromLineForVanishingPoint(lane.right_line, line_seg_r);
    
      // 2. 计算两条线段的交点
      return GetIntersectionFromTwoLineSegments(line_seg_l, line_seg_r, v_point);
    }
  3. 从消失点推导俯仰角

    消失点在图像中的坐标为 (uv,vv)(u_v, v_v)(uv,vv),相机内参为 KKK,则:

    θpitch=arctan⁡(vv−cyfy) \theta_{pitch} = \arctan\left(\frac{v_v - c_y}{f_y}\right) θpitch=arctan(fyvv−cy)

    其中:

    • vvv_vvv:消失点的垂直坐标(行号)
    • cyc_ycy:相机主点Y坐标
    • fyf_yfy:Y方向焦距
    • θpitch\theta_{pitch}θpitch:俯仰角
  4. 直方图滤波

    cpp 复制代码
    bool AddPitchToHistogram(float pitch) {
      // 使用直方图估计器平滑俯仰角
      return pitch_histogram_.Push(pitch);
    }
    
    // 获取最终估计值
    pitch_estimation_ = pitch_histogram_.GetEstimation();
  5. 直线行驶判断

    cpp 复制代码
    bool is_straight = IsTravelingStraight(yaw_change);
    
    if (is_straight) {
      accumulated_straight_driving_in_meter_ += velocity * time_diff;
    } else {
      accumulated_straight_driving_in_meter_ = 0.0f;  // 重置
    }

更新条件

  • 车辆直线行驶(偏航角变化 < 3°)
  • 累积直行距离 > 200m
  • 车道线检测质量良好

优势

  • 无需人工干预
  • 实时更新
  • 适应路面颠簸和车辆老化导致的安装角度变化

4. GNSS/IMU标定

4.1 天线-IMU杆臂标定

杆臂(Leverarm):GNSS天线相位中心与IMU参考点之间的3D偏移向量。

4.1.1 杆臂标定文件
yaml 复制代码
# 文件: modules/calibration/data/mkz_121/gnss_params/ant_imu_leverarm.yaml

leverarm:
  primary:                      # 主天线
    offset:
      x: 0.0                    # X轴偏移(米)
      y: 0.6                    # Y轴偏移(米,天线在IMU左侧60cm)
      z: 1.3                    # Z轴偏移(米,天线在IMU上方1.3m)
    uncertainty:                # 不确定性
      x: 0.01                   # X轴不确定性(米)
      y: 0.01                   # Y轴不确定性
      z: 0.01                   # Z轴不确定性

  secondary:                    # 副天线(双天线系统)
    offset:
      x: 0.0
      y: -0.6                   # 副天线在IMU右侧60cm
      z: 1.3
    uncertainty:
      x: 0.01
      y: 0.01
      z: 0.01

作用

  1. 位置补偿:GNSS测量的是天线位置,需要转换到IMU位置
  2. 姿态辅助:双天线系统可以通过基线向量辅助姿态解算
  3. 精度提升:准确的杆臂参数可以提升定位精度至厘米级
4.1.2 杆臂标定方法

方法1:手动测量法

  1. 使用卷尺测量天线相位中心到IMU参考点的距离
  2. 注意:天线相位中心不是天线外壳中心,需查阅天线规格书
  3. 测量精度:±2cm

方法2:动态标定法

  1. 车辆在开阔场地以8字形行驶
  2. 记录GNSS位置和IMU姿态数据
  3. 使用优化算法自动求解杆臂参数
  4. 测量精度:±1cm

4.2 IMU外参标定

定义IMU相对于车体坐标系的安装角度。

yaml 复制代码
# 文件: modules/calibration/data/mkz_121/vehicle_params/vehicle_imu_extrinsics.yaml

header:
  seq: 0
  frame_id: imu               # IMU坐标系
  stamp:
    secs: 0
    nsecs: 0

child_frame_id: novatel       # GNSS/INS坐标系

transform:
  rotation:
    w: 1.0                    # 单位四元数(无旋转)
    x: 0.0
    y: 0.0
    z: 0.0
  translation:
    x: 0.0                    # IMU与GNSS/INS重合
    y: 0.0
    z: 0.0

标定方法

  1. 使用水平仪确保IMU安装水平
  2. 使用罗盘对齐IMU X轴与车辆前进方向
  3. 记录安装角度偏差
  4. 在定位算法中补偿角度偏差

5. 雷达标定

毫米波雷达主要用于远距离目标检测(100-200m),需要外参标定。

yaml 复制代码
# 文件: modules/calibration/data/mkz_121/radar_params/radar_front_extrinsics.yaml

header:
  seq: 0
  frame_id: novatel           # 参考坐标系
  stamp:
    secs: 0
    nsecs: 0

child_frame_id: radar_front   # 前向雷达

transform:
  rotation:
    w: 1.0                    # 雷达朝向车辆前方(无旋转)
    x: 0.0
    y: 0.0
    z: 0.0
  translation:
    x: 3.5                    # 雷达在车辆前保险杠(前方3.5m)
    y: 0.0                    # 居中安装
    z: 0.5                    # 高度0.5m

标定方法

  1. 手动测量雷达安装位置
  2. 使用角反射器测试雷达指向
  3. 验证雷达检测范围与配置一致

6. 车辆动力学标定

6.1 车辆参数

protobuf 复制代码
# 文件: modules/calibration/data/mkz_121/vehicle_param.pb.txt

vehicle_param {
  # 车辆基本尺寸
  brand: LINCOLN_MKZ
  wheelbase: 2.85                     # 轴距(米)
  front_edge_to_center: 3.89          # 前端到车辆中心距离
  back_edge_to_center: 1.04           # 后端到车辆中心距离
  left_edge_to_center: 1.055          # 左侧到中心距离
  right_edge_to_center: 1.055         # 右侧到中心距离

  # 车轮参数
  wheel_base: 2.85                    # 轴距(米)
  wheel_rolling_radius: 0.335         # 车轮滚动半径(米)

  # 转向参数
  max_steering_angle: 470.0           # 最大方向盘转角(度)
  steer_ratio: 16.0                   # 方向盘转角到车轮转角的比例

  # 动力学参数
  max_acceleration: 3.0               # 最大加速度(m/s²)
  max_deceleration: -6.0              # 最大减速度(m/s²)
  max_lateral_acc: 5.0                # 最大横向加速度(m/s²)

  # 控制延迟
  brake_deadzone: 0.1                 # 制动死区
  throttle_deadzone: 0.0              # 油门死区
}

6.2 控制标定表

protobuf 复制代码
# 文件: modules/control/proto/calibration_table.proto

message ControlCalibrationTable {
  // 速度-加速度-节流阀标定表
  repeated SpeedControlCalibrationTable speed_control_table = 1;

  // 转向标定表
  message SteerCalibration {
    optional double angle = 1;        # 方向盘角度
    optional double torque = 2;       # 转向力矩
  }
  repeated SteerCalibration steer_table = 2;
}

message SpeedControlCalibrationTable {
  optional double speed = 1;          # 车速(m/s)
  optional double acc = 2;            # 加速度(m/s²)
  optional double command = 3;        # 控制命令(0-100%)
}

标定表示例

速度(m/s) 期望加速度(m/s²) 油门命令(%) 制动命令(%)
0 0.5 15 0
5 0.5 20 0
10 0.5 25 0
15 0.5 30 0
0 -0.5 0 10
5 -0.5 0 15
10 -0.5 0 20

7. 在线标定服务

7.1 OnlineCalibrationService类

cpp 复制代码
// 文件: modules/perception/common/lib/calibration_service/online_calibration_service/
//       online_calibration_service.h:31-120

struct CameraStatus {
  float camera_ground_height = -1.f;                  // 相机离地高度
  float pitch_angle = 0.f;                            // 俯仰角
  float pitch_angle_diff = 0.f;                       // 俯仰角差值
  std::vector<double> k_matrix = {0.0, ..., 0.0};     // 内参矩阵(9个元素)
  std::vector<double> ground_plane = {0.0, ..., 0.0}; // 地面平面参数(4个)
};

class OnlineCalibrationService : public BaseCalibrationService {
 public:
  OnlineCalibrationService() = default;
  virtual ~OnlineCalibrationService() = default;

  // 初始化
  bool Init(const CalibrationServiceInitOptions& options) override;

  // 构建索引
  bool BuildIndex() override;

  // ========== 查询接口 ==========

  // 查询地面深度
  bool QueryDepthOnGroundPlane(int x, int y, double* depth) const override;

  // 查询地面3D点
  bool QueryPoint3dOnGroundPlane(int x, int y,
                                 Eigen::Vector3d* point3d) const override;

  // 查询地面平面参数 [n^T, d],满足 n^T * x + d = 0
  bool QueryGroundPlaneInCameraFrame(
      Eigen::Vector4d* plane_param) const override;

  // 查询相机高度和俯仰角
  bool QueryCameraToGroundHeightAndPitchAngle(float* height,
                                              float* pitch) const override;

  // 查询相机高度
  float QueryCameraToGroundHeight() const override {
    if (is_service_ready_) {
      auto iter = name_camera_status_map_.find(sensor_name_);
      return (iter->second).camera_ground_height;
    }
    return -1.f;
  }

  // 查询俯仰角
  float QueryPitchAngle() const override {
    if (is_service_ready_) {
      auto iter = name_camera_status_map_.find(sensor_name_);
      return (iter->second).pitch_angle;
    }
    return -1.f;
  }

  // ========== 更新接口 ==========

  // 使用标定器更新俯仰角
  void Update(CameraFrame* frame) override;

  // 设置相机高度和俯仰角
  void SetCameraHeightAndPitch(
      const std::map<std::string, float>& name_camera_ground_height_map,
      const std::map<std::string, float>& name_camera_pitch_angle_diff_map,
      const float& pitch_angle_master_sensor) override;

  std::string Name() const override { return "OnlineCalibrationService"; }

 private:
  bool is_service_ready_ = false;
  std::string sensor_name_ = "";
  std::string master_sensor_name_ = "";
  std::map<std::string, CameraStatus> name_camera_status_map_;
  std::shared_ptr<BaseCalibrator> calibrator_;
};

7.2 使用示例

cpp 复制代码
// 初始化在线标定服务
OnlineCalibrationService calibration_service;
CalibrationServiceInitOptions options;
options.sensor_name = "front_6mm";
calibration_service.Init(options);

// 每帧更新标定
void ProcessFrame(CameraFrame* frame) {
  // 1. 检测车道线
  DetectLaneLines(frame);

  // 2. 更新俯仰角估计
  calibration_service.Update(frame);

  // 3. 查询当前俯仰角
  float pitch = calibration_service.QueryPitchAngle();
  float height = calibration_service.QueryCameraToGroundHeight();

  AINFO << "Camera pitch: " << pitch << " rad, height: " << height << " m";

  // 4. 使用更新后的标定进行3D重建
  for (int x = 0; x < frame->width; ++x) {
    for (int y = frame->height / 2; y < frame->height; ++y) {
      Eigen::Vector3d point3d;
      if (calibration_service.QueryPoint3dOnGroundPlane(x, y, &point3d)) {
        // 使用3D点进行后续处理
      }
    }
  }
}

8. 标定工具链

8.1 传感器标定工具

位置:modules/tools/sensor_calibration/

8.1.1 数据提取工具

extract_data.py - 从bag文件提取标定数据

python 复制代码
# 用法示例
python extract_data.py \
    --config config/camera_to_lidar_sample_config.yaml \
    --bag_file /data/calibration_data.bag \
    --output_dir /data/extracted/

配置文件示例

yaml 复制代码
# config/camera_to_lidar_sample_config.yaml

# 标定任务类型
calibration_task: "camera_to_lidar"

# 传感器话题
sensors:
  camera:
    topic: "/apollo/sensor/camera/front_6mm/image"
    type: "image"
  lidar:
    topic: "/apollo/sensor/lidar64/PointCloud2"
    type: "pointcloud"
  gnss:
    topic: "/apollo/sensor/gnss/odometry"
    type: "odometry"

# 提取参数
extract_params:
  start_time: 0.0           # 开始时间(秒)
  duration: 120.0           # 提取时长(秒)
  frame_rate: 10.0          # 帧率(Hz)
  min_velocity: 2.0         # 最小速度(m/s)
  localization_status: 56   # 定位状态(56=RTK_FIXED)
8.1.2 数据有效性检查

sanity_check.py - 检查提取数据的完整性

python 复制代码
# 用法
python sanity_check.py \
    --config config/camera_to_lidar_sample_config.yaml \
    --data_dir /data/extracted/

检查项

  • 配置文件完整性
  • 数据文件存在性
  • 图像尺寸一致性
  • 点云点数合理性
  • 时间戳连续性
  • 定位状态有效性
8.1.3 自动配置生成器

configuration_yaml_generator.py - 自动生成标定配置

python 复制代码
# 生成相机-激光雷达标定配置
python configuration_yaml_generator.py \
    --sensor_type camera_to_lidar \
    --output config/my_camera_lidar_config.yaml

8.2 车辆标定工具

位置:modules/tools/vehicle_calibration/

8.2.1 数据采集器

data_collector.py - 采集车辆控制数据

python 复制代码
# 用法
python data_collector.py \
    --bag_file /data/vehicle_test.bag \
    --output_dir /data/vehicle_calib/

采集的数据

  • 车速(m/s)
  • 加速度(m/s²)
  • 油门命令(%)
  • 制动命令(%)
  • 方向盘角度(度)
  • 车轮转角(度)
8.2.2 数据预处理

preprocess.py - 预处理原始数据

python 复制代码
# 用法
python preprocess.py \
    --input_dir /data/vehicle_calib/ \
    --output_dir /data/vehicle_calib/preprocessed/

预处理步骤

  1. 数据对齐:同步不同传感器的时间戳
  2. 异常值过滤:剔除速度、加速度超出合理范围的数据
  3. 平滑滤波:使用滑动平均平滑噪声
  4. 数据分段:按加速、减速、转向分段
8.2.3 标定计算

process.py - 计算标定表

python 复制代码
# 用法
python process.py \
    --input_dir /data/vehicle_calib/preprocessed/ \
    --output_file /data/vehicle_calib/calibration_table.pb.txt

算法

  1. 对于每个速度区间(0-5, 5-10, 10-15 m/s...)
  2. 统计加速度与控制命令的关系
  3. 使用最小二乘法拟合响应曲线
  4. 生成查找表
8.2.4 结果可视化

plot_results.py - 绘制标定结果

python 复制代码
# 用法
python plot_results.py \
    --calibration_file /data/vehicle_calib/calibration_table.pb.txt \
    --output_dir /data/vehicle_calib/plots/

生成图表

  • 油门-加速度曲线
  • 制动-减速度曲线
  • 方向盘角度-车轮转角曲线
  • 标定前后对比

8.3 数据集转换工具

位置:modules/tools/adataset/

8.3.1 KITTI数据集转换

kitti/calibration_converter.py

python 复制代码
# 将KITTI标定格式转换为Apollo格式
python kitti/calibration_converter.py \
    --kitti_calib_dir /data/kitti/calib/ \
    --output_dir /apollo/modules/calibration/data/kitti_140/

KITTI标定文件格式

复制代码
# calib_cam_to_cam.txt
P_rect_00: 7.215377e+02 0.000000e+00 6.095593e+02 ...
P_rect_01: 7.215377e+02 0.000000e+00 6.095593e+02 ...
R_rect_00: 9.999239e-01 9.837760e-03 -7.445048e-03 ...
8.3.2 nuScenes数据集转换

nuscenes/calibration_converter.py

python 复制代码
# 转换nuScenes标定
python nuscenes/calibration_converter.py \
    --nuscenes_dir /data/nuscenes/ \
    --version v1.0-trainval \
    --output_dir /apollo/modules/calibration/data/nuscenes_165/

9. 标定流程与最佳实践

9.1 完整标定流程

复制代码
┌──────────────────────────────────────────────────────────┐
│                  阶段1:准备工作                          │
├──────────────────────────────────────────────────────────┤
│ 1. 确认传感器安装牢固                                     │
│ 2. 准备标定工具和设备(标定板、卷尺、水平仪等)           │
│ 3. 选择合适的标定场地(平坦、开阔、有丰富特征)           │
│ 4. 配置数据采集系统                                      │
└──────────────────────────────────────────────────────────┘
                          ↓
┌──────────────────────────────────────────────────────────┐
│                  阶段2:数据采集                          │
├──────────────────────────────────────────────────────────┤
│ 1. 启动所有传感器                                        │
│ 2. 确认定位状态(RTK Fixed, status=56)                  │
│ 3. 记录标定数据(bag文件)                               │
│    - 激光雷达标定:静态数据(1-2分钟)                    │
│    - 相机-激光雷达标定:包含标定板的多个角度              │
│    - 车辆标定:加速、减速、转向测试(5-10分钟)           │
│ 4. 验证数据质量                                          │
└──────────────────────────────────────────────────────────┘
                          ↓
┌──────────────────────────────────────────────────────────┐
│                  阶段3:数据处理                          │
├──────────────────────────────────────────────────────────┤
│ 1. 提取传感器数据(extract_data.py)                     │
│ 2. 数据有效性检查(sanity_check.py)                     │
│ 3. 预处理数据(滤波、对齐、分段)                        │
└──────────────────────────────────────────────────────────┘
                          ↓
┌──────────────────────────────────────────────────────────┐
│                  阶段4:标定计算                          │
├──────────────────────────────────────────────────────────┤
│ 1. 运行标定算法                                          │
│    - 相机内参:张正友标定法                              │
│    - 外参:ICP配准或PnP求解                              │
│    - 车辆标定:响应曲线拟合                              │
│ 2. 生成标定文件(YAML或Protobuf)                        │
└──────────────────────────────────────────────────────────┘
                          ↓
┌──────────────────────────────────────────────────────────┐
│                  阶段5:验证与部署                        │
├──────────────────────────────────────────────────────────┤
│ 1. 计算标定误差(重投影误差、配准误差)                  │
│ 2. 可视化标定结果                                        │
│ 3. 在实际场景中测试                                      │
│ 4. 部署到生产环境                                        │
│ 5. 定期检查和更新标定参数                                │
└──────────────────────────────────────────────────────────┘

9.2 最佳实践

9.2.1 激光雷达标定最佳实践

内参标定

  1. ✅ 使用厂商提供的官方标定文件
  2. ✅ 定期检查标定文件完整性(每月)
  3. ✅ 保存标定文件的多个备份
  4. ❌ 避免手动修改内参文件

外参标定

  1. ✅ 使用自动标定法(ICP)提高精度
  2. ✅ 在包含垂直和水平结构的场景中标定
  3. ✅ 标定后检查点云投影到图像的对齐程度
  4. ❌ 避免在动态场景中标定
  5. ❌ 避免在单一平面场景中标定
9.2.2 相机标定最佳实践

内参标定

  1. ✅ 使用大尺寸高质量棋盘格(A2或A1纸)
  2. ✅ 采集20-30张不同角度和距离的图像
  3. ✅ 覆盖图像的所有区域(中心和边角)
  4. ✅ 确保重投影误差 < 0.5 pixel
  5. ❌ 避免只在图像中心标定
  6. ❌ 避免棋盘格模糊或部分遮挡

外参标定

  1. ✅ 标定前确保相机内参准确
  2. ✅ 使用带反光标记的专用标定板
  3. ✅ 在标定板的5-10个不同位置采集数据
  4. ✅ 标定后验证:点云投影到图像,检查边缘对齐
  5. ❌ 避免标定板距离过远(> 20m)或过近(< 3m)
9.2.3 在线标定最佳实践
  1. ✅ 启用在线标定作为离线标定的补充
  2. ✅ 设置合理的更新阈值(直行距离、速度)
  3. ✅ 定期记录在线标定参数变化,监控趋势
  4. ✅ 在标定参数突变时报警
  5. ❌ 避免完全依赖在线标定
  6. ❌ 避免在复杂天气条件下过度信任在线标定
9.2.4 车辆标定最佳实践
  1. ✅ 在平坦、开阔的测试场地进行
  2. ✅ 采集多种速度区间的数据(0-30 km/h, 30-60 km/h等)
  3. ✅ 分别采集加速、减速、转向数据
  4. ✅ 每个速度区间采集至少10次重复测试
  5. ✅ 标定后在实际道路测试验证
  6. ❌ 避免在坡道或弯道上标定
  7. ❌ 避免在轮胎磨损严重时标定

9.3 标定频率建议

标定类型 初次标定 定期重新标定 触发条件
激光雷达内参 出厂时 不需要 硬件更换
激光雷达外参 安装后 每6个月 碰撞、重新安装
相机内参 安装后 每6个月 镜头更换、图像异常
相机外参 安装后 每3个月 碰撞、重新安装
在线标定 系统启动时 实时 车辆行驶
车辆标定 车辆交付时 每年 轮胎更换、悬挂调整

10. 标定数据格式

10.1 YAML格式标定文件

Apollo主要使用YAML格式存储标定参数。

10.1.1 YAML格式优势
  • ✅ 人类可读
  • ✅ 易于手动编辑和调试
  • ✅ 支持注释
  • ✅ 跨平台兼容
10.1.2 标准YAML结构
yaml 复制代码
# 相机内参示例
header:                     # 文件头
  seq: 0
  stamp:
    secs: 0
    nsecs: 0
  frame_id: camera_name

height: 1080                # 图像高度
width: 1920                 # 图像宽度
distortion_model: plumb_bob # 畸变模型

D: [k1, k2, p1, p2, k3, k4, k5, k6]  # 畸变系数
K: [fx, 0, cx, 0, fy, cy, 0, 0, 1]    # 内参矩阵(3x3)
R: [1, 0, 0, 0, 1, 0, 0, 0, 1]        # 整流矩阵(3x3)
P: [fx', 0, cx', Tx, 0, fy', cy', Ty, 0, 0, 1, 0]  # 投影矩阵(3x4)

10.2 Protobuf格式

Apollo也使用Protobuf文本格式(.pb.txt)存储车辆参数。

10.2.1 Protobuf格式优势
  • ✅ 类型安全
  • ✅ 自动验证
  • ✅ 易于与代码集成
  • ✅ 支持复杂嵌套结构
10.2.2 示例:车辆参数
protobuf 复制代码
# vehicle_param.pb.txt
vehicle_param {
  brand: LINCOLN_MKZ

  # 尺寸参数
  wheelbase: 2.85
  front_edge_to_center: 3.89
  back_edge_to_center: 1.04
  left_edge_to_center: 1.055
  right_edge_to_center: 1.055
  height: 1.48

  # 转向参数
  max_steering_angle: 470.0
  steer_ratio: 16.0
  min_turn_radius: 5.05

  # 动力学参数
  max_acceleration: 3.0
  max_deceleration: -6.0
  max_lateral_acc: 5.0

  # 刹车和油门
  brake {
    brake_deadzone: 0.1
    brake_offset: 0.0
  }

  throttle {
    throttle_deadzone: 0.0
    throttle_offset: 0.0
  }
}

10.3 坐标系约定

Apollo使用右手坐标系

10.3.1 车体坐标系(Vehicle Frame)
复制代码
      z↑ (向上)
       |
       |
       |____→ x (向前)
      /
     y (向左)
  • 原点:车辆后轴中心
  • X轴:指向车辆前方
  • Y轴:指向车辆左侧
  • Z轴:指向车辆上方
10.3.2 激光雷达坐标系(LiDAR Frame)
复制代码
      z↑ (向上)
       |
       |
       |____→ x (向前)
      /
     y (向左)
  • 原点:激光雷达旋转中心
  • 坐标轴:与车体坐标系平行
10.3.3 相机坐标系(Camera Frame)
复制代码
      z→ (光轴向前)
       /
      /
     x↓ (向下)
     |
     |
     ←y (向左)
  • 原点:相机光心
  • Z轴:光轴方向(向前)
  • X轴:图像向下方向
  • Y轴:图像向左方向

注意:相机坐标系与车体坐标系的X和Z轴互换!


11. 配置参数详解

11.1 激光雷达标定参数

yaml 复制代码
# LaserCorrection 参数详解

rot_correction: 0.0         # 旋转校正(弧度)
                            # 范围:-0.1 到 0.1
                            # 作用:补偿发射器安装角度误差

vert_correction: -0.2618    # 垂直角度校正(弧度)
                            # 范围:-π/2 到 π/2
                            # 作用:定义激光线束的垂直角度

dist_correction: 1.2        # 距离校正(米)
                            # 范围:0 到 2
                            # 作用:补偿测距系统误差

dist_correction_x: 1.3      # X轴距离校正(米)
dist_correction_y: 1.25     # Y轴距离校正(米)
                            # 作用:分轴距离补偿

vert_offset_correction: 0.02   # 垂直偏移(米)
                               # 范围:-0.1 到 0.1
                               # 作用:补偿发射器垂直位置误差

horiz_offset_correction: 0.01  # 水平偏移(米)
                               # 范围:-0.1 到 0.1
                               # 作用:补偿发射器水平位置误差

focal_distance: 18.2        # 焦点距离
                            # 范围:0 到 30
                            # 作用:近距离非线性校正

focal_slope: 1.25           # 焦点斜率
                            # 范围:0 到 3
                            # 作用:焦点校正斜率参数

min_intensity: 40           # 最小强度值
max_intensity: 255          # 最大强度值
                            # 作用:强度归一化范围

11.2 相机标定参数

yaml 复制代码
# 内参参数

K: [fx, 0, cx, 0, fy, cy, 0, 0, 1]
# fx: X方向焦距(像素)
#     典型值:1000-3000(取决于传感器尺寸和焦距)
#     计算:fx = F * width / sensor_width
# fy: Y方向焦距(像素)
#     通常 fy ≈ fx
# cx: 主点X坐标(像素)
#     典型值:width / 2 ± 50
# cy: 主点Y坐标(像素)
#     典型值:height / 2 ± 50

D: [k1, k2, p1, p2, k3, k4, k5, k6]
# k1, k2, k3, k4, k5, k6: 径向畸变系数
#     桶形畸变:k1 < 0(广角镜头常见)
#     枕形畸变:k1 > 0(长焦镜头常见)
#     典型值:k1 ∈ [-1, 0.5], k2 ∈ [-0.5, 0.5]
# p1, p2: 切向畸变系数
#     典型值:|p1|, |p2| < 0.01

11.3 在线标定参数

cpp 复制代码
// CalibratorParams 参数详解

min_nr_pts_laneline: 20
// 车道线最少点数
// 范围:10-50
// 说明:车道线点数少于此值时不进行标定

sampling_lane_point_rate: 0.5
// 车道点采样率
// 范围:0.1-1.0
// 说明:0.5表示采样50%的车道线点

max_allowed_yaw_angle_in_radian: 0.05
// 最大偏航角(弧度)
// 范围:0.01-0.1
// 说明:超过此角度视为转弯,不进行标定
// 0.05 rad ≈ 3°

min_distance_to_update_calibration_in_meter: 50.0
// 更新标定的最小距离(米)
// 范围:20-100
// 说明:直行距离超过此值才更新标定

min_required_straight_driving_distance_in_meter: 200.0
// 需要的最小直行距离(米)
// 范围:100-500
// 说明:累积直行距离超过此值才认为标定有效

11.4 参数调优指南

11.4.1 激光雷达参数调优
场景 参数 推荐值 说明
城市道路 dist_correction 1.0-1.5m 近距离测量多
高速公路 dist_correction 0.5-1.0m 远距离测量多
雨雪天气 min_intensity 60 提高阈值过滤噪声
晴朗天气 min_intensity 30 降低阈值增加点云密度
11.4.2 相机参数调优
场景 参数 推荐值 说明
广角镜头 k1 -0.5 到 -0.3 强桶形畸变
标准镜头 k1 -0.2 到 0.1 轻微畸变
长焦镜头 k1 0.1 到 0.3 枕形畸变
11.4.3 在线标定参数调优
场景 参数 推荐值 说明
高速公路 min_straight_distance 300m 长直道,要求更严格
城市道路 min_straight_distance 150m 直道短,适当放宽
高精度要求 max_yaw_angle 0.02 rad 严格的直行判断
快速收敛 max_yaw_angle 0.08 rad 放宽条件加快收敛

12. 故障排查与常见问题

12.1 激光雷达标定问题

问题1:点云扭曲或抖动

  • 原因

    • 旋转校正参数(rot_correction)不准确
    • 激光雷达安装不牢固
  • 解决方案

    1. 重新加载官方标定文件
    2. 检查激光雷达安装螺丝
    3. 使用在线标定自动提取参数

问题2:点云投影到图像错位

  • 原因

    • 外参标定不准确
    • 相机和激光雷达时间戳不同步
  • 解决方案

    1. 重新进行外参标定
    2. 检查传感器时间同步
    3. 可视化投影结果进行调试

12.2 相机标定问题

问题1:标定后图像畸变未校正

  • 原因

    • 畸变系数计算错误
    • 标定图像质量差
  • 解决方案

    1. 检查重投影误差(应 < 0.5 pixel)
    2. 增加标定图像数量和角度多样性
    3. 确保棋盘格在图像中清晰完整

问题2:在线标定俯仰角不收敛

  • 原因

    • 车道线检测质量差
    • 车辆未满足直行条件
    • 累积直行距离不足
  • 解决方案

    1. 检查车道线检测结果
    2. 在笔直道路上以恒定速度行驶200m以上
    3. 调低min_required_straight_driving_distance参数

12.3 系统集成问题

问题1:多传感器时间戳不对齐

  • 原因

    • 传感器未使用GPS时间同步
    • 计算机系统时间漂移
  • 解决方案

    1. 配置所有传感器使用GPS时间戳
    2. 启用NTP时间同步
    3. 检查CyberRT消息时间戳

问题2:标定参数加载失败

  • 原因

    • 标定文件路径错误
    • YAML格式错误
  • 解决方案

    1. 检查日志中的文件路径
    2. 使用YAML验证器检查格式
    3. 确保文件权限可读

13. 总结

13.1 标定模块核心要点

三层标定体系

  1. 内参标定:传感器自身物理特性(相机焦距、激光雷达角度)
  2. 外参标定:传感器之间相对位姿(相机-激光雷达、IMU-车体)
  3. 动力学标定:车辆控制响应特性(油门-加速度、方向盘-转角)

关键技术

  1. 激光雷达标定:YAML配置文件,支持在线从数据流提取
  2. 相机标定:张正友标定法(离线)+ 车道线消失点法(在线)
  3. 在线标定服务:实时更新相机俯仰角和地面高度
  4. 工具链完善:数据提取、验证、标定、可视化全流程工具

数据格式

  1. YAML格式:人类可读,适合手动编辑和调试
  2. Protobuf格式:类型安全,适合代码集成
  3. 标准化结构:ROS-compatible的header-transform结构

13.2 标定精度要求

传感器 参数类型 精度要求 典型误差来源
LiDAR 内参 < 1cm 温度漂移、老化
LiDAR 外参 < 2cm 安装误差、振动
Camera 内参 < 0.5 pixel 镜头畸变、温度
Camera 外参 < 2cm, < 1° 安装误差、车身变形
GNSS/IMU 杆臂 < 5cm 测量误差
Vehicle 动力学 < 5% 轮胎磨损、载重

附录

A. 支持的传感器型号

激光雷达

  • Velodyne: HDL-64E S2/S3, VLP-16, VLP-32C, VLS-128
  • LSLidar: CH16, CH32, CH64, CH64W, CH128, CH120
  • Hesai: Pandar系列(通过驱动适配)

相机

  • 工业相机:支持GenICam、GigE Vision标准
  • 消费级相机:USB3.0 UVC相机
  • 推荐分辨率:1920x1080或更高

GNSS/IMU

  • NovAtel: SPAN-CPT, PwrPak7
  • Xsens: MTi系列
  • 其他支持NMEA 0183协议的GNSS

雷达

  • Continental: ARS 408
  • Delphi: ESR系列
  • Bosch: MRR系列

B. 关键文件索引

文件路径 功能 行数范围
drivers/lidar/velodyne/parser/calibration.h 激光雷达标定类定义 1-87
drivers/lidar/velodyne/parser/calibration.cc 激光雷达标定实现 1-200+
perception/common/lib/calibrator/laneline/lane_based_calibrator.h 车道线标定器 1-150
perception/common/lib/calibration_service/online_calibration_service.h 在线标定服务 1-120
tools/sensor_calibration/extract_data.py 数据提取工具 -
tools/vehicle_calibration/process.py 车辆标定处理 -

C. 参考资料

  1. OpenCV Camera Calibrationhttps://docs.opencv.org/4.x/dc/dbb/tutorial_py_calibration.html
  2. ROS Camera Calibrationhttp://wiki.ros.org/camera_calibration
  3. Velodyne User Manualhttps://velodynelidar.com/support/manuals/
  4. Apollo Calibration Guidehttps://github.com/ApolloAuto/apollo/tree/master/docs/specs/Apollo_Sensor_Installation_Guide
  5. Zhang's Calibration Method:Z. Zhang, "A flexible new technique for camera calibration", IEEE TPAMI 2000

参考资料与引用

官方资源

  1. Apollo 官方 GitHub 仓库

    https://github.com/ApolloAuto/apollo

    • Apollo 开源项目主仓库,包含完整源代码
  2. Apollo 官方文档

    https://apollo.baidu.com/docs

    • 官方技术文档和开发指南
  3. Apollo 开发者社区

    https://apollo.baidu.com/community

    • 官方开发者论坛和技术交流平台

技术规范与标准

  1. ISO 26262 - 道路车辆功能安全标准

    https://www.iso.org/standard/68383.html

  2. ISO 21448 (SOTIF) - 预期功能安全标准

    https://www.iso.org/standard/77490.html

学术论文与技术资源

  1. CenterPoint: Center-based 3D Object Detection and Tracking

    Yin, T., Zhou, X., & Krähenbühl, P. (2021)

    https://arxiv.org/abs/2006.11275

  2. BEVFormer: Learning Bird's-Eye-View Representation from Multi-Camera Images

    Li, Z., et al. (2022)

    https://arxiv.org/abs/2203.17270

  3. OpenDRIVE 地图标准

    https://www.asam.net/standards/detail/opendrive/

开源工具与库

  1. Bazel 构建系统

    https://bazel.build/

  2. Fast-DDS (eProsima)

    https://www.eprosima.com/index.php/products-all/eprosima-fast-dds

  3. PROJ 坐标转换库

    https://proj.org/

  4. TensorRT 开发指南

    https://docs.nvidia.com/deeplearning/tensorrt/

  5. PCL 点云库文档

    https://pointclouds.org/

  6. IPOPT 优化求解器

    https://coin-or.github.io/Ipopt/

说明

本文档内容整理自上述官方资料、开源代码以及相关技术文档。所有代码示例和技术细节均基于 Apollo 10.0 版本。如需获取最新信息,请访问 Apollo 官方网站和 GitHub 仓库。

版权说明

Apollo® 是百度公司的注册商标。本文档为基于开源项目的非官方技术研究文档,仅供学习参考使用。

相关推荐
qq_317620315 小时前
05.Transform模块详解
apollo·transform
Coder个人博客4 天前
Apollo VehicleState 车辆状态模块接口调用流程图与源码分析
人工智能·自动驾驶·apollo
程序员龙一5 天前
百度Apollo Cyber RT底层原理解析
自动驾驶·ros·apollo·cyber rt
Coder个人博客8 天前
Apollo Canbus 底盘通信模块接口调用流程图与源码分析
人工智能·自动驾驶·apollo
Coder个人博客8 天前
Apollo Prediction 预测模块接口调用流程图与源码分析
人工智能·自动驾驶·apollo
johnny_hhh14 天前
apollo配置环境
apollo
Hi202402174 个月前
使用 Apollo TransformWrapper 生成相机到各坐标系的变换矩阵
数码相机·线性代数·矩阵·自动驾驶·apollo
Hi202402174 个月前
Orin-Apollo园区版本:订阅多个摄像头画面拼接与硬编码RTMP推流
ffmpeg·apollo·orin·图像拼接·图传
小庞在加油6 个月前
Apollo源码架构解析---附C++代码设计示例
开发语言·c++·架构·自动驾驶·apollo