利用利用Kalibr对相机和imu标定的详细完整过程
硬件配置信息
- 标定板: 9×7格棋盘格,每格15mm×15mm
- IMU话题:
/wit/imu
- 相机话题:
/camera/color/image_raw
- 标定工具: Kalibr
1. 环境准备
1.1 安装Kalibr
# 克隆Kalibr仓库
git clone https://github.com/ethz-asl/kalibr.git
cd kalibr
# 按照官方文档编译安装
# 注意:需要ROS环境
1.2 创建工作目录
mkdir ~/imu_camera_calibration
cd ~/imu_camera_calibration
2. 配置文件准备
2.1 创建标定板配置文件
创建文件 checkerboard.yaml
:
target_type: 'checkerboard'
targetCols: 8 # 9格-1 = 8个内部角点
targetRows: 6 # 7格-1 = 6个内部角点
rowSpacingMeters: 0.015 # 15mm
colSpacingMeters: 0.015 # 15mm
2.2 创建IMU配置文件
创建文件 imu.yaml
:
#IMU configuration for WIT sensor
accelerometer_noise_density: 2.0e-3 #[m/s^2/sqrt(Hz)]
accelerometer_random_walk: 3.0e-3 #[m/s^3/sqrt(Hz)]
gyroscope_noise_density: 1.6e-4 #[rad/s/sqrt(Hz)]
gyroscope_random_walk: 1.9e-5 #[rad/s^2/sqrt(Hz)]
rostopic: /wit/imu
update_rate: 200.0 #[Hz]
3. 数据采集准备
3.1 硬件布置
正确布置:
┌─────────────────┐
│ │
│ 标定板(固定) │ ← 贴在墙上或平放在桌面
│ │ 保持完全静止
└─────────────────┘
📱 ← 手持相机+IMU一起移动
(两者必须刚性固定)
关键点:
- ✅ 标定板固定不动
- ✅ 相机和IMU刚性连接,一起移动
- ✅ 光照充足且稳定
- ✅ 标定板平整无弯曲
3.2 系统检查
# 1. 检查ROS话题
rostopic list | grep -E "(camera|wit)"
# 2. 检查数据发布频率
rostopic hz /camera/color/image_raw
rostopic hz /wit/imu
# 3. 检查消息格式
rostopic type /camera/color/image_raw
rostopic type /wit/imu
# 4. 查看几条消息确认数据正常
rostopic echo /wit/imu -n 3
4. 数据采集
4.1 采集脚本
创建 collect_data.sh
:
#!/bin/bash
echo "========================================="
echo " IMU-相机标定数据采集"
echo "========================================="
echo "设备布置检查列表:"
echo " ☐ 标定板已固定在墙上/桌面"
echo " ☐ 相机和IMU刚性连接"
echo " ☐ 光照充足且稳定"
echo " ☐ 标定板完全可见且平整"
echo ""
echo "运动要求:"
echo " - 移动相机+IMU组合体,保持标定板静止"
echo " - 缓慢平滑运动,避免急停急转"
echo " - 保持标定板在视野内"
echo " - 包含6自由度运动"
echo " - 总时长:90-120秒"
echo ""
read -p "确认所有准备工作完成,按Enter开始录制..."
echo "开始录制数据包..."
timeout 120s rosbag record /camera/color/image_raw /wit/imu -O calibration_data.bag
echo ""
echo "数据采集完成!"
echo "文件保存为: calibration_data.bag"
echo ""
echo "数据统计:"
rosbag info calibration_data.bag
4.2 运动模式指南
推荐运动序列(总时长120秒):
-
0-10秒: 静止预热
- 面对标定板,距离1-2米
- 保持静止,让系统稳定
-
10-30秒: 平移运动
- 缓慢前后移动(改变与标定板距离)
- 左右平移(水平移动)
- 上下移动(垂直移动)
-
30-50秒: 旋转运动
- 绕相机光轴旋转(roll)
- 改变俯仰角度(pitch)
- 改变偏航角度(yaw)
-
50-80秒: 组合运动
- "∞"字形轨迹
- 同时包含平移和旋转
- 保持运动连续性
-
80-110秒: 多角度观察
- 从不同角度观察标定板
- 近距离和远距离交替
- 倾斜角度观察
-
110-120秒: 回到初始位置
- 平滑回到起始位置
- 短暂静止结束
运动示意图:
运动轨迹示例(俯视图):
标定板
┌─────┐
│ │
│ ■ │ ← 固定不动
│ │
└─────┘
↑
相机运动轨迹:
╭─→─╮ ← 水平"8"字
╱ ╲
╱ ∞ ╲ ← 同时上下移动
╱ ╲ ← 改变角度观察
5. 标定执行
5.1 相机内参标定
kalibr_calibrate_cameras \
--target checkerboard.yaml \
--bag calibration_data.bag \
--models pinhole-radtan \
--topics /camera/color/image_raw \
--bag-from-to 5 115 \
--show-extraction
参数说明:
--target
: 标定板配置文件--bag
: 数据包文件--models
: 相机模型(针孔+径向切向畸变)--topics
: 相机话题--bag-from-to
: 跳过前5秒和后5秒--show-extraction
: 显示特征点提取过程
5.2 IMU-相机外参标定
kalibr_calibrate_imu_camera \
--target checkerboard.yaml \
--bag calibration_data.bag \
--cam camchain-calibration_data.yaml \
--imu imu.yaml \
--bag-from-to 5 115 \
--show-extraction
参数说明:
--cam
: 第一步生成的相机内参文件--imu
: IMU配置文件
6. 结果验证
6.1 质量指标检查
相机标定质量:
- 重投影误差 < 0.5像素
- 标定板检测成功率 > 80%
- 畸变参数合理
IMU-相机标定质量:
- 重投影误差 < 1.0像素
- 时间偏移绝对值 < 0.05秒
- 外参矩阵合理
6.2 验证命令
# 验证相机标定结果
kalibr_camera_validator \
--cam camchain-calibration_data.yaml \
--target checkerboard.yaml \
--bag calibration_data.bag
# 查看详细报告
# 检查生成的PDF报告文件
6.3 结果文件
标定成功后生成的文件:
camchain-calibration_data.yaml
- 相机内参
cam0:
camera_model: pinhole
intrinsics: [fx, fy, cx, cy]
distortion_model: radtan
distortion_coeffs: [k1, k2, p1, p2]
resolution: [width, height]
rostopic: /camera/color/image_raw
camchain-imucam-calibration_data.yaml
- IMU-相机外参
cam0:
T_cam_imu: # 4x4变换矩阵
- [R11, R12, R13, tx]
- [R21, R22, R23, ty]
- [R31, R32, R33, tz]
- [0.0, 0.0, 0.0, 1.0]
timeshift_cam_imu: -0.01234 # 时间偏移
report-cam-calibration_data.pdf
- 详细报告report-imucam-calibration_data.pdf
- IMU标定报告
7. 常见问题排查
7.1 标定失败
可能原因:
- 运动不充分,缺少某些自由度
- 标定板检测质量差
- 数据采集时间不够
解决方案:
# 检查标定板检测效果
rqt_image_view /camera/color/image_raw
# 重新采集数据,注意:
# 1. 增加运动幅度
# 2. 改善光照条件
# 3. 延长采集时间
7.2 重投影误差过大
解决方案:
- 检查标定板是否平整
- 提高运动平滑度
- 确保标定板始终清晰可见
- 调整相机曝光设置
7.3 时间同步问题
检查方法:
# 比较时间戳
rostopic echo /camera/color/image_raw/header/stamp
rostopic echo /wit/imu/header/stamp
# 时间差应该很小(< 0.1秒)
7.4 IMU数据异常
检查步骤:
# 确认IMU单位正确
# 加速度:m/s²,角速度:rad/s
# 检查重力方向
rostopic echo /wit/imu/linear_acceleration
# 静止时应接近 [0, 0, ±9.8]
# 检查坐标系
# 确认使用右手坐标系
8. 使用标定结果
标定完成的参数文件可以直接用于:
- VINS-Mono: 复制到config文件夹
- ORB-SLAM3: 转换为相应格式
- OKVIS: 修改配置文件
- 其他VIO系统: 根据格式要求调整
参数转换示例(VINS-Mono格式):
# 从Kalibr结果提取参数
body_T_cam0: !!opencv-matrix
rows: 4
cols: 4
dt: d
data: [R11, R12, R13, tx,
R21, R22, R23, ty,
R31, R32, R33, tz,
0.0, 0.0, 0.0, 1.0]
9. 完整执行清单
# 1. 准备配置文件
□ checkerboard.yaml
□ imu.yaml
□ collect_data.sh
# 2. 检查系统
□ ROS话题正常
□ 数据发布频率检查
□ 硬件布置确认
# 3. 数据采集
□ 执行采集脚本
□ 按要求运动120秒
□ 检查bag文件质量
# 4. 执行标定
□ 相机内参标定
□ IMU-相机外参标定
□ 检查结果质量
# 5. 验证结果
□ 查看PDF报告
□ 检查误差指标
□ 保存标定文件