硬件设备

激光雷达:DJI Livox Avia混合固态激光雷达
相机:Intel Realsense D435i深度相机

外参标定

外参标定是进行多传感器融合的必要前提。

标定流程

livox_camera_calib是香港大学MaRS 实验室开发的一款的激光雷达和相机标定的算法。算法分为分为单场景标定(Single scene calibration)多场景标定(Multi scenes calibration),本文只探讨单场景标定。配置过程参考livox_camera_calib官网的流程即可。

cd ~/catkin_ws/src
git clone https://github.com/hku-mars/livox_camera_calib.git
cd ../
catkin_make
source ~/catkin_ws/devel/setup.bash

配置好环境后运行标定launch文件。过程如下:
(1)修改config/calib.yaml文件路径

# Data path. adjust them!
common:
    image_file: "/home/ggh/workdir/catkin_ws/src/livox_camera_calib/data/2.png" #你自己存放相机影像png的路径
    pcd_file: "/home/test/lidarimu/catkin_ws/src/livox_camera_calib/data/2.pcd" #你自己存放点云pcd的路径
    result_file: "/home/test/lidarimu/catkin_ws/src/livox_camera_calib/result/extrinsic.txt" #存放标定结果的路径

# Camera Parameters. Adjust them!
# 你自己相机的内参数和镜头畸变参数
camera:
    camera_matrix: [1364.45, 0.0,      958.327,
                0.0,     1366.46,  535.074,
                0.0,     0.0,      1.0     ]
    dist_coeffs: [0.0958277, -0.198233, -0.000147133, -0.000430056, 0.000000]

# Calibration Parameters.!
calib:
    calib_config_file: "/home/test/lidarimu/catkin_ws/src/livox_camera_calib/config/config_indoor.yaml" #连接的另外一个yaml的文件,视你的标定场景而定,这个会直接影响标定结果,一定要记得修改
    use_rough_calib: true # set true if your initial_extrinsic is bad

(2)运行单场景标定roslaunch文件

roslaunch livox_camera_calib calib.launch

经过一系列迭代优化得到标定结果,如下数图所示。

点云-图像残差图
粗优化结果
最终优化结果
RVIZ和运行结果

问题解决

