基于mid-360的FAST_LIO2,Point-LIO,faster-lio,LIO-SAM部署(持续更新)

硬件:orangepi5 8G+32G (RK3588S ARM64)

系统:ubuntu 20.04

FAST_LIO2:

1.编译livox-SDK2

git clone https://github.com/Livox-SDK/Livox-SDK2.git
cd ./Livox-SDK2/
mkdir build && cd build
cmake .. && make -j8
sudo make install

2.编译FAST_LIO

2.1 创建工作空间

mkdir FAST-LIO2 && cd FAST-LIO2
mkdir src && cd src

2.2 下载livox_ros_driver2源码

git clone https://github.com/Livox-SDK/livox_ros_driver2.git
cd livox_ros_driver2
./build.sh ROS1

2.3 下载FAST_LIO2源码

git clone https://github.com/hku-mars/FAST_LIO.git
cd FAST_LIO
git submodule update --init
cd ../..

3.修改FAST_LIO代码

3.1 FAST_LIO2的CMakelists.txt

find_package(catkin REQUIRED COMPONENTS
  ...
  livox_ros_driver
  ...
)

改为

find_package(catkin REQUIRED COMPONENTS
  ...
  livox_ros_driver2
  ...
)

3.2 FAST_LIO2的package.xml

<build_depend>livox_ros_driver</build_depend>
<run_depend>livox_ros_driver</run_depend>

改为

<build_depend>livox_ros_driver2</build_depend>
<run_depend>livox_ros_driver2</run_depend>

3.3 FAST_LIO2的头文件引用

用vscode的搜索一键替换

#include <livox_ros_driver/CustomMsg.h>

改为

#include <livox_ros_driver2/CustomMsg.h>

3.4 FAST_LIO2的命名空间

用vscode的搜索一键替换

livox_ros_driver::

改为

livox_ros_driver2::

编译:

catkin_make

Point-LIO:

1.编译livox-SDK

git clone https://github.com/Livox-SDK/Livox-SDK.git
cd Livox-SDK
cd build && cmake ..
make -j8
sudo make install

2.编译Point-LIO

2.1 编译livox_ros_driver

mkdir -p Point-LIO/src #-p  代表递归创建文件夹
cd Point-LIO/src
git clone https://github.com/Livox-SDK/livox_ros_driver.git
cd ..
catkin_make

2.1 编译Point-LIO

cd src
git clone https://github.com/hku-mars/Point-LIO.git
cd ..
catkin_make

  src/config 文件夹下增加的 mid360.yaml 文件配置:

common:
    lid_topic:  "/livox/lidar" 
    imu_topic:  "/livox/imu" 
    con_frame: false # true: if you need to combine several LiDAR frames into one
    con_frame_num: 1 # the number of frames combined
    cut_frame: false # true: if you need to cut one LiDAR frame into several subframes
    cut_frame_time_interval: 0.1 # should be integral fraction of 1 / LiDAR frequency
    time_lag_imu_to_lidar: 0.0 # Time offset between LiDAR and IMU calibrated by other algorithms, e.g., LI-Init (find in Readme)
                               # the timesample of IMU is transferred from the current timeline to LiDAR's timeline by subtracting this value
 
preprocess:
    lidar_type: 1 
    scan_line: 4
    timestamp_unit: 1           # the unit of time/t field in the PointCloud2 rostopic: 0-second, 1-milisecond, 2-microsecond, 3-nanosecond.
    blind: 0.5 
 
mapping:
    imu_en: true
    start_in_aggressive_motion: false # if true, a preknown gravity should be provided in following gravity_init
    extrinsic_est_en: false # for aggressive motion, set this variable false
    imu_time_inte: 0.005 # = 1 / frequency of IMU
    satu_acc: 3.0 # the saturation value of IMU's acceleration. not related to the units
    satu_gyro: 35 # the saturation value of IMU's angular velocity. not related to the units
    acc_norm: 1.0 # 1.0 for g as unit, 9.81 for m/s^2 as unit of the IMU's acceleration
    lidar_meas_cov: 0.001 # 0.001; 0.01
    acc_cov_output: 500
    gyr_cov_output: 1000 
    b_acc_cov: 0.0001 
    b_gyr_cov: 0.0001 
    imu_meas_acc_cov: 0.1 #0.1 # 0.1
    imu_meas_omg_cov: 0.1 #0.01 # 0.1
    gyr_cov_input: 0.01 # for IMU as input model
    acc_cov_input: 0.1 # for IMU as input model
    plane_thr: 0.1 # 0.05, the threshold for plane criteria, the smaller, the flatter a plane
    match_s: 81
    fov_degree: 360 
    det_range: 100
    gravity_align: true # true to align the z axis of world frame with the direction of gravity, and the gravity direction should be specified below
    gravity: [0.0, 0.0, -9.810] # [0.0, 9.810, 0.0] # gravity to be aligned
    gravity_init: [0.0, 0.0, -9.810] # [0.0, 9.810, 0.0] # # preknown gravity in the first IMU body frame, use when imu_en is false or start from a non-stationary state
    extrinsic_T: [ -0.011, -0.02329, 0.04412 ]
    extrinsic_R: [ 1, 0, 0,
                   0, 1, 0,
                   0, 0, 1 ]
 
