这边博客用来记录使用港科大 Fast-Calib 使用流程,因为在实际使用的时候发现他们的配置文件和 ReadMe 文件写不是特别清晰,我的学生反映只跑通了一个配置文件,因此在这里记录一下有关修改配置和对应使用方法。涉及到以下仓库:
除了 Fast-Calib
这个标定仓库以外,港科大还在早期提供了一个 livox_camera_calib 这个仓库,但在编译上要比这个仓库多一些操作,如果你对 livox_camera_calib
仓库感兴趣或者想要对比一下标定结果,那么可以参考下面的博客与对应的 Github 仓库,(优先参考仓库因为所有 bug 修复都会第一时间同步到这个上面)。
- Lidar-Camera-Calibration: https://github.com/GaohaoZhou-ops/Lidar-Camera-Calibration
- Livox Mid360 与 RealSense D435i 在 Jetson Orin 上用 livox_camera_calib 进行外参标定: https://blog.csdn.net/nenchoumi3119/article/details/150586376?spm=1001.2014.3001.5502
后续我们会将多个开源的标定工具集成到一个仓库中,类似我们之前的开源的 JetsonSLAM 这个仓库进行组织;
Step1. 拉取源码并编译
假设你的标定空间为 calib_ws
,使用下面的命令拉取源码并编译,目前来看无论是在 X86 还是 Arm 上的编译都不会有特别多的问题,
$ cd calib_ws/src
$ git clone https://github.com/hku-mars/FAST-Calib.git
然后直接编译即可
$ cd calib_ws
$ catkin_make
Step2. 下载官方数据样本
官方在这里提供了场景单视角与场景多视角的标定示例包,通过下面的链接可以获取:
- 单视角数据包:https://connecthkuhk-my.sharepoint.com/personal/zhengcr_connect_hku_hk/_layouts/15/onedrive.aspx?id=%2Fpersonal%2Fzhengcr%5Fconnect%5Fhku%5Fhk%2FDocuments%2Fcalib%5Fdata&ga=1
- 多视角数据包:https://pan.baidu.com/s/1Mkw7EWfiFT68LEzdkQnxeg?pwd=nyuh#list/path=%2F
你也可以直接从我的网盘中下载:
https://pan.baidu.com/s/17K5GJaJoCCOO_BlLH066Yg?pwd=jss4
数据集下载好后放在任意位置都行,只需要在配置文件中修改路径即可,这里假设最终的文件结构如下:
$ cd calib_ws/
$ tree -L 2
.
├── dataset
│ ├── avia_multi_scene # 多视角数据包
│ └── single_scene_data # 单视角数据包
└── src
└── FAST-Calib # 预案吗工程
Step3. 运行示例
这里主要是介绍如何调整配置文件中的参数以及技巧,弥补官方文档中缺失的解释部分。
【Note】:在运行所有示例之前需要清理一下 calib_ws/src/FAST-Calib/output
文件夹的内容,如果你的这个文件夹为空则继续即可;如果你的文件夹中已经有了东西,那么建议直接清空这个文件夹,因为在多视角标定的时候会读取 circle_center_record.txt
这个文件,之前残留的部分会影响到融合结果。
3.1 Avia 多视角标定
该示例需要分阶段用到下面三对数据包:
avia_multi_scene/11.bag
&avia_multi_scene/11.jpg
avia_multi_scene/22.bag
&avia_multi_scene/22.jpg
avia_multi_scene/33.bag
&avia_multi_scene/33.jpg
multi_scene_11
第一阶段需要使用到 avia_multi_scene/11.bag
和 avia_multi_scene/11.jpg
这两个样本数据,修改 calib_ws/src/FAST-Calib/config/qr_params.yaml
文件内容如下:
# Camera intrinsics
# multi-scene
fx: 2478.48702288166
fy: 2478.58544825456
cx: 1230.99707596681
cy: 1025.66149498072
k1: -0.0493178189623200
k2: 0.147394487986097
p1: -0.00127118592043482
p2: -0.00200379689523022
# Calibration target parameters
marker_size: 0.20 # ArUco marker size (our test data uses 0.16m; adjust to match your marker size)
delta_width_qr_center: 0.55 # Half the distance between the centers of two markers in the horizontal direction
delta_height_qr_center: 0.35 # Half the distance between the centers of two markers in the vertical direction
delta_width_circles: 0.5 # Distance between the centers of two circles in the horizontal direction
delta_height_circles: 0.4 # Distance between the centers of two circles in the vertical direction
circle_radius: 0.12 # Radius of the circle
# multi_scene_11
x_min: 2.0
x_max: 5.0
y_min: -1.0
y_max: 1.0
z_min: 0.0
z_max: 2.0
# Input
lidar_topic: "/livox/lidar" # /ouster/points /livox/lidar
bag_path: "/home/orin/Desktop/calib_ws/dataset/avia_multi_scene/11.bag"
image_path: "/home/orin/Desktop/calib_ws/dataset/avia_multi_scene/11.jpg"
# Output
output_path: "$(find fast_calib)/output"
运行即可得到标定结果:
$ cd calib_ws
$ source devel/setup.bash
$ roslaunch fast_calib calib.launch
你在终端应该能看到下面的输出,如果发现 RMSE
值特别离谱,那么检查 yaml 文件是否使用的是 multi_scene_11
内容:
multi_scene_22
第二阶段需要使用到 avia_multi_scene/22.bag
和 avia_multi_scene/22.jpg
这两个样本数据,修改 calib_ws/src/FAST-Calib/config/qr_params.yaml
文件内容如下:
# ...
# 上面的部分不用改动
# multi_scene_22
x_min: 2.0
x_max: 5.0
y_min: -4.0
y_max: 1.0
z_min: 0.0
z_max: 2.0
# Input
lidar_topic: "/livox/lidar" # /ouster/points /livox/lidar
bag_path: "/home/orin/Desktop/calib_ws/dataset/avia_multi_scene/22.bag"
image_path: "/home/orin/Desktop/calib_ws/dataset/avia_multi_scene/22.jpg"
# Output
output_path: "$(find fast_calib)/output"
然后运行脚本:
$ roslaunch fast_calib calib.launch
终端输出如下:
multi_scene_33
第二阶段需要使用到 avia_multi_scene/33.bag
和 avia_multi_scene/33.jpg
这两个样本数据,修改 calib_ws/src/FAST-Calib/config/qr_params.yaml
文件内容如下:
# ...
# 上面的部分不用改动
# multi_scene_33
x_min: 2.0
x_max: 5.0
y_min: -1.0
y_max: 4.0
z_min: 0.0
z_max: 2.0
# Input
lidar_topic: "/livox/lidar" # /ouster/points /livox/lidar
bag_path: "/home/orin/Desktop/calib_ws/dataset/avia_multi_scene/33.bag"
image_path: "/home/orin/Desktop/calib_ws/dataset/avia_multi_scene/33.jpg"
# Output
output_path: "$(find fast_calib)/output"
然后运行脚本:
$ roslaunch fast_calib calib.launch
终端输出如下:
融合多视角标定结果
在进行多视角标定融合之前建议检查一下 calib_ws/src/FAST-Calib/output/circle_center_record.txt
文件中是否有 不小于3条 的标定结果,因为根据官方文档中的描述至少需要 3 次标定结果才能进行融合:
以我这边的文件为例:
time: 2025-09-01 14:57:06
lidar_centers: {4.20954,0.115556,0.925946} {4.2042,0.127745,0.520105} {4.19602,-0.371739,0.509748} {4.20129,-0.380586,0.906658}
qr_centers: {-0.0548394,-0.941356,4.25156} {-0.0624851,-0.541451,4.25576} {0.437417,-0.531868,4.25335} {0.445063,-0.931773,4.24916}
time: 2025-09-01 15:02:55
lidar_centers: {4.45013,0.111751,0.944239} {4.458,0.111903,0.548373} {4.65024,-0.353032,0.546272} {4.64393,-0.3569,0.941126}
qr_centers: {-0.0432598,-0.968805,4.50334} {-0.0493594,-0.568924,4.51093} {0.416619,-0.565257,4.69218} {0.422718,-0.965138,4.68459}
time: 2025-09-01 15:06:24
lidar_centers: {4.90411,0.381771,0.902504} {4.89949,0.391846,0.504875} {4.68953,-0.0661878,0.493763} {4.69526,-0.0737863,0.889996}
qr_centers: {-0.321193,-0.92974,4.9442} {-0.330377,-0.529853,4.94669} {0.125373,-0.518106,4.74137} {0.134558,-0.917992,4.73888}
然后运行下面的命令,这条命令运行非常快并且不会打开rviz,因为只涉及到数学运算:
$ roslaunch fast_calib multi_calib.launch
最终融合的结果保存在 calib_ws/src/FAST-Calib/output/multi_calib_result.txt
文件中,这个格式是可以直接复制到 FAST-LIVO2
工程中使用的:
# FAST-LIVO2 calibration format
Rcl: [ -0.003111, -0.999995, -0.000789,
-0.010254, 0.000821, -0.999947,
0.999943, -0.003103, -0.010256]
Pcl: [ 0.077836, 0.023247, 0.055067]
3.2 Mid360 单视角标定
由于 Livox Mid360 是现在具身机器人的主流传感器,但官方仓库中并没有对这部分进行详细介绍,直接取消注释配置文件中的参数是无法运行的。这里将告诉你如何修改配置文件,以及里面参数的意义。官方示例中虽然没有提供多视角 Mid360 数据包,但你可以仿照上面 Avia 多视角的方式 先进行单视角标定再融合。
此处为了避免啰嗦就只进行一次单视角标定以下面两个数据包为例:
single_scene_data/mid360/11.png
&single_scene_data/mid360/11.bag
【Note】:同样,在运行标定之前建议清空一下输出文件夹 src/FAST-Calib/output
避免数据混乱;
试探雷达范围
在修改配置文件之前可以通过 rviz 先试探一下激光雷达的视野范围,因为官方提供的数据包都特别小只有十几秒的市场,因此在调试过程中可以用 --loop
的参数让其循环播放:
$ cd calib_ws
$ rosbag play --loop dataset/single_scene_data/mid360/11.bag
然后打开 rvz 查看可视化点云:
$ rviz
- 手动修改
Fixed Frame
值为livox_frame
; - 添加点云后增大
Decay Time
值; - 添加
Axes
突出坐标原点;
修改配置文件
上面的 rviz 在调试过程中可以一直启动,不会影响标定结果。通过 rviz 可以看到这个数据包距离坐标原点三个方向大概是 x=[1.0,2.5]
,y=[-1.0,1.0]
,z=[-0.5, 1.5]
,那么修改配置文件 src/FAST-Calib/config/qr_params.yaml
:
# Camera intrinsics
# mid360
fx: 843.501050605967
fy: 845.199690011973
cx: 321.017429415352
cy: 239.294896816737
k1: -0.465219389887045
k2: 0.237050091701749
p1: 0.00521922785740506
p2: 0.000418186016514835
# Calibration target parameters
marker_size: 0.20 # ArUco marker size (our test data uses 0.16m; adjust to match your marker size)
delta_width_qr_center: 0.55 # Half the distance between the centers of two markers in the horizontal direction
delta_height_qr_center: 0.35 # Half the distance between the centers of two markers in the vertical direction
delta_width_circles: 0.5 # Distance between the centers of two circles in the horizontal direction
delta_height_circles: 0.4 # Distance between the centers of two circles in the vertical direction
circle_radius: 0.12 # Radius of the circle
# 适配 single_scene_data/mid360/11.bag 数据包的参数
x_min: 1.0
x_max: 2.5
y_min: -1.0
y_max: 1.0
z_min: -0.5
z_max: 1.5
# Input
lidar_topic: "/livox/lidar" # /ouster/points /livox/lidar
bag_path: "/home/orin/Desktop/calib_ws/dataset/single_scene_data/mid360/11.bag"
image_path: "/home/orin/Desktop/calib_ws/dataset/single_scene_data/mid360/11.png"
# Output
output_path: "$(find fast_calib)/output"
然后启动标定脚本:
$ roslaunch fast_calib calib.launch
终端输出如下:
标定结果保存在 src/FAST-Calib/output/single_calib_result.txt
文件中:
# FAST-LIVO2 calibration format
cam_model: Pinhole
cam_width: 1440
cam_height: 1080
scale: 1.0
cam_fx: 843.501
cam_fy: 845.2
cam_cx: 321.017
cam_cy: 239.295
cam_d0: -0.465219
cam_d1: 0.23705
cam_d2: 0.00521923
cam_d3: 0.000418186
Rcl: [ 0.403589, -0.911757, -0.076256,
-0.139593, 0.021008, -0.989986,
0.904229, 0.410192, -0.118796]
Pcl: [ 0.729378, 1.238788, 0.755164]
常见问题与解决方案
Can not select 0 unique points out of 0!
如果你在运行脚本 calib.launch
后出现了下面的报错,那么是你的 yaml 文件中给的 x_min, x_max, y_min, y_max, z_min, z_max
中没有有效角点导致,参考 3.2
中 试探雷达范围
操作修改配置文件中的内容。
Number of lidar center points to be sorted is not 4.
如果你在运行脚本 calib.launch
后出现了下面的报错,那么还是因为 yaml 文件中给的 x_min, x_max, y_min, y_max, z_min, z_max
值不对导致的。这个错误是最容易出现的,因为官方文档的说明比较笼统,如果你直接取消注释配置文件中的 mid360 部分就会出现这个情况: