跳转至

修改时间:2026.1.26 参与者:刘志钰

基于Ubuntu系统的驱动配置以及初步建图

Linux 系统 : ubuntu 22.04

ROS2 : humble

参考教程:ROS2+mid360 建图教程(1)

ROS2+mid360 建图教程(2)

编译 livox ros driver2(ROS2、livox、rviz、ubuntu22.04)

一、依赖配置

在我们运行之前,还需要用到如下几个依赖:

pip install catkin_pkg
pip install empy==3.3.4
pip install numpy
pip install lark
sudo apt-get install ros-humble-pcl-ros
sudo apt install ros-humble-tf-transformations
sudo pip3 install transforms3d
rclpy
import rclpy的时候出现 "libstdc++.so.6: version `GLIBCXX_3.4.30' not found"
可以在base环境中试一下 conda install -c conda-forge gcc=12.1.0

二、驱动配置

1. 安装 Livox-SDK2

Livox-SDK2 地址在 github

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

生成的共享库和静态库安装到 “/usr/local/lib” 目录下。头文件安装到 “/usr/local/include” 目录下

2. 安装 livox_ros_driver2

livox_ros_driver2 地址在 github

git clone https://github.com/Livox-SDK/livox_ros_driver2.git ws_livox/src/livox_ros_driver2

#终端进入到/src/livox_ros_driver2目录下
source /opt/ros/humble/setup.sh
./build.sh humble


#如果4.5行教程不行的话建议用ROS2最常用的编译方法,
#终端进入到/ws_livox目录下
colcon build  #如果里面有别的功能包,学过ROS2的应该知道在后面加--packages-select来指定编译
source install/setup.bash

之后再把 config 文件夹中的 MID360_config.json 文件修改了:

{
  "lidar_summary_info" : {
    "lidar_type": 8
  },
  "MID360": {
    "lidar_net_info" : {
      "cmd_data_port": 56100,
      "push_msg_port": 56200,
      "point_data_port": 56300,
      "imu_data_port": 56400,
      "log_data_port": 56500
    },
    "host_net_info" : {
      "cmd_data_ip" : "192.168.1.50",    # 这四个我标记的地方改成和设置那边IPv4一样的ip就行
      "cmd_data_port": 56101,
      "push_msg_ip": "192.168.1.50",     # 你完全可以复制我这个,完全可用
      "push_msg_port": 56201,
      "point_data_ip": "192.168.1.50",   # 对的就是这四个
      "point_data_port": 56301,
      "imu_data_ip" : "192.168.1.50",    # 四个截至到这里
      "imu_data_port": 56401,
      "log_data_ip" : "",
      "log_data_port": 56501
    }
  },
  "lidar_configs" : [
    {
      "ip" : "192.168.1.146",            # 这个不一样了,ip最后改成1+雷达序列码后两位(雷达本体旁边贴纸)
      "pcl_data_type" : 1,
      "pattern_mode" : 0,
      "extrinsic_parameter" : {
        "roll": 0.0,
        "pitch": 0.0,
        "yaw": 0.0,
        "x": 0,
        "y": 0,
        "z": 0
      }
    }
  ]
}

#!!!!!!!!!!记住除了我标注的地方其他地方不用动!!!!!!!!!!

三、主机配置

进入主机设置 - 网络,然后在有线处添加,名字随便你取,我们一般取 mid-360,然后点击 IPv4,改为手动,在底下添加如下所示:

最后一切设置完毕后就点击右上角的应用即可。

四、功能包运行

终端进入到 /src/livox_ros_driver2 目录下,将激光雷达与电脑连接,输入以下指令就可以看到在 Rviz2 上生成的点云图了。

ros2 launch livox_ros_driver2 rviz_MID360_launch.py

激光雷达SLAM算法fast_lio部署与配置

这边我找了一个 fast_lio2 的开源地址在 github

下载完后的应该是一个名叫 FAST_LIO_ROS2_ros2 之类的名字

我建议使用 vscode 全局将此类名字更改为 fast_lio, 这是真理,不然就有可能 g

剩下的就是正常编译以及添加 source 等等,注意开两个终端

分别运行以下代码:

ros2 launch livox_ros_driver2 msg_MID360_launch.py

ros2 launch fast_lio mapping_mid360.launch.py


# 应该知道哪个运行哪个的吧

