Lightning-Speed Lidar Localization and Mapping
Lightning-LM is a complete laser mapping and localization module.
Features of Lightning-LM:
- [done] Complete 3D Lidar SLAM, fast LIO front-end (AA-FasterLIO), standard
- [done] 3D to 2D map conversion (g2p5), optional, if selected outputs real-time 2D grid map, can be saved
- [done] Real-time loop closure detection, standard, performs back-end loop closure detection and correction if selected
- [done] Smooth high-precision 3D Lidar localization, standard
- [done] Dynamic loading scheme for map partitions, suitable for large-scale scenes
- [done] Localization with separate dynamic and static layers, adaptable to dynamic scenes, selectable strategies for dynamic layer, optional, if selected saves dynamic layer map content, three strategies available (short-term, medium-term, permanent), default is permanent
- [done] High-frequency IMU smooth output, standard, 100Hz
- GPS geoinformation association, optional (TODO)
- Vehicle odometry input, optional (TODO)
- [done] Lightweight optimization library miao and incremental optimization (derived from g2o, but lighter and faster, supports incremental optimization, no need to rebuild optimization model), standard, used in both loop closure and localization
- [done] Two verification schemes: offline and online. Offline allows breakpoint debugging with strong consistency. Online allows multi-threaded concurrency, fast processing speed, dynamic frame skipping, and low resource usage.
- [done] High-frequency output based on extrapolator and smoother, adjustable smoothing factor
- [done] High-performance computing: All the above features can run using less than one CPU core on the pure CPU side (online localization 0.8 cores, mapping 1.2 cores, 32-line LiDAR, without UI).
- Mapping on the VBR campus dataset:
- Localization on VBR
Ubuntu 22.04 or higher.
Ubuntu 20.04 should also work, but not tested.
- ros2 humble or above
- Pangolin (for visualization, see thirdparty)
- OpenCV
- PCL
- yaml-cpp
- glog
- gflags
- pcl_conversions
On Ubuntu 22.04, run: bash ./scripts/install_dep.sh.
Build this package with colcon build.
Then source install/setup.bash to use it.
After building, you will get the corresponding online/offline mapping and localization programs for this package. The offline programs are suitable for scenarios with offline data packets to quickly obtain mapping/localization results, while the online programs are suitable for scenarios with actual sensors to obtain real-time results.
For example, calling the offline mapping program on the NCLT dataset:
ros2 run lightning run_slam_offline --input_bag ~/data/NCLT/20130110/20130110.db3 --config ./config/default_nclt.yaml
If you want to call the online version, just change the offline part to online.
You can directly use our converted datasets. If you need the original datasets, you need to convert them to the ros2 db3 format.
Converted dataset addresses:
- OneDrive: https://1drv.ms/f/c/1a7361d22c554503/EpDSys0bWbxDhNGDYL_O0hUBa2OnhNRvNo2Gey2id7QMQA?e=7Ui0f5
- BaiduYun: https://pan.baidu.com/s/1NEGQcYoMtd57oqog09pB6w?pwd=5v8h 提取码: 5v8h
Original dataset addresses:
- NCLT dataset: http://robots.engin.umich.edu/nclt/
- UrbanLoco dataset: https://github.com/weisongwen/UrbanLoco
- VBR dataset: https://www.rvp-group.net/slam-dataset.html
- Real-time mapping (real-time bag playback)
- Start the mapping program:
ros2 run lightning run_slam_online --config ./config/default_nclt.yaml - Play the data bag
- Save the map
ros2 service call /lightning/save_map lightning/srv/SaveMap "{map_id: new_map}"
- Start the mapping program:
- Offline mapping (traverse data, faster)
ros2 run lightning run_slam_offline --config ./config/default_nclt.yaml --input_bag [bag_file]- It will automatically save to the data/new_map directory after finishing.
- Viewing the map
- View the full map:
pcl_viewer ./data/new_map/global.pcd - The actual map is stored in blocks, global.pcd is only for displaying the result.
- map.pgm stores the 2D grid map information.
- Note that during the localization program run or upon exit, results for dynamic layers might also be stored in the same directory, so there might be more files.
- View the full map:
- Real-time localization
- Write the map path to
system.map_pathin the yaml file, default isnew_map(consistent with the mapping default). - Place the vehicle at the mapping starting point.
- Start the localization program:
ros2 run lightning run_loc_online --config ./config/default_nclt.yaml - Play the bag or input sensor data.
- Write the map path to
- Offline localization
ros2 run lightning run_loc_offline --config ./config/default_nclt.yaml --input_bag [bag_file]
- Receiving localization results
- The localization program outputs TF topics at the same frequency as the IMU (50-100Hz).
First, you need to know your LiDAR type and set the corresponding fasterlio.lidar_type. Set it to 1 for Livox series, 2 for Velodyne, 3 for Ouster.
If it's not one of the above types, you can refer to the Velodyne setup method.
A simpler way is to first record a ros2 bag, get offline mapping and localization working, and then debug the online situation.
You usually need to modify common.lidar_topic and common.imu_topic to set the LiDAR and IMU topics.
The IMU and LiDAR extrinsic parameters can default to zero; we are not sensitive to them.
The fasterlio.time_scale related to timestamps is sensitive. You should pay attention to whether the LiDAR point cloud has timestamps for each point and if they are calculated correctly. This code is in core/lio/pointcloud_preprocess.
Refer to the next section for other parameter adjustments.
You can fine-tune Lightning by modifying the configuration file, turning some features on or off. Common configuration items include:
system.with_loop_closingWhether loop closure detection is neededsystem.with_uiWhether 3D UI is neededsystem.with_2duiWhether 2D UI is neededsystem.with_g2p5Whether grid map is neededsystem.map_pathStorage path for the mapfasterlio.point_filter_numPoint sampling number. Increasing this results in fewer points, faster computation, but not recommended to set above 10.g2p5.esti_floorWhether g2p5 needs to dynamically estimate ground parameters. If the LiDAR rotates horizontally and the height is constant, you can turn this option off.g2p5.grid_map_resolutionResolution of the grid map
- [done] UI displays trajectory after loop closure
- [done] Grid map saved in ROS-compatible format
- [done] Check if grid map resolution values are normal
- Force 2D output
- Additional convenience features (turn localization on/off, reinitialize, specify location, etc.)
-
Converting ros1 data to ros2 Install
pip install -i https://pypi.tuna.tsinghua.edu.cn/simple rosbagsConvert:
rosbags-convert --src [your_ROS1_bag_file.bag] --dst [output_ROS2_bag_directory]
Lightning-LM 是一个完整的激光建图+定位模块。
Lightning-LM特性:
- [done] 完整的3D Lidar SLAM,快速的LIO前端(AA-FasterLIO),标配
- [done] 3D至2D地图转换(g2p5),选配,选上的话会输出实时的2D栅格,可以保存
- [done] 实时回环检测,标配,选上的话会进行后端回环检测并闭环
- [done] 流畅的高精3D Lidar 定位,标配
- [done] 地图分区动态加载方案,适用大场景
- [done] 动静态图层分离定位,适配动态场景,可选择动态图层的策略,选配,选上的话会保存动态图层的地图内容,有三种策略可以选(短期、中期、永久),默认永久
- [done] 高频率IMU平滑输出,标配,100Hz
- GPS地理信息关联,选配 (TODO)
- 车辆里程计输入,选配 (TODO)
- [done] 轻量优化库miao以及增量式优化(来自g2o,但更轻更快,支持增量优化,不需要重新构建优化模型),标配,在回环、定位中均有用到
- [done] 离线与在线两种验证方案。离线可以断点调试,一致性强。在线可以多线程并发,处理速度快,可以设置动态跳帧,占用低。
- [done] 基于外推器和平滑器的高频率输出,平滑因子可调
- [done] 高性能计算:以上这些特性在纯CPU端不到一个核心就可以运行(在线定位0.8个核,建图1.2个核,32线雷达,无UI情况)
- VBR campus数据集上的建图:
- VBR上的定位
Ubuntu 22.04 或更高版本。
Ubuntu 20.04 应该也可行,未测试。
- ros2 humble 及以上
- Pangolin(用于可视化,见thirdparty)
- OpenCV
- PCL
- yaml-cpp
- glog
- gflags
- pcl_conversions
在Ubuntu 22.04上,执行:bash ./scripts/install_dep.sh即可。
colcon build本包即可。
然后source install/setup.bash即可使用。
编译后,会得到本包对应的在线/离线建图程序与定位程序。离线程序适用于存在离线数据包,快速得到建图/定位结果的方案,在线程序则适用于有实际传感器,得到实时结果的方案。
例如:在NCLT数据集上调用离线建图程序:
ros2 run lightning run_slam_offline --input_bag ~/data/NCLT/20130110/20130110.db3 --config ./config/default_nclt.yaml
如果希望调用在线的版本,则将offline部分改成online即可。
您可以直接使用我们转换完的数据集。如果需要原始的数据集,您需要将它们转换到ros2的db3格式。
转换后的数据集地址:
- OneDrive: https://1drv.ms/f/c/1a7361d22c554503/EpDSys0bWbxDhNGDYL_O0hUBa2OnhNRvNo2Gey2id7QMQA?e=7Ui0f5
- BaiduYun: https://pan.baidu.com/s/1NEGQcYoMtd57oqog09pB6w?pwd=5v8h 提取码: 5v8h
原始数据集地址:
- NCLT 数据集:http://robots.engin.umich.edu/nclt/
- UrbanLoco 数据集: https://github.com/weisongwen/UrbanLoco
- VBR 数据集:https://www.rvp-group.net/slam-dataset.html
- 实时建图(实时播包)
- 启动建图程序:
ros2 run lightning run_slam_online --config ./config/default_nclt.yaml - 播放数据包
- 保存地图
ros2 service call /lightning/save_map lightning/srv/SaveMap "{map_id: new_map}"
- 启动建图程序:
- 离线建图(遍历跑数据,更快一些)
ros2 run lightning run_slam_offline --config ./config/default_nclt.yaml --input_bag 数据包- 结束后会自动保存至data/new_map目录下
- 查看地图
- 查看完整地图:
pcl_viewer ./data/new_map/global.pcd - 实际地图是分块存储的,global.pcd仅用于显示结果
- map.pgm存储了2D栅格地图信息
- 请注意,在定位程序运行过程中或退出时,也可能在同目录存储动态图层的结果,所以文件可能会有更多。
- 查看完整地图:
-
实时定位
- 将地图路径写到yaml中的 system-map_path 下,默认是new_map(和建图默认一致)
- 将车放在建图起点处
- 启动定位程序:
ros2 run lightning run_loc_online --config ./config/default_nclt.yaml - 播包或者输入传感器数据即可
-
离线定位
ros2 run lightning run_loc_offline --config ./config/default_nclt.yaml --input_bag 数据包
-
接收定位结果
- 定位程序输出与IMU同频的TF话题(50-100Hz)
首先您需要知道自己的雷达类型,设置对应的fasterlio.lidar_type类型。livox系列的配置成1,Velodyne的设置成2,ouster设置成3. 如果不在以上种类,可以参考velodyne的设置方式。
比较简单的方式是先录一个ros2的数据包,将离线的建图、定位调通后,再去调试在线的情况。
您通常需要修改common.lidar_topic和common.imu_topic来设置雷达与imu的话题。
imu和雷达外参默认为零就好,我们对这个不敏感。
时间戳相关的fasterlio.time_scale是敏感的。您最好关注一下雷达点云是否带有每个点的时间戳,以及它们是否计算正确。这些代码在core/lio/pointcloud_preprocess里.
其他参数调整参考下一节。
您可以在配置文件中对lightning进行微调,打开或者关闭一些功能。常见的配置项有:
- system.with_loop_closing 是否需要回环检测
- system.with_ui 是否需要3DUI
- system.with_2dui 是否需要2DUI
- system.with_g2p5 是否需要栅格地图
- system.map_path 地图的存储路径
- fasterlio.point_filter_num 点的采样数。调大后点数会少一些,计算更快,但不建议调到10以上。
- g2p5.esti_floor g2p5是否需要动态估计地面参数。如果雷达水平旋转且高度不变,可以关闭此选项.
- g2p5.grid_map_resolution 栅格地图的分辨率
- [done] UI显示闭环后轨迹
- [done] 栅格地图保存为兼容ROS的形式
- [done] 检查栅格地图的分辨率取值是否正常
- 强制2D输出
- 额外便利性功能(打开关闭定位,重新初始化,指定位置等)
-
将ros1数据转换至ros2 安装
pip install -i https://pypi.tuna.tsinghua.edu.cn/simple rosbags转换:
rosbags-convert --src [你的ROS1_bag文件.bag] --dst [输出ROS2bag目录]