【开发背景】
最近正在做室内转室外的无人车项目,首当其冲的就是解决室外建图问题。之前室内一直用的Cartographer 2D建图,效果蛮好的,但是就是面临大场景的时候,闭环检测太吃平台算力了,所以现在只能换一个激光SLAM算法。网上搜索了一下目前流行的室外激光SLAM,发现LIO-SAM使用的人比较多,相关踩坑记录也比较丰富,索性就拿它试水了。
【硬件信息】
Robosense速腾16线激光雷达
Rion瑞芬TL720D陀螺转角仪
Intel NUC工控机
【安装流程】
1、创建一个干净的工作空间目录:
mkdir -p ~/liosam_ws/src
cd ~/liosam_ws/src
2、下载lio-sam源码及其依赖
sudo apt-get install -y ros-melodic-robot-localization
sudo apt-get install -y ros-melodic-robot-state-publisher
sudo add-apt-repository ppa:borglab/gtsam-release-4.0
sudo apt install libgtsam-dev libgtsam-unstable-dev
git clone https://ghproxy.com/https://github.com/TixiaoShan/LIO-SAM.git
3、下载robosense激光雷达ros驱动包
git clone https://ghproxy.com/https://github.com/RoboSense-LiDAR/rslidar_sdk.git
cd rslidar_sdk
git submodule init
git submodule update
4、下载robosense雷达点云转velodyne雷达的功能包
git clone https://github.com/HViktorTsoi/rs_to_velodyne.git
5、自己写一个瑞芬imu的ros驱动包
6、下载imu内参标定工具及其依赖
sudo apt-get install libdw-dev
git clone https://gitcode.net/mirrors/gaowenliang/code_utils.git
git clone https://gitcode.net/mirrors/gaowenliang/imu_utils.git
7、回到工程目录编译
cd ~/liosam_ws
catkin_make
【编译问题】
不出所料,你的catkin_make一定会失败,接下来我们一一进行修改:
1、修改 imu_utils 包的CMakeLists.txt的32行
catkin_package(CATKIN_DEPENDS code_utils)
2、修改 imu_utils 包的package.xml的53行
<build_depend>code_utils</build_depend>
<exec_depend>code_utils</exec_depend>
3、修改 ~/liosam_ws/src/code_utils-master/src/sumpixel_test.cpp 文件的第2行
#include "code_utils/backward.hpp"
4、修改 ~/liosam_ws/src/rs_to_velodyne/src/rs_to_velodyne.cpp 第28到38行
struct RsPointXYZIRT {
PCL_ADD_POINT4D;
float intensity;
uint16_t ring = 0;
double timestamp = 0;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
} EIGEN_ALIGN16;
POINT_CLOUD_REGISTER_POINT_STRUCT(RsPointXYZIRT,
(float, x, x)(float, y, y)(float, z, z)(float, intensity, intensity)
(uint16_t, ring, ring)(double, timestamp, timestamp))
5、修改 ~/liosam_ws/src/rslidar_sdk/CMakeLists.txt 第8行
set(POINT_TYPE XYZIRT)
6、现在再编译,应该就没问题了,如果还有问题,请留言
【必要工作】
1、IMU内参校准
将IMU静置不动,开启以下程序进行内参计算
roslaunch rion_imu imu.launch #开启瑞芬imu驱动
roslaunch imu_utils tl720d.launch #开启校准
2、LIO-SAM参数设置( ~/liosam_ws/src/LIO-SAM/config/params.yaml)
# IMU Settings 用标定工具得到的数据替换这些参数
imuAccNoise: 3.9939570888238808e-03
imuGyrNoise: 1.5636343949698187e-03
imuAccBiasN: 6.4356659353532566e-05
imuGyrBiasN: 3.5640318696367613e-05
imuGravity: 9.80511
imuRPYWeight: 0.01
# Extrinsics: T_lb (lidar -> imu) 建议imu直接放在雷达正上方,给一个单位矩阵即可
extrinsicTrans: [0.0, 0.0, 0.0]
extrinsicRot: [1, 0, 0,
0, 1, 0,
0, 0, 1]
extrinsicRPY: [1, 0, 0,
0, 1, 0,
0, 0, 1]
【运行指令】
只要你各部分的Topic话题都对上了,用以下命令就可以开始跑了
#开启rs雷达
roslaunch rslidar_sdk start.launch
#开启话题转换
rosrun rs_to_velodyne rs_to_velodyne XYZIRT XYZIRT
#开启imu
roslaunch rion imu.launch
#开启lio-sam建图
roslaunch lio_sam run.launch
【额外记录】
1、点云PCD文件转栅格地图PGM
git clone https://ghproxy.com/https://github.com/Hinson-A/pcd2pgm_package.git
2、安装3D点云实时转2D栅格地图软件包Octomap
sudo apt-get install ros-melodic-octomap-ros
sudo apt-get install ros-melodic-octomap-server
sudo apt-get install ros-melodic-octomap-rviz-plugins
一个可参考的launch文件
<launch>
<!--启动的节点-->
<node pkg="octomap_server" type="octomap_server_node" name="octomap_server">
<!--栅格分辨率-->
<param name="resolution" value="0.05" />
<!--世界坐标系话题,一般为map-->
<param name="frame_id" type="string" value="/map" />
<param name="sensor_model/max_range" value="1000.0" />
<param name="latch" value="true" />
<!--截取的三维点云范围-->
<param name="pointcloud_max_z" value="1.2" />
<param name="pointcloud_min_z" value="-0.5" />
<param name="graound_filter_angle" value="3.14" />
<!--订阅的点云消息名称 PointClout2,即上一步发布出来的点云topic-->
<!-- cloud_in是octomap默认的输入话题,做一下映射-->
<remap from="/cloud_in" to="/lio_sam/mapping/cloud_registered" />
</node>
</launch>
3、Ouster雷达驱动安装
##配置电脑ip
192.168.2.1
子网掩码 255.255.255.0
##配置雷达ip,这里的 eno1 要换成你自己的网卡名称,ping一下测试
sudo dnsmasq -C /dev/null -kd -F 192.168.2.2,192.168.2.100 -i enp3s0 --bind-dynamic
git clone https://ghproxy.com/https://github.com/ouster-lidar/ouster_example
catkin_make
## 时间戳如果没有改成正确模式,会出现没有map坐标系的现象,雷达和imu外参标定不准会有抖动现象
## os-122130000698需要根据自己雷达型号更改
roslaunch ouster_ros sensor.launch sensor_hostname:=os-122130000698.local lidar_mode:=2048x10 timestamp_mode:=TIME_FROM_ROS_TIME
#查找雷达当前地址
avahi-browse -lr _roger._tcp
## 设置雷达静态ip,可以设置下,这样雷达每次启动ip就不会变了
https://ouster.atlassian.net/wiki/spaces/SUPPORT/pages/831062017/IP
4、一个问题(move_base下面的代价子图只更新了一半(180度))
解决办法:手动调用costmap更新服务