不过开两个终端太烦了,我们来整合一下 msg_MID360_launch.pymapping_mid360.launch.py 这两个 launch 文件。

首先在 fast_lio 功能包的 launch 文件夹里面建一个启动文件,名字随意,然后输入如下代码:

import os.path
import os

from ament_index_python.packages import get_package_share_directory

import launch
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from launch.conditions import IfCondition

from launch_ros.actions import Node



xfer_format   = 1    # 0-使用 PointCloud2 格式(PointXYZRTL), 1-自定义点云格式
multi_topic   = 0    # 0-所有 LiDARs 共享同一话题, 1-每个 LiDAR 使用独立话题
data_src      = 0    # 0-数据来源于 lidar, 其他数字属于无效数据源
publish_freq  = 10.0 # 发布频率, 5.0, 10.0, 20.0, 50.0, etc.
output_type   = 0
frame_id      = 'livox_frame'  # 坐标框架ID

# 指定 LiDAR 数据文件的路径
lvx_file_path = '/home/hyz/project/ws_livox/src/Indoor_sampledata.lvx2'

cmdline_bd_code = 'livox0000000001'

 # 完整的用户配置文件路径
user_config_path = '/home/hyz/project/ws_livox/src/livox_ros_driver2/config/MID360_config.json'


livox_ros2_params = [
    {"xfer_format": xfer_format},
    {"multi_topic": multi_topic},
    {"data_src": data_src},
    {"publish_freq": publish_freq},
    {"output_data_type": output_type},
    {"frame_id": frame_id},
    {"lvx_file_path": lvx_file_path},
    {"user_config_path": user_config_path},
    {"cmdline_input_bd_code": cmdline_bd_code}
]



def generate_launch_description():

    livox_driver = Node(
        package='livox_ros_driver2',
        executable='livox_ros_driver2_node',
        name='livox_lidar_publisher',
        output='screen',
        parameters=livox_ros2_params
        )



    package_path = get_package_share_directory('fast_lio')
    default_config_path = os.path.join(package_path, 'config')
    default_rviz_config_path = os.path.join(
        package_path, 'rviz', 'fastlio.rviz')

    use_sim_time = LaunchConfiguration('use_sim_time')
    config_path = LaunchConfiguration('config_path')
    config_file = LaunchConfiguration('config_file')
    rviz_use = LaunchConfiguration('rviz')
    rviz_cfg = LaunchConfiguration('rviz_cfg')

    declare_use_sim_time_cmd = DeclareLaunchArgument(
        'use_sim_time', default_value='false',
        description='Use simulation (Gazebo) clock if true'
    )
    declare_config_path_cmd = DeclareLaunchArgument(
        'config_path', default_value=default_config_path,
        description='Yaml config file path'
    )
    decalre_config_file_cmd = DeclareLaunchArgument(
        'config_file', default_value='mid360.yaml',
        description='Config file'
    )
    declare_rviz_cmd = DeclareLaunchArgument(
        'rviz', default_value='true',
        description='Use RViz to monitor results'
    )
    declare_rviz_config_path_cmd = DeclareLaunchArgument(
        'rviz_cfg', default_value=default_rviz_config_path,
        description='RViz config file path'
    )

    fast_lio_node = Node(
        package='fast_lio',
        executable='fastlio_mapping',
        parameters=[PathJoinSubstitution([config_path, config_file]),
                    {'use_sim_time': use_sim_time}],
        output='screen'
    )
    rviz_node = Node(
        package='rviz2',
        executable='rviz2',
        arguments=['-d', rviz_cfg],
        condition=IfCondition(rviz_use)
    )

    ld = LaunchDescription()
    ld.add_action(declare_use_sim_time_cmd)
    ld.add_action(declare_config_path_cmd)
    ld.add_action(decalre_config_file_cmd)
    ld.add_action(declare_rviz_cmd)
    ld.add_action(declare_rviz_config_path_cmd)

    ld.add_action(livox_driver)
    ld.add_action(fast_lio_node)
    ld.add_action(rviz_node)

    return ld

其中 lvx_file_path 目前我还没花时间研究有什么实质性的用处,大概是类似于数据集训练出的模型的东西,帮助得到更好的建图效果。

其中 user_config_path 参数需要 /ws_livox/src/livox_ros_driver2/config/MID360_config.json 的绝对位置,你们自行在前端补全。

Livox_mid360跑通代码

https://github.com/XJU-Hurricane-Team/Vision_coding