FAST_LIO_SAM 融入后端优化的FASTLIO SLAM 系统 前端:FAST_LIO2 后端:LIO_SAM

FAST_LIO_SAM

Front_end : fastlio2 Back_end : lio_sam

indoor

Videos : FAST-LIO-SAM Bilibili_link

Source code : FAST_LIO_SAM

Related worked

1.FAST-LIO2为紧耦合的lio slam系统,因其缺乏前端,所以缺少全局一致性,参考lio_sam的后端部分,接入GTSAM进行后端优化。

2.FAST_LIO_SLAM的作者kim在FAST-LIO2的基础上,添加SC-PGO模块,通过加入ScanContext全局描述子,进行回环修正,SC-PGO模块与FAST-LIO2解耦,非常方便,很优秀的工作。

3.FAST_LIO_LC的作者yanliang-wang,在FAST_LIO_SLAM的基础上添加了:1.基于Radius Search 基于欧式距离的回环检测搜索,增加回环搜索的鲁棒性;2.回环检测的优化结果,更新到FAST-LIO2的当前帧位姿中,幷进行ikdtree的重构,进而更新submap。

Contributions

FAST_LIO_SAM的主要贡献:

1.对比FAST_LIO_SLAMFAST_LIO_LC 使用外部接入的PGO回环检测模块进行后端优化 ,FAST_LIO_SAM 将LIO-SAM的后端GTSAM优化部分移植到FAST-LIO2的代码中,数据传输处理环节更加清晰。

2.增加关键帧的保存,可通过rosservice的指令对地图和轨迹进行保存。

3.FAST_LIO_SLAM中的后端优化,只使用了GPS的高层进行约束,GPS的高层一般噪声比较大,所以添加GPS的XYZ三维的postion进行GPS先验因子约束。

Prerequisites

  • Ubuntu 18.04 and ROS Melodic
  • PCL >= 1.8 (default for Ubuntu 18.04)
  • Eigen >= 3.3.4 (default for Ubuntu 18.04)
  • GTSAM >= 4.0.0(tested on 4.0.0-alpha2)

Build

cd YOUR_WORKSPACE/src
git clone https://github.com/kahowang/FAST_LIO_SAM.git
cd ..
catkin_make

Quick test

Loop clousre:

1 .For indoor dataset

dataset is from yanliang-wang 's FAST_LIO_LC ,dataset which includes /velodyne_points(10Hz) and /imu/data(400Hz).

roslaunch fast_lio_sam mapping_velodyne16.launch
rosbag play  T3F2-2021-08-02-15-00-12.bag  

indoor

2 .For outdoor dataset

dataset is from LIO-SAM Walking dataset: [Google Drive]

roslaunch fast_lio_sam mapping_velodyne16_lio_sam_dataset.launch
rosbag  play  walking_dataset.bag

outdoor_1

outdoor_2

3.save_map

输入如下指令到terminal中,地图文件将会保存在应文件夹中

rosservice call /save_map "resolution: 0.0
destination: ''" 
success: True
4.save_poes

输入如下指令到terminal中,poes文件将会保存在相应文件夹中

rosservice call /save_pose "resolution: 0.0
destination: ''" 
success: False

evo 绘制轨迹

evo_traj kitti optimized_pose.txt without_optimized_pose.txt -p
evo1evo2
5.some config
# Loop closure
loopClosureEnableFlag: true		      # use loopclousre or not 
loopClosureFrequency: 4.0                     # Hz, regulate loop closure constraint add frequency
surroundingKeyframeSize: 50                   # submap size (when loop closure enabled)
historyKeyframeSearchRadius: 1.5             # meters, key frame that is within n meters from current pose will be considerd for loop closure
historyKeyframeSearchTimeDiff: 30.0           # seconds, key frame that is n seconds older will be considered for loop closure
historyKeyframeSearchNum: 20                  # number of hostory key frames will be fused into a submap for loop closure
historyKeyframeFitnessScore: 0.3              # icp threshold, the smaller the better alignment

# visual iktree_map  
visulize_IkdtreeMap: true

# visual iktree_map  
recontructKdTree: true

savePCDDirectory: "/fast_lio_sam_ws/src/FAST_LIO_SAM/PCD/"        # in your home folder, starts and ends with "/". Warning: the code deletes "LOAM" folder then recreates it. See "mapOptimization" for implementation

Use GPS:

1.dataset

dataset is from LIO-SAM Park dataset: [Google Drive]

roslaunch fast_lio_sam mapping_velodyne16_lio_sam_dataset.launch
rosbag  play  parking_dataset.bag

