Home

Awesome

To be a better FAST-LIO2

0 Introdunction

Note

1 Prerequisites

3 Build

cd YOUR_WORKSPACE/src
git clone https://github.com/Yixin-F/better_fastlio2
cd ..
catkin_make

4 How to Use

4.1 LIO Mapping using Livox, Velodyne, Ouster or Robosense

In this section, we developed a more comprehensive FAST-LIO2 version including dynamic removal using SCV-OD (accepted by T-GRS) and YOLO(optional), optimization backend using Scan Context, GPS(optional) and GTSAM. At the same time, we rewritted the mechanism of i-kdtree reconstruction to be suitable for low-power embedded devices. The basic framework is illustrated in the following figure.

<img src="./pic/3-1.png" alt="Files generated after running LIO" width="800">

You can run it by the following commands.

source ./devel/setup.bash
roslaunch fast_lio_sam mapping_*.launch

For other application, you need to first check the Config/*.yaml about the settings for different LiDAR types, we list parameters here. "-" means that it depends on your own project.

Parameters中文解释default(默认值)
lid_topic雷达话题名称-
imu_topicIMU话题名称-
time_sync_en是否进行时间软同步false
rootDir结果保存根路径-
savePCD是否保存点云帧PCDtrue
savePCDDirectory点云帧PCD保存路径PCDs/
saveSCD是否保存点云帧SCDtrue
saveSCDDirectory点云帧SCD保存路径SCDs/
saveLOG是否保存LOG文件true
saveLOGDirectoryLOG文件保存路径LOG/
map_save_en是否保存地图true
pcd_save_interval-(未使用)-
lidar_type雷达类型-
livox_typeLivox类型-
scan_line雷达线数-
blind无效距离范围(m)1.0
feature_enabled是否进行特征提取false
point_filter_num有效采样点步长1
scan_rate扫描频率-
time_unit时间单位-
camera_en是否使用相机false
camera_external相机到IMU外参-
camera_internal相机内参-
acc_cov线加速度协方差0.1
gyr_cov角速度协方差0.1
b_acc_cov线加速度偏置协方差0.001
b_gyr_cov角速度偏置协方差0.001
fov_degree视角范围(deg)180.0
det_range最远探测距离(m)100.0
cube_leni-kdtree维护立方体边长(m)500
extrinsic_est_en是否在线标定雷达到IMU外参false
mappingSurfLeafSize点云地图下采样分辨率(m)0.2
keyframeAddingDistThreshold关键帧平移阈值(m)1.0
keyframeAddingAngleThreshold关键帧旋转阈值(rad)0.2
extrinsic_T雷达到IMU平移外参-
extrinsic_R雷达到IMU旋转外参-
max_iterationESEKF最大迭代次数3
recontructKdTree是否重建i-kdtreefalse
kd_stepi-kdtree重建步长50
filter_size_map_mini-kdtree下采样分辨率(m)0.2
loopClosureEnableFlag是否开启回环检测false
loopClosureFrequency回环检测频率(hz)1.0
historyKeyframeSearchRadius有效回环检测搜索半径(m)10.0
historyKeyframeSearchTimeDiff有效回环检搜索时差(s)30.0
historyKeyframeSearchNum历史帧搜索个数1
historyKeyframeFitnessScoreicp检验阈值0.2
ground_en是否进行地面约束false
tollerance_en是否使用自由度阈值约束false
sensor_height传感器高度(m)-
z_tollerancez轴约束阈值(m)2.0
rotation_tollerancepitch和roll约束阈值(rad)0.2
path_en是否发布位姿轨迹true
scan_publish_en是否发布点云true
dense_publish_en是否发布稠密点云true
scan_bodyframe_pub_en是否发布IMU坐标系下点云false
globalMapVisualizationSearchRadiusi-kdtree搜索距离(m)10.0
globalMapVisualizationPoseDensityi-kdtree位姿采样步长1
globalMapVisualizationLeafSizei-kdtree可视化下采样分辨率(m)0.2
visulize_IkdtreeMap是否发布i-kdtreetrue

Note that if you wanna use the dynamic removal module, you have to make the "src/laserMapping.cpp line 2271-2307" effect. But differnet from the origianl dynamic removal method in T-GRS paper, we utilized the voxel center to align consecutive keyframes, which improves the real-time performance but also sacrifices some precision. So, we do not recommend using the Velodyne VLP16 for testing because its scan point cloud is too sparse. This dynamic removal module can be showed by the following figure.

<img src="./pic/3-13.png" alt="Files generated after running LIO" width="800">
  1. Here we list some important functions in src/laserMapping.cpp as follows:
Function Name中文解释
imageCallbackusb图像回调函数 720x1280
paramSettingusb相机内参与外参设置
BoxCallbackyolo目标检测包络框
publish_frame_world_color彩色点云发布
updatePath更新里程计轨迹
constraintTransformation位姿变换限制
getCurPose获得当前位姿
visualizeLoopClosure发布回环检测marker
saveFrame保存关键帧
addOdomFactor添加激光里程计因子
addLoopFactor添加回环因子
recontructIKdTreei-kdtree重建
saveKeyFramesAndFactor关键帧保存、因子添加和因子图优化主函数
correctPoses更新优化后的位姿
detectLoopClosureDistance回环检测--近邻搜索
loopFindNearKeyframes搜索最近关键帧
performLoopClosure回环检测--scan context,回环检测执行
loopClosureThread回环检测主函数
SigHandlectrl+c 终止函数
dump_lio_state_to_log保存log文件
pointBodyToWorld_ikfom点云变换到世界坐标系下
pointBodyToWorld点云变换到世界坐标系下
pointBodyToWorld点云变换到世界坐标系下
RGBpointBodyToWorld彩色点云变换到世界坐标系下
RGBpointBodyLidarToIMU彩色点云变换到IMU坐标系下
points_cache_collect删除i-kdtree缓存
lasermap_fov_segmentFoV视角分割
standard_pcl_cbk标准pcl点云回调函数
livox_pcl_cbklivox pcl点云回调函数
livox_ros_cbkros pcl点云回调函数
imu_cbkimu回调函数
LivoxRepubCallback-
map_incrementali-kdtree增量管理
publish_frame_world发布世界坐标系下点云
publish_frame_body发布IMU坐标系下点云
publish_effect_world发布世界坐标系下有效点云
publish_map发布世界坐标系下i-kdtree点云
publish_effect_world设置位姿
set_posestamp发布世界坐标系下有效点云
publish_odometry发布里程计
publish_path_imu发布IMU轨迹
publish_path发布未优化位姿
publish_path_update发布优化后位姿
CreateFile创建文件夹
savePoseService位姿保存服务
saveMapService地图保存服务
savePoseService位姿保存服务
saveMap地图保存触发
publishGlobalMap发布世界坐标系下关键帧点云
h_share_model观测更新主函数
main里程计主函数
  1. Here we list some important functions in include/dynamic-remove/tgrs.cpp as follows:
Function Name中文解释
mergeClusters聚类覆盖
findVoxelNeighbors搜索近邻体素
cluster聚类主函数
getBoundingBoxOfCloud获取聚类物体boundingbox
getCloudByVec使用vector提取点云
recognizePD识别潜在动态物体主函数
trackPD跟踪潜在动态物体主函数
saveColorCloud按照聚类类别保存彩色点云
  1. Here we list some important functions in include/sc-relo/Scancontext.cpp as follows:
Function Name中文解释
coreImportTest-
rad2degrad2deg
deg2raddeg2rad
xy2thetaxy2theta
circshift矩阵行平移
eig2stdvec矩阵转换为vector
distDirectSCsc矩阵距离计算
fastAlignUsingVkeysc矩阵列匹配
distanceBtnScanContextsc矩阵相似度计算
makeScancontextsc生成
makeRingkeyFromScancontextring生成
makeSectorkeyFromScancontextsector对应
makeAndSaveScancontextAndKeyssc生成主函数
saveScancontextAndKeyssc插入
detectLoopClosureIDBetweenSessionmulti-session重定位检测主函数
getConstRefRecentSCDsc获取
detectClosestKeyframeID回环帧ID获取
detectLoopClosureID回环帧ID获取
saveCurrentSCDscd保存
loadPriorSCDmulti-session加载先验scd
relocalizemulti-session重定位主函数

After you have run the command, there are several files being generated in the filefold "rootDir/*" as follows:

<img src="./pic/lio_file.png" alt="Files generated after running LIO" width="600">
File Name中文解释
LOG日志文件
PCDsPCD格式 关键帧点云
SCDsSCD格式 关键帧Scan Context描述子
globalMap.pcdPCD格式 全局地图
singlesession_posegraph.g2og2o格式 全局位姿图
trajectory.pcdPCD格式 xyz位姿轨迹
transformations.pcdPCD格式 xyz+rpy位姿轨迹

We show some simple results:

<img src="./pic/6-4.png" alt="Files generated after running LIO" width="600"> <img src="./pic/6-8.png" alt="Files generated after running LIO" width="600"> <img src="./pic/6-14.png" alt="Files generated after running LIO" width="600">

Now, we give some suggestion to improve this special LIO framework: Firstly, change the point-cloud map management mechanism. You can use the sparse method like hash table similar to Faster-LIO.

Secondly, improve the residual calculation method. The point-to-plane registrition during LiDAR measurement, which utilizes generalized patches instead of actual planes may lead to inconsistencies in registration. You can use true planes modeling by uncertainty.

Thirdly, find a better loop closure descriptor, such as STD, G3Reg.

Forthly, detect dynamic points during LiDAR points insertation.

4.2 Multi-session Mapping

In this section, we developed a multi-session mapping module using joint and anchor-based pose-graph optimization, which aims to reduce the cost of repeated mapping and detect differences between them. Seeing the following figure for more details.

<img src="./pic/4-3.png" alt="Files generated after running LIO" width="650">

You can run it by these commands.

source ./devel/setup.bash
roslaunch fast_lio_sam multi_session.launch

You also need to first check the Config/multi_session.yaml, we list parameters here. "-" means that it depends on your own project.

Parameters中文解释default(默认值)
sessions_dir存储多个lio结果的根路径-
central_sess_name中心阶段lio文件名称-
query_sess_name子阶段lio文件名称-
save_directory多阶段结果保存路径-
iterationisam2迭代优化次数3

Here we list some important functions in include/multi-session/incremental_mapping.cpp as follows:

Function Name中文解释
fileNameSort文件名称排序
pairIntAndStringSortstd::pair排序
Session单阶段类构建函数
initKeyPoses位姿初始化
updateKeyPoses位姿更新
loopFindNearKeyframesCentralCoord搜索中心位姿图中的近邻位姿
loopFindNearKeyframesLocalCoord搜索子位姿图中的近邻位姿
loadSessionKeyframePointclouds加载关键帧点云 PCD格式
loadSessionScanContextDescriptors加载关键帧sc SCD格式
loadSessionGraph加载位姿图 PCD格式
loadGlobalMap加载点云地图
getPoseOfIsamUsingKey从isam2中获取位姿
writeAllSessionsTrajectories保存单阶段位姿图 G2O格式
run联合位姿图优化主函数
initNoiseConstants初始化噪声
initOptimizer初始化isam2优化器
updateSessionsPoses根据anchor更新位姿图
optimizeMultisesseionGraph位姿图更新主函数
doICPVirtualRelativeICP验证
doICPGlobalRelativeICP验证
detectInterSessionSCloopssc重定位主函数
detectInterSessionRSloopsrs重定位主函数
equisampleElementssc重定位std::pair保存
addSCloopssc重定位因子添加主函数
calcInformationGainBtnTwoNodes重定位优化残差主函数
findNearestRSLoopsTargetNodeIdxrs重定位std::pair保存
addRSloopsrs重定位因子添加主函数
addSClinitTrajectoryByAnchoringoopsanchor生成主函数
addSessionToCentralGraph添加节点
loadAllSessions加载文件名称
visualizeLoopClosure可视化重定位因子边
loadCentralMap加载中心地图
getReloKeyFrames获得重定位关键帧主函数

If you wanna run this multi-session module, you should have two-stage results from the LIO mapping module, more details can be found in the last section. We give examples on Parkinglot Dataset here.

<img src="./pic/multi-session.png" alt="Files generated after running multi-session" width="800">
File Name中文解释
01 ~ 0201 ~ 02 的单阶段 lio mapping 结果,文件格式同 4.1
01**** 对 01 的 multi-session 结果

We show the details in file "0102" as follows:

<img src="./pic/multi_session_details.png" alt="Files generated after running multi-session" width="800">
File Name中文解释
01_central_aft_intersession_loops.txtTXT格式 multi-session后 中心坐标系下01位姿轨迹
01_central_bfr_intersession_loops.txtTXT格式 multi-session前 中心坐标系下01位姿轨迹
01_local_aft_intersession_loops.txtTXT格式 multi-session后 子坐标系下01位姿轨迹
01_local_bfr_intersession_loops.txtTXT格式 multi-session前 子坐标系下01位姿轨迹
02_central_aft_intersession_loops.txtTXT格式 multi-session后 中心坐标系下02位姿轨迹
02_central_bfr_intersession_loops.txtTXT格式 multi-session前 中心坐标系下02位姿轨迹
02_local_aft_intersession_loops.txtTXT格式 multi-session后 子坐标系下02位姿轨迹
02_local_bfr_intersession_loops.txtTXT格式 multi-session前 子坐标系下02位姿轨迹
aft_map2.pcdPCD格式 multi-session后 中心坐标系下0102拼接地图
aft_transformation1.pcdPCD格式 multi-session后 中心坐标系下01地图
aft_transformation2.pcdPCD格式 multi-session后 中心坐标系下02地图

We show some simple results:

<img src="./pic/6-18.png" alt="Files generated after running LIO" width="600"> <img src="./pic/6-21.png" alt="Files generated after running LIO" width="600">

Here, we also give some suggestion to improve it:

Firstly, do not update the isam2 optimizer immediately upon receiving a relocalization message, because this will cost more memory and time. You can develop some mechanism to select more important relocalization anchor.

Secondly, transfer this offline multi-session code into online mode to adapt to multi-agent exploration like m-tare.

4.3 Object-level Updating

In this section, we developed a object-level updating module to solve the ineffective machanism of point-level method. The difference detection during this updating is similar to the dynamic detection in the period of dynamic removal. As shown by following figure.

<img src="./pic/4-6.png" alt="Files generated after running LIO" width="700">

You can run it by

source ./devel/setup.bash
roslaunch fast_lio_sam object_update.launch

Note that we just update the local map in similar area, so if you wanna test object-level updating, you should manually select these areas like that we show you in src/object_update.cpp line 235~383.

<img src="./pic/update.png" alt="Files generated after running object-level updating" width="350">

The upper part means that we choose the 0-50 frames with skip as 5 in 01 to update the 0-30 frames with skip as 3 in 02. Remember that you can change the skip by rewritting the "i" in for-loop. We finally get the updated map of 01.

<img src="./pic/update_details.png" alt="Files generated after running object-level updating" width="400">
File Name中文解释
prior_map_select.pcdPCD格式 先验被更新地图的区域
cur_map_select.pcdPCD格式 当前更新地图的区域
result.pcdPCD格式 更新地图结果

The following is the expremental results:

<img src="./pic/update_ex.png" alt="Files generated after running object-level updating" width="700">

As for how to improve it, I do not know. Maybe you can integrate it into LIO revisiting or online relocalization.

4.4 Online Relocalization and Incremental Mapping

In this section, we developed a online relocalization and incremental mapping module, which aims to utilize the prior map during navigation and exploration. More details referred to the following figure.

<img src="./pic/5-1.png" alt="Files generated after running LIO" width="800">

Yeah, run it by

source ./devel/setup.bash
roslaunch fast_lio_sam online_relocalization.launch
roslaunch fast_lio_sam mapping_*.launch
rosbag play -r * *.bag

You also need to first check the Config/online_relocalization.yaml, we list parameters here. "-" means that it depends on your own project.

Parameters中文解释default(默认值)
priorDir先验知识根路径-
cloudTopiclio点云发布话题-
poseTopiclio位姿发布话题-
searchDis近邻先验关键帧搜索半径(m)5.0
searchNum近邻先验关键帧搜索个数3
trustDis区域覆盖搜索半径(m)5.0
regMode配准方法4
extrinsic_T雷达到IMU平移外参-
extrinsic_R雷达到IMU旋转外参-

The data structure in "priorDir" is similar to the result of lio mapping. Please do not open i-kdtree recontruction, loop closure detection or dynamic removal during online relocalization. You can set the manual pose in rviz by button 2D Pose Estimation. You can finally get the relocalization poses.txt and time.txt.

  1. Here we list some important functions in include/online-relo/pose_estimator.cpp as follows:
Function Name中文解释
pose_estimator在线定位类构造函数
allocateMemory-
cloudCBK里程计点云回调函数
poseCBK里程计位姿回调函数
externalCBKrviz设置位姿回调函数
run在线定位主函数
easyToRelo覆盖区域检测主函数
globalRelo全局位姿出初始化主函数
publish_odometry在线定位里程计发布
publish_path在线定位轨迹发布
  1. Here we list some important functions in include/FRICP-toolkit/registration.h as follows:
Function Name中文解释
Registeration配准类构造函数
run配准主函数

We show some simple results:

<img src="./pic/6-24.png" alt="Files generated after running LIO" width="600"> <img src="./pic/6-28.png" alt="Files generated after running LIO" width="600"> <img src="./pic/6-25.png" alt="Files generated after running LIO" width="600">

How to improve it? Nothing, actually it's meaningless.

5 File Tree

.
├── build
│   ├── atomic_configure
│   ├── catkin
│   ├── catkin_generated
│   ├── CATKIN_IGNORE
│   ├── CMakeCache.txt
│   ├── CMakeFiles
│   ├── CTestConfiguration.ini
│   ├── CTestCustom.cmake
│   ├── devel
│   └── teaser-prefix
├── CMakeLists.txt  // bulid settings
├── config
│   ├── hap_livox.yaml
│   ├── hap_ros.yaml
│   ├── kitti.yaml
│   ├── mulran.yaml
│   ├── multi_session.yaml
│   ├── nclt.yaml
│   ├── online_relo.yaml
│   ├── velodyne16.yaml
│   └── velodyne64_kitti_dataset.yaml
├── include
│   ├── analysis  // test *.py
│   ├── common_lib.h
│   ├── dynamic-remove  // dynamic removal head
│   ├── FRICP-toolkit  // robust and fast ICP head
│   ├── ikd-Tree  // i-kdtree
│   ├── IKFoM_toolkit
│   ├── kitti2bag  // kitti to bag 
│   ├── math_tools.h  // math functions
│   ├── matplotlibcpp.h  // matplotlib
│   ├── multi-session  // multi-session head
│   ├── mutexDeque.h  // mutex tool
│   ├── nanoflann.hpp  // nanoflann
│   ├── online-relo  // online relocalization head
│   ├── sc-relo  // scan context head
│   ├── sophus
│   ├── teaser-toolkit  // teaser head
│   ├── tictoc.hpp  // tictoc
│   ├── tool_color_printf.h  // colerful print
│   └── use-ikfom.hpp
├── launch
│   ├── mapping_hap_livox.launch  // livox mapping
│   ├── mapping_hap_ros.launch
│   ├── mapping_mulran.launch  // mulran mapping
│   ├── mapping_velodyne16.launch  // velodyne mapping
│   ├── mapping_velodyne64_kitti_dataset.launch  // kitti mapping
│   ├── multi_session.launch  // multi-session
│   ├── object_update.launch  // object-level updating
│   └── online_relo.launch  // online relocalization
├── LICENSE
├── Log
│   ├── fast_lio_time_log_analysis.m  // time analysis
│   ├── guide.md
│   ├── imu.txt  // imu poses output
│   └── plot.py  // plot using matplotlib
├── msg
│   ├── cloud_info.msg  // cloud msg
│   └── Pose6D.msg  // pose msg
├── note.txt  // development note
├── package.xml
├── pic
│   ├── color.png
│   ├── lio_file.png
│   ├── multi_session_details.png
│   ├── multi-session.png
│   ├── update_details.png
│   ├── update.png
│   └── yolo.png
├── README.md
├── rviz_cfg
│   ├── fastlio_hk.rviz
│   ├── loam_livox.rviz
│   ├── loc_new.rviz
│   ├── loc.rviz
│   └── sc_relo.rviz
├── src
│   ├── IMU_Processing.hpp  // imu process -main
│   ├── laserMapping.cpp  // esekf mapping -main
│   ├── multi_session.cpp  // multi-session -main
│   ├── object_update.cpp  // object-level updating -main
│   ├── online_relocalization.cpp  // online relocalization -main
│   ├── preprocess.cpp  // lidar process -main
│   └── preprocess.h
└── srv
    ├── save_map.srv  // service to save map
    └── save_pose.srv  // service to save poses

6 References

citation

If you use any code in this project, please cite paper

@article{fang2024segmented,
  title={Segmented Curved-Voxel Occupancy Descriptor for Dynamic-Aware LiDAR Odometry and Mapping},
  author={Fang, Yixin and Qian, Kun and Zhang, Yun and Shi, Tong and Yu, Hai},
  journal={IEEE Transactions on Geoscience and Remote Sensing},
  year={2024},
  publisher={IEEE}
}

and our paper

@article{fang2024liloc,
  title={LiLoc: Lifelong Localization using Adaptive Submap Joining and Egocentric Factor Graph},
  author={Fang, Yixin and Li, Yanyan and Qian, Kun and Tombari, Federico and Wang, Yue and Lee, Gim Hee},
  journal={arXiv preprint arXiv:2409.10172},
  year={2024}
}