最近在调试Livox MID360激光雷达时,发现官方提供的FAST-LIO2安装指南对RK3588平台适配不足,导致不少用户在Ubuntu20.04环境下遇到编译错误、依赖缺失等问题。作为一款基于迭代卡尔曼滤波的轻量级激光惯性里程计,FAST-LIO2在嵌入式设备上的实时性能表现优异,特别适合无人机、移动机器人等场景。本文将分享在RK3588+Ubuntu20.04环境下的完整部署方案,重点解决以下痛点:
实测环境:Rockchip RK3588开发板(8核Cortex-A76/A55),Ubuntu 20.04.6 LTS,内核版本5.10.160
首先更新apt源并安装基础编译工具:
bash复制sudo apt update && sudo apt upgrade -y
sudo apt install -y build-essential cmake git wget
针对RK3588的ARMv8架构,需要特别安装以下优化库:
bash复制sudo apt install -y libatlas-base-dev libopenblas-dev liblapack-dev
由于FAST-LIO2官方推荐使用ROS1,我们选择Noetic版本:
bash复制sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list'
sudo apt-key adv --keyserver 'hkp://keyserver.ubuntu.com:80' --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654
sudo apt update
sudo apt install -y ros-noetic-desktop-full
配置环境变量时需注意ARM平台的特殊路径:
bash复制echo "source /opt/ros/noetic/setup.bash" >> ~/.bashrc
source ~/.bashrc
FAST-LIO2要求Eigen3版本≥3.3.7,但Ubuntu20.04默认安装的是3.3.4。推荐源码编译安装:
bash复制wget https://gitlab.com/libeigen/eigen/-/archive/3.4.0/eigen-3.4.0.tar.gz
tar xzf eigen-3.4.0.tar.gz
cd eigen-3.4.0
mkdir build && cd build
cmake .. -DCMAKE_INSTALL_PREFIX=/usr/local
sudo make install
默认的PCL库可能存在点云处理性能问题,建议重新编译:
bash复制sudo apt install -y libflann-dev libboost-all-dev libvtk7-dev libqhull-dev
git clone https://github.com/PointCloudLibrary/pcl.git
cd pcl && mkdir build && cd build
cmake -DCMAKE_BUILD_TYPE=Release -DBUILD_GPU=ON ..
make -j$(nproc)
sudo make install
bash复制mkdir -p ~/fastlio_ws/src
cd ~/fastlio_ws/src
catkin_init_workspace
bash复制git clone https://github.com/hku-mars/FAST_LIO.git
cd FAST_LIO
git submodule update --init
cd ../..
编译前需要修改两处关键配置:
FAST_LIO/CMakeLists.txt:cmake复制# 添加Eigen3路径
include_directories(/usr/local/include/eigen3)
FAST_LIO/include/common_lib.h中的宏定义:cpp复制#define USE_IKFOM 1 // 启用迭代卡尔曼滤波
开始编译:
bash复制catkin_make -j4 -DCMAKE_BUILD_TYPE=Release
注意:RK3588的Cortex-A76核心建议使用-j4参数,避免内存溢出
安装Livox ROS驱动:
bash复制cd ~/fastlio_ws/src
git clone https://github.com/Livox-SDK/livox_ros_driver.git
修改livox_ros_driver/config/MID360_config.json:
json复制{
"lidar_summary_info" : {
"lidar_type": 8,
"support_features": {
"imu": true,
"rain_fog_mode": false
}
}
}
编译驱动:
bash复制cd ~/fastlio_ws
catkin_make -j4
创建FAST_LIO/launch/mid360.launch:
xml复制<launch>
<arg name="rviz" default="true" />
<node pkg="livox_ros_driver" type="livox_ros_driver_node" name="livox_lidar" output="screen">
<param name="xfer_format" value="1"/>
<param name="multi_topic" value="0"/>
<param name="data_src" value="0"/>
<param name="publish_freq" type="double" value="10.0"/>
<param name="output_data_type" value="0"/>
<param name="frame_id" value="livox_frame"/>
<param name="lvx_file_path" value="$(find livox_ros_driver)/config/MID360_config.json"/>
</node>
<node pkg="fast_lio" type="fastlio_mapping" name="laserMapping" output="screen">
<param name="map_file_path" type="string" value="" />
<param name="max_iteration" type="int" value="4" />
<param name="cube_side_length" type="double" value="200.0" />
<rosparam command="load" file="$(find fast_lio)/config/mid360.yaml" />
</node>
<group if="$(arg rviz)">
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find fast_lio)/rviz_cfg/loam_livox.rviz" />
</group>
</launch>
config/mid360.yaml中需要特别关注的参数:
yaml复制preprocess:
lidar_type: 8 # MID360设备类型码
blind: 0.5 # 过滤近距离噪点(m)
point_filter_num: 1 # 降采样率
feature_extract:
N_SCANS: 6 # 激光线数
edge_threshold: 0.1 # 边缘特征阈值
surf_threshold: 0.1 # 平面特征阈值
mapping:
acc_cov: 0.1 # 加速度计协方差
gyr_cov: 0.1 # 陀螺仪协方差
b_acc_cov: 0.0001 # 加速度计偏置协方差
b_gyr_cov: 0.0001 # 陀螺仪偏置协方差
bash复制taskset -c 4-7 roslaunch fast_lio mid360.launch
bash复制sudo cpufreq-set -g performance
common_lib.h中的缓冲区大小cpp复制#define INIT_BUFFER_SIZE 1e7 // 根据点云密度调整
问题1:Eigen版本冲突
code复制error: ‘Eigen::aligned_allocator’ has not been declared
解决方法:
bash复制sudo rm -rf /usr/include/eigen3
sudo ln -s /usr/local/include/eigen3 /usr/include/eigen3
问题2:PCL库缺失
code复制Could not find a package configuration file provided by "PCL"
解决方法:
bash复制sudo apt install -y ros-noetic-pcl-conversions ros-noetic-pcl-ros
问题3:点云畸变严重
现象:运动过程中点云拉伸变形
解决方法:
mid360.yaml中的time_offset参数mapping部分的imu_cov值问题4:CPU占用过高
优化方案:
yaml复制# 在mid360.yaml中添加:
mapping:
max_iteration: 3 # 减少迭代次数
downsample_size: 0.5 # 增大降采样粒度
在室内10m×10m环境下的测试数据:
| 指标 | 数值 |
|---|---|
| 平均处理延迟 | 23.4ms |
| 内存占用 | 1.2GB |
| 轨迹误差(RMSE) | 0.38m/100m |
| CPU占用率 | 65% |
调试建议:
mapping/fov_degree到30cube_side_length至500以上extrinsic_T参数