Line Color define: path_no_optimized(blue)、path_updated(red)、path_gnss(green)

gps_optimized_path

gps_optimized_with_map

2.save_map

输入如下指令到terminal中,地图文件将会保存在应文件夹中

rosservice call /save_map "resolution: 0.0
destination: ''" 
success: True

FAST-LIO Map (no gnss prior factor) Red ; FAST-LIO-SAM (with gnss prior factor) Blue

gps_map

3.save_poes

输入如下指令到terminal中,poes文件将会保存在相应文件夹中

rosservice call /save_pose "resolution: 0.0
destination: ''" 
success: False

evo 绘制轨迹

evo_traj kitti gnss_pose.txt optimized_pose.txt  -p
FAST-LIO (no gnss prior factor)FAST-LIO-SAM (with gnss prior factor)
evo_no_optimizedevo_optimized
4.some config
# GPS Settings
useImuHeadingInitialization: false           # if using GPS data, set to "true"
useGpsElevation: false                      # if GPS elevation is bad, set to "false"
gpsCovThreshold: 2.0                        # m^2, threshold for using GPS data
poseCovThreshold: 0 #25.0                      # m^2, threshold for using GPS data  位姿协方差阈值 from isam2
5.some fun

when you want to see the path in the Map [satellite map](http://dict.youdao.com/w/satellite map/#keyfrom=E2Ctranslation),you can also use Mapvizp plugin . You can refer to my blog on CSDN.

mapviz_1

mapviz_2

Attention:

1.FAST-LIO2中对pose姿态是使用so3表示,而gtsam中,输入的relative_pose姿态是Euler RPY形式表示,需要使用罗德里格斯的公式进行转换更新。

2.参考yanliang-wang FAST-LIO-LC中的iktree reconstruct

3.在walking数据集中,因为有个别数据是在同一个地方不断手持旋转激光雷达,旋转激光雷达的角度达到了保存关键帧的阈值,在短时间内,保存了多帧相似的关键帧,导致ISAM2出现特征退化,进而里程计跑飞,可以根据数据集的情况适当调整关键帧选取的阈值参数。

4.添加GPS prior 先验因子的部分diamante,参考lio_sam的先验因子部分,对比于kim的FAST-LIO-SLAM,FAST-LIO-SLAM中只是用了GPS的高层约束,并没有使用xy方向的约束,而GPS在高层(Z轴)的误差比较大,优化过程中容易引入误差。

5.GPS先验因子中,**“useGpsElevation”**是否选择GPS的高层约束,默认不使用,因为GPS的高层噪声比较大。

6.LIO-SAM 中使用ekf_localization_node这个ROS Package 把GPS的WGS84 坐标系 转到 World系下,FAST-LIO-SAM考虑到尽量与外部的ROS package 解耦,调用 GeographicLib进行坐标转换。

some problems:

1.GNSS的经纬高噪声协方差没有转换到World系下,暂时使用latitude longtitude 的cov noise 作为x y 向的cov nosie

2.应该使用的是ENU坐标系,但是使用GeographicLib转换后的结果得到的坐标系是NED坐标系下的,原因暂时没捋清楚,待解决。(X: E Y: N Z: -D )

3.在跑较大的数据集(600s)时,偶尔出现程序崩的现象,暂时没定位问题所在,待解决。

Acknowledgements

​ In this project, the LIO module refers to FAST-LIO and the pose graph optimization refers to FAST_LIO_SLAM and LIO_SAM.The mainly idea is for FAST_LIO_LC.Thanks there great work .

​ Also thanks yanliang-wang、minzhao-zhu、peili-ma 's great help .

​ edited by kaho 2022.6.20

<think>嗯,用户想了解FAST_LIO的测距方法或实现。首先,我需要回忆一下FAST_LIO的基本原理。FAST-LIO是结合激光雷达(LiDAR)和惯性测量单元(IMU)的紧耦合里程计,主要用于实时定位和建图。根据提供的引用,特别是引用[3]提到,它使用了紧耦合的迭代卡尔曼滤波器(IKF)。这可能意味着IMU和LiDAR数据在状态估计中被紧密集成,减少误差累积。 用户提到测距,可能是指如何通过FAST-LIO实现距离测量或者里程计的计算。我需要看看各引用中的关键点。引用[1]和[3]都提到了FAST-LIO2,它可能改进了原始版本,比如使用ikd-tree进行高效的点云管理。引用[4]提到S-FAST_LIO简化了状态变量定义,使用Sophus库替代IKFOM,这可能影响状态更新和优化的方式。 测距的实现通常涉及传感器数据融合。IMU提供高频的加速度和角速度,但存在漂移;LiDAR提供准确但低频的环境扫描。紧耦合方法会同步处理这两者,用IMU的数据预测运动,再用LiDAR点云匹配进行校正。迭代卡尔曼滤波在这个过程中不断优化状态估计,可能涉及预测和更新步骤的多次迭代,如引用[3]中的Iterated Kalman Filter。 此外,引用[2]提到FAST-LIO_SLAM结合了SC-PGO(可能是基于扫描上下文的位姿图优化),这可能在后端进一步优化里程计的轨迹,减少漂移。而引用[4]中的S-FAST_LIO简化了状态变量的表示,可能使计算更高效,适合实时应用。 在代码层面,FAST-LIO的实现可能包括IMU预积分、点云特征提取、状态预测、卡尔曼增益计算、协方差更新等步骤。例如,IMU数据用于预测机器人的运动状态,然后LiDAR点云通过匹配算法(如ICP或NDT)与局部地图对齐,产生观测数据,进而更新状态估计。 用户可能需要了解具体的实现步骤或算法细节。比如,如何初始化系统,如何处理传感器数据的同步,如何管理地图(如ikd-tree的结构),以及优化方法(如位姿图优化)。此外,代码中的数学公式,如状态方程和观测方程的推导,也是关键部分。例如,引用[4]提到使用Sophus库处理李群,这可能涉及到姿态表示的优化,避免奇异性问题。 可能的相关问题包括如何选择或调整卡尔曼滤波的参数,如何处理不同LiDAR传感器的数据输入,或者在动态环境中的鲁棒性措施。此外,用户可能对FAST-LIO与其他SLAM方法(如LOAM或LIO-SAM)的区别感兴趣,或者如何在实际项目中部署和优化FAST-LIO的性能。</think>### FAST-LIO测距方法及实现解析 FAST-LIOFast LiDAR-Inertial Odometry)是一种基于**紧耦合迭代卡尔曼滤波**的实时里程计方法,通过融合LiDAR点云和IMU数据实现高精度运动估计。其核心实现流程如下: 1. **传感器数据预处理** - **IMU预积分**:在LiDAR扫描间隔内对IMU角速度和加速度进行积分,生成高频运动预测$${\Delta \mathbf{R}, \Delta \mathbf{v}, \Delta \mathbf{p}}$$[^3] - **LiDAR点云去畸变**:利用IMU积分结果对原始点云进行运动补偿,消除扫描过程中的运动畸变[^1] 2. **状态预测与更新** - 状态向量定义为$${\mathbf{x} = [\mathbf{R}, \mathbf{p}, \mathbf{v}, \mathbf{b}_g, \mathbf{b}_a]^T}$$(包含姿态、位置、速度、陀螺仪/加速度计零偏) - 迭代卡尔曼滤波通过以下步骤优化状态: $$ \mathbf{x}_{k+1} = \mathbf{x}_k \boxplus (\mathbf{K}_k (\mathbf{z}_k - h(\mathbf{x}_k))) $$ 其中$\boxplus$为流形加法,$\mathbf{K}_k$为卡尔曼增益[^3] 3. **点云匹配优化** - 使用**ikd-Tree**高效管理局部地图,支持动态插入/删除点云 - 通过最近邻搜索建立点-面/点-边约束,计算残差: $$ \mathbf{r}_i = \mathbf{n}_i^T (\mathbf{T}_{LI} \cdot \mathbf{p}_i - \mathbf{q}_i) $$ ($\mathbf{n}_i$为法向量,$\mathbf{q}_i$为地图点)[^1] 4. **关键实现优化** - **计算简化**:S-FAST_LIO版本使用Sophus库定义SE(3)状态,替代原版IKFOM框架,降低计算复杂度[^4] - **零偏补偿**:对IMU零偏进行在线标定,防止误差累积 - **并行处理**:将特征提取、地图更新等模块并行化[^2] ```cpp // 代码片段(基于FAST-LIO2简化) void propagate_state(IMUData &imu) { Eigen::Vector3d ang_vel = imu.gyro - state.bg; // 零偏补偿 Eigen::Vector3d lin_acc = imu.acc - state.ba; state.R *= Sophus::SO3d::exp(ang_vel * dt).matrix(); // 姿态更新 state.v += (state.R * lin_acc + gravity) * dt; state.p += state.v * dt; } ``` 5. **性能增强技术** - **重定位机制**:通过保存关键帧构建全局地图,实现闭环检测 - **自适应参数**:根据运动状态动态调整滤波器噪声参数 - **多传感器支持**:可扩展接入轮式编码器、GPS等传感器
评论 66
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值