odometry: 
    publish_odometry_without_downsample: false
 
publish:
    path_en: true                 # false: close the path output
    scan_publish_en: true         # false: close all the point cloud output
    scan_bodyframe_pub_en: false  # true: output the point cloud scans in IMU-body-frame
 
pcd_save:
    pcd_save_en: false
    interval: -1                 # how many LiDAR frames saved in each pcd file; 
                                 # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames.

 src/launch 文件夹下增加 mapping_mid360.launch 文件: 

<launch>
<!-- Launch file for Livox AVIA LiDAR -->
 
	<arg name="rviz" default="true" />
 
	<node pkg="point_lio" type="pointlio_mapping" name="laserMapping" output="screen">
	<rosparam command="load" file="$(find point_lio)/config/mid360.yaml" />
	<param name="use_imu_as_input" type="bool" value="1"/> <!--change to 1 to use IMU as input of Point-LIO-->
	<param name="prop_at_freq_of_imu" type="bool" value="1"/>
	<param name="check_satu" type="bool" value="1"/>
	<param name="init_map_size" type="int" value="10"/>
	<param name="point_filter_num" type="int" value="1"/> <!--4, 3--> 
	<param name="space_down_sample" type="bool" value="1" />  
	<param name="filter_size_surf" type="double" value="0.3" /> <!--0.5, 0.3, 0.2, 0.15, 0.1--> 
	<param name="filter_size_map" type="double" value="0.2" /> <!--0.5, 0.3, 0.15, 0.1-->
	<param name="cube_side_length" type="double" value="2000" /> <!--1000-->
	<param name="runtime_pos_log_enable" type="bool" value="0" /> <!--1-->
	</node>
	<group if="$(arg rviz)">
	<node launch-prefix="nice" pkg="rviz" type="rviz" name="rviz" args="-d $(find point_lio)/rviz_cfg/loam_livox.rviz" />
	</group>
 
	launch-prefix="gdb -ex run --args"
 
</launch>

运行

roslaunch point_lio mapping_mid360.launch

faster-lio

1.编译livox-SDK

git clone https://github.com/Livox-SDK/Livox-SDK.git
cd Livox-SDK
cd build && cmake ..
make -j8
sudo make install

2.编译faster-lio 

2.1 编译livox_ros_driver

mkdir -p Point-LIO/src #-p  代表递归创建文件夹
cd Point-LIO/src
git clone https://github.com/Livox-SDK/livox_ros_driver.git
cd ..
catkin_make

2.2  编译faster-lio

mkdir -p faster_lio_ws/src
cd faster_lio_ws/src
git clone https://github.com/gaoxiang12/faster-lio.git
cd ..
catkin_make

src/config 文件夹下增加的 mid360.yaml 文件配置

common:
  lid_topic: "/livox/lidar"
  imu_topic: "/livox/imu"
  time_sync_en: false         # ONLY turn on when external time synchronization is really not possible
 
preprocess:
  lidar_type: 1                # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR,
  scan_line: 4
  blind: 0.5
  time_scale: 1e-3
 
mapping:
  acc_cov: 0.1
  gyr_cov: 0.1
  b_acc_cov: 0.0001
  b_gyr_cov: 0.0001
  fov_degree: 360
  det_range: 100.0
  extrinsic_est_en: false      # true: enable the online estimation of IMU-LiDAR extrinsic
  extrinsic_T: [ -0.011, -0.02329, 0.04412  ]
  extrinsic_R: [ 1, 0, 0,
                 0, 1, 0,
                 0, 0, 1 ]
 
publish:
  path_publish_en: false
  scan_publish_en: true       # false: close all the point cloud output
  scan_effect_pub_en: true    # true: publish the pointscloud of effect point
  dense_publish_en: false       # false: low down the points number in a global-frame point clouds scan.
  scan_bodyframe_pub_en: true  # true: output the point cloud scans in IMU-body-frame
 
path_save_en: true                 # 保存轨迹,用于精度计算和比较
 
pcd_save:
  pcd_save_en: true
  interval: -1                 # how many LiDAR frames saved in each pcd file;
  # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames.
 
feature_extract_enable: false
point_filter_num: 3
max_iteration: 3
filter_size_surf: 0.5
filter_size_map: 0.5             # 暂时未用到,代码中为0, 即倾向于将降采样后的scan中的所有点加入map
cube_side_length: 1000
 
ivox_grid_resolution: 0.5        # default=0.2
ivox_nearby_type: 18             # 6, 18, 26
esti_plane_threshold: 0.1        # default=0.1

在 src/launch 文件夹下增加 mapping_mid360.launch:

<launch>
<!-- Launch file for Livox AVIA LiDAR -->
 
	<arg name="rviz" default="true" />
 
	<rosparam command="load" file="$(find faster_lio)/config/mid360.yaml" />
 
	<param name="feature_extract_enable" type="bool" value="0"/>
	<param name="point_filter_num_" type="int" value="3"/>
	<param name="max_iteration" type="int" value="3" />
	<param name="filter_size_surf" type="double" value="0.5" />
	<param name="filter_size_map" type="double" value="0.5" />
	<param name="cube_side_length" type="double" value="1000" />
	<param name="runtime_pos_log_enable" type="bool" value="1" />
    <node pkg="faster_lio" type="run_mapping_online" name="laserMapping" output="screen" />
 
	<group if="$(arg rviz)">
	<node launch-prefix="nice" pkg="rviz" type="rviz" name="rviz" args="-d $(find faster_lio)/rviz_cfg/loam_livox.rviz" />
	</group>
 
</launch>

运行:

roslaunch faster_lio mapping_mid360.launch

LIO-SAM:

 1.编译livox-SDK

git clone https://github.com/Livox-SDK/Livox-SDK.git
cd Livox-SDK
cd build && cmake ..
make -j8
sudo make install

2.编译LIO-SAM

2.1 编译livox_ros_driver

mkdir -p Point-LIO/src #-p  代表递归创建文件夹
cd Point-LIO/src
git clone https://github.com/Livox-SDK/livox_ros_driver.git
cd ..
catkin_make

2.2  编译faster-lio

依赖:

sudo apt-get install -y ros-noetic-navigation
sudo apt-get install -y ros-noetic-robot-localization
sudo apt-get install -y ros-noetic-robot-state-publisher
sudo add-apt-repository ppa:borglab/gtsam-release-4.0
sudo apt install libgtsam-dev libgtsam-unstable-dev

下载代码:

mkdir -p LIOSAM/src
cd LIOSAM/src
git clone https://github.com/nkymzsy/LIO-SAM-MID360.git

修改CMakelists:

C++11  改成C++14

修改src/LIO-SAM-MID360-master/include 目录下,utility.h 文件

#include <opencv/cv.h> 改为 #include <opencv2/opencv.hpp>

#include <pcl/kdtree/kdtree_flann.h> 头文件放到 #include <opencv2/opencv.hpp>前面

编译:

cd ~/LIOSAM
catkin_make

启动

roslaunch lio_sam run6axis.launch

LIOSAM-mid360的yaml文件的参数好像有点问题,会飘,通常出现在雷达和IMU没标定好的情况。过两天测试好再更新这些问题解决办法。

感觉大佬的部署教学,有些部署错误这里已修改多层长走廊场景下Fast-Lio2、Point-Lio、LIO-SAM、Faster-Lio建图对比视频_哔哩哔哩_bilibili

### 如何使用 Fast-LIO 实现 SLAM 建图 #### 准备工作 为了成功实现基于Fast-LIO的SLAM建图,需先准备好硬件设备并配置软件环境。通常情况下,这涉及到LiDAR传感器(如Livox MID-360)以及惯性测量单元(IMU),这些组件的数据流将被用于构建地图。 对于软件方面,在Ubuntu操作系统环境下推荐采用ROS(机器人操作系统)作为开发平台。确保已正确安装ROS版本,并设置好对应的Python解释器和其他依赖项[^3]。 #### 下载与编译源码 获取Fast-LIO项目的最新版源代码是必要的第一步。可以通过GitHub仓库克隆项目到本地计算机上: ```bash git clone --recursive https://github.com/hku-mars/FAST_LIO.git ~/catkin_ws/src/ cd ~/catkin_ws && catkin_make -j1 source devel/setup.bash ``` 上述命令会拉取Fast-LIO库至指定目录内,并完成编译过程以便后续调用其功能节点[^1]。 #### 配置参数文件 根据所使用的具体型号调整相应的启动脚本中的参数设定非常重要。例如当选用Livox系列激光雷达时,则应参照官方文档修改`mapping_avia.launch`内的相应字段来匹配实际连接情况;同样地也要针对IMU数据同步等问题作出适当处理[^4]。 #### 启动系统 一切准备就绪之后就可以尝试执行完整的SLAM流程了。打开终端窗口依次输入如下指令以激活各个服务端口并加载预设好的场景模型: ```bash roslaunch livox_ros_driver2 msg_MID360.launch # 开启LiDAR驱动程序 roslaunch fast_lio mapping_avia.launch # 执行Fast-LIO SLAM算法 rviz -d ./config/rviz_config.rviz # 可视化显示结果 ``` 以上步骤能够帮助用户快速搭建起一套基于Fast-LIO框架下的三维空间重建实验环境[^5]。 #### 数据保存与分析 最后一步是在测试过程中定期保存生成的地图文件供后期研究之用。一般而言,可通过RVIZ插件或者专门设计的小工具来进行此操作。此外还可以利用MATLAB等科学计算工具进一步解析所得成果的质量指标。
评论 14
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值