问题一:运行calib.launch报错:[lidar_camera_calib-2] process has died [pid 26108, exit code -11, cmd

NODES
/
lidar_camera_calib (livox_camera_calib/lidar_camera_calib)
rviz (rviz/rviz)

auto-starting new master
process[master]: started with pid [26093]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to 8bfc51c8-dc14-11ed-9ebe-0cc47a6c9e2b
process[rosout-1]: started with pid [26104]
started core service [/rosout]
process[lidar_camera_calib-2]: started with pid [26108]
process[rviz-3]: started with pid [26112]
pcd_file path:/home/lk/catkin_ws/src/livox_camera_calib/data/single_scene_calibration/0.pcd
[lidar_camera_calib-2] process has died [pid 26108, exit code -11, cmd /home/lk/catkin_ws/devel/lib/livox_camera_calib/lidar_camera_calib __name:=lidar_camera_calib __log:=/home/lk/.ros/log/8bfc51c8-dc14-11ed-9ebe-0cc47a6c9e2b/lidar_camera_calib-2.log].
log file: /home/lk/.ros/log/8bfc51c8-dc14-11ed-9ebe-0cc47a6c9e2b/lidar_camera_calib-2*.log”

从这段报错中除了能得到是在加载pcd文件时出错以外,看不出来任何有用信息。这时rviz被打开,发现在rviz软件界面显示未接收到任何点云或图片数据,大胆猜测是pcd数据没有加载失败
在这里插入图片描述
忘了截图了,这里引用来自livox_camera_calib主页#85 Issue的图,在Issue中没有解决这个问题。

在这里插入图片描述
图源:livox_camera_calib主页#85 Issue

经分析,直接问题断定为加载pcd点云文件失败,猜测问题本源在于opencv版本冲突。为了确定这一猜测,基于vscode配置ros代码调式
在这里插入图片描述
红框处为报错的地方(调试时忘记截图,在此处用红框标记之),由此猜测是 cv_bridge 与 opencv4版本冲突问题,因为我的系统是ubuntu 18.04,ROS版本为melodic,而 melodic 版本的 cv_bridge 功能包中所用 opencv 版本为 opencv3,我安装的是opencv4。考虑到noetic 版本的 cv_bridge 功能包使用的是 opencv4,所以提出
【解决方法】:通过安装noetic 版本的 cv_bridge ,将新的 cv_bridge 和 我自己功能包的依赖设为同一版本的 opencv,同时保留 melodic 版本的 cv_bridge 功能包(后面会说到为什么要同时保留)。具体安装过程参考这篇文章
退回catkin工作空间,重新catkin_make,然后再次运行

roslaunch livox_camera_calib calib.launch

加载成功!
在这里插入图片描述

问题二:运行自己的标定数据报错:[pcl::KdTreeFLANN::setInputCloud] Cannot create a KDTree with an empty input cloud!

[ INFO] [1691133251.022876409]: Sucessfully load calib config file
[ INFO] [1691133251.636212259]: Sucessfully load image!
[ INFO] [1691133251.640953018]: Sucessfully extract edge from image, edge size:15957
[ INFO] [1691133251.640971292]: Loading point cloud from pcd file.
[ INFO] [1691133281.547540320]: Sucessfully load pcd, pointcloud size: 9936000
[ INFO] [1691133281.547566909]: Building Voxel
[ INFO] [1691133285.886021869]: Extracting Lidar Edge
[ INFO] [1691133292.414024597]: Finish prepare!
Initial rotation matrix:
 0 -1  0
 0  0 -1
 1  0  0
Initial translation:0 0 0
[pcl::KdTreeFLANN::setInputCloud] Cannot create a KDTree with an empty input cloud!
Rough calibration min cost:1
[pcl::KdTreeFLANN::setInputCloud] Cannot create a KDTree with an empty input cloud!
[pcl::KdTreeFLANN::setInputCloud] Cannot create a KDTree with an empty input cloud!
[pcl::KdTreeFLANN::setInputCloud] Cannot create a KDTree with an empty input cloud!
[pcl::KdTreeFLANN::setInputCloud] Cannot create a KDTree with an empty input cloud!
[pcl::KdTreeFLANN::setInputCloud] Cannot create a KDTree with an empty input cloud!
[pcl::KdTreeFLANN::setInputCloud] Cannot create a KDTree with an empty input cloud!
[pcl::KdTreeFLANN::setInputCloud] Cannot create a KDTree with an empty input cloud!

在这里插入图片描述

导致无法进入优化程序,具体表现为没有输出点云-图像残差图以及没有点云叠加的优化窗口,如下图所示。
错误的点云-图像残差图在这里插入图片描述
排除了点云路径错误点云话题名称错误以及点云密度过于稀疏等livox_camera_calib项目网站上#19 Issue#84 Issue中提到的可能的错误,即能读取并在rviz上显示就说明点云路径和话题名称没错,能提取到足够多的线特征(红色的线条)就说明点云密度达到标定要求(为此我还对比了项目demo中3.pcd的点云密度,我采集的点云数量远高于demo中的点云数量),如下图所示。但是问题依然没有得到解决。
在这里插入图片描述

那么问题该如何解决呢?需要说明的是,我采集的标定数据设置的分辨率为640480,项目demo中给的影像分辨率是19201080。于是,我将我的D435i的RGB影像分辨率设置为与demo一致的1920*1080,并且将影像话题发布频率降低为30Hz(否则会硬件报错),该操作在realsense_camera包的rs_camera.launch中进行,如图所示:
在这里插入图片描述
重新录制ros包,从中提取png格式影像,重新运行calib.launch,pcd加载完成后,进入优化模式,问题解决!
在这里插入图片描述

相机内参标定

在标定激光雷达和相机外部参数之前,我们必须尽可能地知道相机准确的焦距、像主点偏移以及镜头畸变等相机内部参数。最直接的,我们在修改config/calib.yaml文件时,相机内参是必须由我们自己给定。因此,在开始外参标定前,我们首先要标定相机内参。

标定流程

对于Intel Realsense D435i相机的标定,我们可以参考这篇文章,即使用ETHZ出品的Kalibr工具包来标定。由于这篇文章已经写得非常详细,在此我就不过多赘述了。使用Intel Realsense D435i的同学可以无脑照着这篇文章操作,使用别的系列或者别的品牌的同学注意要在有些关键地方需要根据自身设备作出修改。
需要注意的一点是文章中运行标定ros功能包时有一个小错误,即文章中给的运行命令是

kalibr_calibrate_cameras --target ~/kalibr_ws/src/Kalibr/data/checkerboard.yaml --bag ~/kalibr_ws/src/Kalibr/data/camd435i.bag --models pinhole-equi --topics /color --show-extractio

如果同学们按照这个命令输入会发现会报错:找不到kalibr_calibrate_cameras包,这时不要慌张,在前面加上rosrun等操作即可

rosrun kalibr kalibr_calibrate_cameras --target ~/kalibr_ws/src/Kalibr/data/checkerboard.yaml --bag ~/kalibr_ws/src/Kalibr/data/camd435i.bag --models pinhole-equi --topics /color --show-extractio

问题解决

问题一:运行kalibr_calibrate_cameras报错:UnicodedecodeError:‘ascii’ codec can’t decode byte oxco in position 0: ordinalnot in range(128)

在这里插入图片描述
这红框中可知,这是因为当前的python版本(我装的是python2.7)与noetic版本的cv_bridge冲突所致,这是不要慌,在这个包里用回原来的melodic版本的cv_bridge就OK了,这也就是为何我在上文中说要同时保留这两个版本的cv_bridge的原因。具体操作如下:
找到catkin工作空间下python文件夹下cv_bridge下的_init_.py文件,一般路径是:~/workdir/catkin ws/devel/lib/python2.7/dist-packages/cv bridge/init .py ,修改扩展路径_extended_path为melodic版本的cv_bridge的python路径即可
在这里插入图片描述
重新运行ROS功能包,问题解决!
在这里插入图片描述

Logo

瓜分20万奖金 获得内推名额 丰厚实物奖励 易参与易上手

更多推荐