一、前言
这个标定包是不依赖任何物理标定板或者标定目标,来进行激光雷达和相机的联合标定,通常,LiDAR和相机的标定需要使用一些已知尺寸、固定形状的标定板(例如棋盘格、圆形标定板等),这些物体在标定过程中作为“目标”,通过图像或激光点云中的特征点来进行坐标系的对齐和转换。但"无目标"方法并不依赖这些标定板或物理目标,而是通过其他方式(如自然场景中的几何关系、已知的运动模式、结构光等)来实现标定。
官网:https://github.com/koide3/direct_visual_lidar_calibration?tab=readme-ov-file
基础环境:Ubuntu22.04 ros2
硬件设备:非重复扫描固态激光雷达livox_avia + usb相机
参考csdn:direct_visual_lidar_calib环境部署及应用_direct lidar calibration-优快云博客
二、安装常见依赖
1.安装依赖
# Install dependencies
sudo apt install libomp-dev libboost-all-dev libglm-dev libglfw3-dev libpng-dev libjpeg-dev
2.安装GTSAM
# Install GTSAM
git clone https://github.com/borglab/gtsam
cd gtsam && git checkout 4.2a9
mkdir build && cd build
# For Ubuntu 22.04, add -DGTSAM_USE_SYSTEM_EIGEN=ON
cmake .. -DGTSAM_BUILD_EXAMPLES_ALWAYS=OFF \
-DGTSAM_BUILD_TESTS=OFF \
-DGTSAM_WITH_TBB=OFF \
-DGTSAM_BUILD_WITH_MARCH_NATIVE=OFF
make -j$(nproc)
sudo make install
3.安装Ceres
# Install Ceres
git clone --recurse-submodules https://github.com/ceres-solver/ceres-solver
cd ceres-solver
git checkout e47a42c2957951c9fafcca9995d9927e15557069
mkdir build && cd build
cmake .. -DBUILD_EXAMPLES=OFF -DBUILD_TESTING=OFF -DUSE_CUDA=OFF
make -j$(nproc)
sudo make install
在进行 make -j$(nproc) 这一步骤后,会报错(如图)
解决方法:这是链接器(ld)在尝试生成可执行文件时,找不到libtest_util 库的错误。通过禁用benchmark编译(不需要测试和基准测试)
cmake .. -DBUILD_EXAMPLES=OFF -DBUILD_TESTING=OFF -DBUILD_BENCHMARKS=OFF -DUSE_CUDA=OFF
make -j$(nproc)
4.安装Iridescence
# Install Iridescence for visualization
git clone https://github.com/koide3/iridescence --recursive
mkdir iridescence/build && cd iridescence/build
cmake .. -DCMAKE_BUILD_TYPE=Release
make -j$(nproc)
sudo make install
三、安装SuperGlue
pip3 install numpy opencv-python torch matplotlib
git clone https://github.com/magicleap/SuperGluePretrainedNetwork.git
echo 'export PYTHONPATH=$PYTHONPATH:/path/to/SuperGluePretrainedNetwork' >> ~/.bashrc
source ~/.bashrc
四、构建direct_visual_lidar_calibration
# ROS2
cd ~/ros2_ws/src
git clone https://github.com/koide3/direct_visual_lidar_calibration.git --recursive
cd .. && colcon build
构建时,报错
error: static assertion failed: Error: GTSAM was built against a different version of Eigen
解决方法: 这个错误信息提示了 GTSAM 和 Eigen 版本不兼容的问题。打开gtsam/cmake/HandleEigen.cmake文件,在第12行加入set(GTSAM_USE_SYSTEM_EIGEN ON)
五、数据采集
参考:从零入门激光SLAM(二十三)——direct_visual_lidar_calibration全型号激光雷达-相机标定包_激光slam入门教程-优快云博客
1.usb_cam节点驱动
主要参考:ROS2使用usb_cam_ros2 usbcam-优快云博客
除文中遇到的问题,报错信息:[ERROR] [usb_cam_node_exe-1]: process has died [pid 17787, exit code -11]
说明 usb_cam_node_exe
节点崩溃了,返回了 exit code -11
(通常是段错误或内存访问错误)
可能是参数配置文件出现问题,查看相机支持的格式
v4l2-ctl --list-formats
修改 sudo vim /opt/ros/humble/share/usb_cam/config/params_1当中的yamlpixel_format:
修改后可正常运行launch文件
2.前提条件
相机内参矩阵和畸变系数已经标定,且相机和LiDAR必须刚性固定
单目相机标定,获取内参,见:Ubuntu22.04 ros2_humble 单目相机标定-优快云博客
3.录制rosbag文件
在使用rosbag前,确认是否安装
sudo apt-get install ros-<distro>-ros2bag ros-<distro>-rosbag2*
接下来创建一个新的文件夹,保存数据库文件:
mkdir bag_files
cd bag_files
分别打开相机节点和雷达节点
ros2 launch usb_cam camera.launch.py
ros2 launch livox_ros2_avia livox_lidar_rviz_launch.py
ros2 bag 可以录制系统中发布的话题数据,查看当前有哪些话题
ros2 topic list
录制图像数据和点云数据,该命令会将数据保存在当前终端所在的路径下,所以最好先cd到刚才创建好的目录下,再运行
ros2 bag record /livox/lidar /camera1/image_raw /livox/imu /camera1/camera_info
按ctrl+c即可停止录制
六、标定示例
按照官方手册及进行
1.数据集下载
官网:https://koide3.github.io/direct_visual_lidar_calibration/example/
2.预处理
ros2 run direct_visual_lidar_calibration preprocess bag_files2 bag_files_preprocessed2 -av
3.(a)初始猜测(自动)
运行官网命令
ros2 run direct_visual_lidar_calibration find_matches_superglue.py bag_files_preprocessed2 --rotate_camera 90
报错:Python 没有找到models这个模块
【解决】:
1.检查一下是否有 models
目录存在
find ~/ros2_ws/src/ -type d -name "models"
2.将 SuperGluePretrainedNetwork
目录添加到 Python 路径中,以便 Python 可以找到 models
模块。可以通过修改 PYTHONPATH
环境变量来完成这一点。
export PYTHONPATH=$PYTHONPATH:/home/robot/ros2_ws/src/SuperGluePretrainedNetwork
使其生效:
source ~/.bashrc
3.重新编译工作空间
colcon build --symlink-install
source install/setup.bash
4.重新运行
查看livox_preprocessed文件夹,每个 ROS 2 包(rosbag)都被处理并且加载了 SuperPoint 和 SuperGlue 模型
执行基于RANSAC的初始猜测估计
ros2 run direct_visual_lidar_calibration initial_guess_auto bag_files_preprocessed2
完成了相机-激光雷达的初步配准。输出显示了使用RANSAC和最小二乘法(LSQ)估计的相机和激光雷达之间的变换矩阵T_camera_lidar 。Ceres Solver优化结果,显示了迭代次数和优化前后的成本值。终止条件为收敛。
3.(b)初始猜测(手动)
ros2 run direct_visual_lidar_calibration initial_guess_manual livox_preprocessed
4.精细相机配准
ros2 run direct_visual_lidar_calibration calibrate bag_files_preprocessed2
5.校准结果检查
ros2 run direct_visual_lidar_calibration calibrate bag_files_preprocessed2
6.校准结果文件
校准完成后,用文本编辑器打开livox_preprocessed/calib.json,查找标定结果T_lidar_camera