Skip to content

LIO-SAM#

什么是 LIO-SAM?#

  • 实现高精度、实时移动机器人轨迹估计和地图构建的框架.它在因子图上构建了激光雷达惯性里程计,允许将来自不同来源的大量相对和绝对测量值(包括循环闭合)作为因子纳入系统.

存储库信息#

https://github.com/TixiaoShan/LIO-SAM

必需的传感器#

  • LIDAR [Livox, Velodyne, Ouster, Robosense*]
  • IMU [9-AXIS]
  • GPS [OPTIONAL]

*Robosense 激光雷达不受官方支持,但其 Helios 系列可以用作 Velodyne 激光雷达.

下图中描述的 LIO-SAM 方法的系统架构, 请查看 官方仓库 以获取更多信息.

lio-sam-architecture

LIO-SAM 的系统架构

我们在 tutorial_vehicle上使用 Robosense Helios 5515CLAP B7 传感器, 因此,我们将使用这些传感器来运行 LIO-SAM.

此外,LIO-SAM 还使用 Applanix POS LVXHesai Pandar XT32 传感器设置进行了测试.一些附加信息 根据传感器,此页面将提供.

ROS 兼容性#

由于 Autoware 目前使用 ROS 2 Humble,我们将继续使用 ROS 2 版本的 LIO-SAM.

  • ROS
  • ROS 2 (此外,它与 Humble 发行版兼容)

依赖#

ROS 2 依赖项:

要安装这些依赖项,您可以在终端中使用以下 bash 命令:

sudo apt install ros-humble-perception-pcl \
       ros-humble-pcl-msgs \
       ros-humble-vision-opencv \
       ros-humble-xacro

其他依赖项:

  • gtsam (Georgia Tech Smoothing and Mapping 库)

要安装 gtsam,您可以在终端中使用以下 bash 命令:

  # Add GTSAM-PPA
  sudo add-apt-repository ppa:borglab/gtsam-release-4.1
  sudo apt install libgtsam-dev libgtsam-unstable-dev

构建并运行#

1) 安装#

为了使用和构建 LIO-SAM,我们将为 LIO-SAM 创建工作区:

    mkdir -p ~/lio-sam-ws/src
    cd ~/lio-sam-ws/src
    git clone -b ros2 https://github.com/TixiaoShan/LIO-SAM.git
    cd ..
    colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release

2) 设置#

LIO-SAM 建成后, 我们需要记录 ROS 2 Bag 文件,其中包括 LIO-SAM 的必要主题. LIO-SAM 上的 config file 中描述了必要的主题.

配备 Robosense Helios 和 CLAP B7 的 LIO-SAM 的 ROS 2 袋示例
Files:             map_bag_13_09_0.db3
Bag size:          38.4 GiB
Storage id:        sqlite3
Duration:          3295.326s
Start:             Sep 13 2023 16:40:23.165 (1694612423.165)
End:               Sep 13 2023 17:35:18.492 (1694615718.492)
Messages:          1627025
Topic information: Topic: /sensing/gnss/clap/ros/imu | Type: sensor_msgs/msg/Imu | Count: 329535 | Serialization Format: cdr
Topic: /sensing/gnss/clap/ros/odometry | Type: nav_msgs/msg/Odometry | Count: 329533 | Serialization Format: cdr
Topic: /sensing/lidar/top/pointcloud_raw | Type: sensor_msgs/msg/PointCloud2 | Count: 32953 | Serialization Format: cdr

注意: 我们在 clap_b7_driver 中使用 use_odometry 来从 navsatfix 发布 GPS 里程计主题.

请在 lio_sam/config/params.yaml 中设置主题和传感器设置. 以下是一些 out tutorial_vehicle 的示例修改.

  • 主题名称:
-   pointCloudTopic: "/points"
+   pointCloudTopic: "/sensing/lidar/top/pointcloud_raw"
-   imuTopic: "/imu/data"
+   imuTopic: "/sensing/gnss/clap/ros/imu"
    odomTopic: "odometry/imu"
-   gpsTopic: "odometry/gpsz"
+   gpsTopic: "/sensing/gnss/clap/ros/odometry"

由于我们将通过 Autoware 使用 GPS 信息, 所以我们需要启用 useImuHeadingInitialization 参数.

  • GPS 设置:
-   useImuHeadingInitialization: false
+   useImuHeadingInitialization: true
-   useGpsElevation: false
+   useGpsElevation: true

我们还将更新传感器设置. 由于 Robosense 激光雷达不受官方支持, 我们将 32 通道 Robosense Helios 5515 激光雷达设置为 Velodyne:

  • 传感器设置:
-   sensor: ouster
+   sensor: velodyne
-   N_SCAN: 64
+   N_SCAN: 32
-   Horizon_SCAN: 512
+   Horizon_SCAN: 1800

然后 我们将更新 Robosense 激光雷达和 CLAP B7 GNSS/INS (IMU) 系统之间的外部转换.

  • 外在转换:
-   extrinsicTrans:  [ 0.0,  0.0,  0.0 ]
+   extrinsicTrans:  [-0.91, 0.0, -1.71]
-   extrinsicRot:    [-1.0,  0.0,  0.0,
-                      0.0,  1.0,  0.0,
-                      0.0,  0.0, -1.0 ]
+   extrinsicRot:    [1.0,  0.0,  0.0,
+                     0.0,  1.0,  0.0,
+                     0.0,  0.0, 1.0 ]
-   extrinsicRPY: [ 0.0,  1.0,  0.0,
-                  -1.0,  0.0,  0.0,
-                   0.0,  0.0,  1.0 ]
+   extrinsicRPY: [ 1.0,  0.0,  0.0,
+                   0.0,  1.0,  0.0,
+                   0.0,  0.0,  1.0 ]

警告

映射方向是朝向现实世界中的前进方向. 如果 LiDAR 传感器向后,根据您移动的方向, 那么你也需要改变 extrinsicRot. 除非 IMU 试图朝着错误的方向发展,否则可能会出现问题.

例如,在我们的 Applanix POS LVX 和 Hesai Pandar XT32 设置中,IMU 方向是朝向前进的方向,而 根据 IMU 方向,LiDAR 方向在 Z 轴上有 180 度的差异.换句话说,他们面朝后方 彼此.该工具可能需要对 IMU 进行转换.

  • 在这种情况下,校准参数更改如下:
-   extrinsicRot:    [-1.0,  0.0,  0.0,
-                      0.0,  1.0,  0.0,
-                      0.0,  0.0, -1.0 ]
+   extrinsicRot:    [-1.0,  0.0,  0.0,
+                     0.0,  -1.0,  0.0,
+                     0.0,   0.0,  1.0 ]
-   extrinsicRPY: [ 0.0,  1.0,  0.0,
-                  -1.0,  0.0,  0.0,
-                   0.0,  0.0,  1.0 ]
+   extrinsicRPY: [ -1.0,  0.0,  0.0,
+                    0.0, -1.0,  0.0,
+                    0.0,  0.0,  1.0 ]
  • 最后,我们在 RViz 中获得了这个转换可视化:

lio-sam-imu-direction

在 RViz 中转换 Applanix POS LVX 和 Hesai Pandar XT32 的可视化效果

现在,我们已准备好为 Autoware 创建地图.

3) Usage#

如果您为 LIO-SAM 设置了配置并创建了 bag 文件,则可以使用以下命令启动 LIO-SAM:

ros2 launch lio_sam run.launch.py

rviz2 屏幕将打开,然后您可以播放您的 bag 文件:

ros2 bag play <YOUR-BAG-FILE>

如果 mapping 过程完成,您可以通过调用此服务来保存 map:

ros2 service call /lio_sam/save_map lio_sam/srv/SaveMap "{resolution: 0.2, destination: <YOUR-MAP-DIRECTORY>}"

以下是在我们的园区环境中演示 LIO-SAM 映射的视频:

输出地图格式为本地 UTM, 我们将本地 UTM 地图更改为 MGRS 格式以进行tutorial_vehicle. 另外,如果您想将 UTM 更改为 MGRS for autoware, 请关注 convert-utm-to-mgrs-map 页面.

示例结果#

lio-sam-output

校园环境的示例地图输出

Paper#

感谢您引用 LIO-SAM (IROS-2020) 来引用此代码中的任何一个.

@inproceedings{liosam2020shan,
  title={LIO-SAM: Tightly-coupled Lidar Inertial Odometry via Smoothing and Mapping},
  author={Shan, Tixiao and Englot, Brendan and Meyers, Drew and Wang, Wei and Ratti, Carlo and Rus Daniela},
  booktitle={IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)},
  pages={5135-5142},
  year={2020},
  organization={IEEE}
}

部分代码改编自 LeGO-LOAM.

@inproceedings{legoloam2018shan,
  title={LeGO-LOAM: Lightweight and Ground-Optimized Lidar Odometry and Mapping on Variable Terrain},
  author={Shan, Tixiao and Englot, Brendan},
  booktitle={IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)},
  pages={4758-4765},
  year={2018},
  organization={IEEE}
}

致谢#

  • LIO-SAM 基于 LOAM(J. Zhang 和 S. Singh.LOAM:Lidar 里程计和实时映射).