三维激光SLAM(XTDrone)

双系统ubuntu20.04复现三维激光SLAM时碰到一些问题,这里分享解决过错,希望能帮到大家。
由于ubuntu在安装过程中已经自动配置好了Ceres以及PCL,因此直接进行ALOAM与3D激光雷达插件编译即可。

1.ALOAM与3D激光雷达插件编译问题

编译出错的主要原因是OpenCV的兼容性问题,OpenCV4关于有些函数有了新的写法,按照如下方式进行解决即可:

  • 进入~/catkin_ws/src/A-LOAM/src/scanRegistration.cpp文件:
    #include <opencv/cv.h>修改为#include <opencv2/imgproc/imgproc_c.h>(44 行左右)
  • 进入~/catkin_ws/src/A-LOAM/src/kittiHelper.cpp文件:
    CV_LOAD_IMAGE_GRAYSCALE替换为cv::IMREAD_GRAYSCALE(91行左右,有两处)

注意报错后再重新编译时执行:

点击查看代码
cd ~/catkin_ws
catkin clean -y
# 避免爆内存
catkin build -j1
然后就编译成功了,会有一些警告不用管

image

注意之后需要执行:

点击查看代码
echo "source ~/catkin_ws/devel/setup.bash" >> ~/.bashrc
source ~/.bashrc
否则3D激光雷达插件无法在仿真环境中启用(检查一下不要重复加,否则后续gazebo无法启动会报下面的错)

image

2.修改刷新率

通过运行:find ~/XTDrone -type f \( -name "*.urdf" -o -name "*.xacro" -o -name "*.sdf" \) | grep -E "lidar|laser|velodyne|gpu",列出所有的雷达模型文件如下图:
image
教程中使用的是iris_3d_gpu_lidar,但是在对应的sdf文件中并没有找到update_rate,后来才发现其继承了3d_gpu_lidar.sdf,而这个文件中是有<update_rate>15</update_rate>,可以调整刷新率,越小,ALOAM不会卡。

3.Rviz没有雷达数据

如图,在启动ALOAM后并没有显示出雷达数据。

image

ROS坐标系有一个特点,以/开头表示全局绝对坐标系(是独立的,不与其他坐标系产生树关系),而不以/开头表示相对坐标系(会自动挂载在当前坐标系树下)。而ALOAM需要将自己的坐标系挂载到base_link或 laser_3d下,因此必须使用相对名称。我们将~/catkin_ws/src/A-LOAM/src路径下所有的.cpp和.hpp文件中有/camera和/camera_init的前缀 / 都删除,然后再重新编译即可成功。

image

后话: 关于为什么要改camera我暂时还没搞清楚,希望有朋友能够解答。现在理解是: 原始ALOAM使用/camera全局坐标系,无法接入XTDrone仿真TF树。去掉 / 变为 camera 相对坐标系后,自动挂载到机器人坐标系链,TF恢复连通,ALOAM正常工作。下图为修改后的TF_Tree:

image

posted @ 2026-04-13 21:36  九钟  阅读(8)  评论(0)    收藏  举报