【LIO-SAM 跑自录数据集】

LIO-SAM

测试环境: Ubuntu18.04 ROS melodic
激光雷达:RS16
组合惯导:华测CGI-410(频率100HZ)

一、数据格式

1.1 IMU数据格式
作者用的九轴IMU,本次测试用的六轴,未对源码修改。
注:IMU单位:rad/s;m/s^2;rad;
IMU坐标:y前,x右,z上(作者:x前,y左,z上)

1.2 Lidar 数据格式
LIO-SAM要求激光雷达的数据格式:XYZIRT
更改:rslidar_sdk中的CMakeLists.txt

#=======================================
# Custom Point Type (XYZI, XYZIRT)
#=======================================
set(POINT_TYPE XYZIRT)

安装rs_to_velodyne转化节点:

  1. 安装好最新的驱动之后,打开lidar_sdk工作空间/src/rslidar_sdk文件位置与rslidar_sdk并列新建workspace,再新建src,src安装rs_to_velodyne包,并编译。
git clone https://github.com/HViktorTsoi/rs_to_velodyne.git
cd ..
catkin_make
  1. 在与src并列的位置新建launch文件夹,在launch文件夹内新建rs2velodyne.launch文件用来启动节点,并在launch内写入
<launch>
  <node pkg="rs_to_velodyne" name="rs_to_velodyne" type="rs_to_velodyne"  args="XYZIRT XYZIRT"   output="screen">
  </node>
</launch>
  1. 将转化节点写入同一launch文件
<launch>
  <node pkg="rslidar_sdk" name="rslidar_sdk_node" type="rslidar_sdk_node" output="screen">
    <param name="config_path" value=""/>
  </node>
  <!-- rviz -->
  <!--<node pkg="rviz" name="rviz" type="rviz" args="-d $(find rslidar_sdk)/rviz/rviz.rviz" />-->
 <include file="$(find rs_to_velodyne)/launch/rs2velodyne.launch" /> 
</launch>

1.3 GPS数据要求
目前只注意到GPS数据格式为:sensor_msgs/NavSatFix

1.4 话题及frame_id
为了调试方便,更改自录数据集传感器话题和frame_id

// Lidar
/points_raw   --------------> frame_id:"velodyne"
// IMU
/imu_raw        --------------> frame_id:"imu_link"
// GPS
/gps_driver    -------------->frame_id:"navsat_link"

二、IMU内参标定及Lidar和IMU的外参标定
参考:标定.
注:本次实验IMU和Lidar坐标系均为:y前,x右,z上
IMU内参及lidar->IMU的平移旋转均为默认的配置文件。


三、下载LIO-SAM并编译

3.1 安装相关依赖包

sudo apt-get install -y ros-kinetic-navigation
sudo apt-get install -y ros-kinetic-robot-localization
sudo apt-get install -y ros-kinetic-robot-state-publisher 

3.2 安装GTSAM 4.0.2

git clone https://github.com/borglab/gtsam.git
mkdir build && cd build
cmake -DGTSAM_BUILD_WITH_MARCH_NATIVE=OFF ..
sudo make install -j4

3.3 下载lio-sam、编译

cd ~/catkin_ws/src
git clone https://github.com/TixiaoShan/LIO-SAM.git
cd ../
catkin_make

四、修改LIO-SAM配置参数

4.1 params.yaml
打开config文件下的params.yaml

  # Topics
  pointCloudTopic: "/points_raw"               # Point cloud data (雷达话题)
  imuTopic: "/imu_raw"                                  # IMU data  (IMU话题)
  odomTopic: "odometry/imu"                   # IMU pre-preintegration odometry, same frequency as IMU
  gpsTopic: "odometry/gps"                        # GPS odometry topic from navsat, see module_navsat.launch file
# GPS Settings
  useImuHeadingInitialization: true           # if using GPS data, set to "true" (使用GPS,改为true)
  useGpsElevation: false                      # if GPS elevation is bad, set to "false"
  gpsCovThreshold: 2.0                        # m^2, threshold for using GPS data
  poseCovThreshold: 1.0                      # m^2, threshold for using GPS data

这里用的是默认参数,根据实际情况做进一步修改。

 # Extrinsics (lidar -> IMU)
  extrinsicTrans: [0.0, 0.0, 0.0]
  # extrinsicRot: [-1, 0, 0,
  #                 0, 1, 0,
  #                 0, 0, -1]
  #extrinsicRPY: [0,  1, 0,
  #                -1, 0, 0,
  #                 0, 0, 1]
  extrinsicRot: [1, 0, 0,
                  0, 1, 0,
                  0, 0, 1]
  extrinsicRPY: [1, 0, 0,
                  0, 1, 0,
                  0, 0, 1]

其余地方暂未作修改。

4.2 module_navsat.launch
打开launch/include/module_navsat.launch文件

<launch>

    <arg name="project" default="lio_sam"/>

    <env name="ROSCONSOLE_CONFIG_FILE" value="$(find lio_sam)/launch/include/rosconsole/rosconsole_error.conf"/>
    
    <!-- EKF GPS-->
    <node pkg="robot_localization" type="ekf_localization_node" name="ekf_gps" respawn="true">
        <remap from="odometry/filtered" to="odometry/navsat" />
    </node>

    <!-- Navsat -->
    <node pkg="robot_localization" type="navsat_transform_node" name="navsat" respawn="true">
        <!-- <rosparam param="datum">[42.35893211, -71.09345588, 0.0, world, base_link]</rosparam> -->
        <remap from="imu/data" to="/imu_raw" />    // 修改为自己的Imu话题
        <remap from="gps/fix" to="/gps_driver" />    // 修改为自己的gps话题
        <remap from="odometry/filtered" to="odometry/navsat" />
    </node>

</launch>

五、运行

source devel/setup.bash
roslaunch lio-sam run.launch

生成的全局点云图
在这里插入图片描述

GPS约束

这里外参转换因为用的默认的,所以GPS在下面
在这里插入图片描述

点云地图和轨迹
在这里插入图片描述
点云地图和GPS轨迹
在这里插入图片描述

lidar odom和gps 轨迹

高程方向还有很大的误差
在这里插入图片描述


参考

  1. LIO-SAM运行自己数据包遇到的问题解决–SLAM不学无数术小问题.
  2. lio-sam运行自己的rosbag.
  3. ubuntu18运行编译LIO-SAM并用官网和自己的数据建图(修改汇总).
  • 11
    点赞
  • 87
    收藏
    觉得还不错? 一键收藏
  • 33
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 33
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值