前言

Livox mid360需要使用Livox-SDK2,而非Livox-SDK,以及对应的livox_ros_driver2 。并需要修改FAST_LIO中部分代码。

1. 安装Livox-SDK2

参考官方教程。 1.1. 安装CMake

sudo apt install cmake

1.2. 安装编译Livox-SDK2

git clone https://github.com/Livox-SDK/Livox-SDK2.git

cd ./Livox-SDK2/

mkdir build && cd build

cmake .. && make -j

sudo make install

注: Livox-SDK2可以下载在任何位置并编译安装。

2. 编译FAST_LIO工程

2.1. 创建ROS1工程

mkdir fast_lio && cd fast_lio

mkdir src && cd src

2.2. 在src文件夹中下载FAST_LIO源码

git clone https://github.com/hku-mars/FAST_LIO.git

cd FAST_LIO

git submodule update --init

cd ../..

2.3. 在src文件夹中下载livox_ros_driver2源码

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

3. 修改FAST_LIO代码

3.1. 修改FAST_LIO的CMakelists.txt 修改前:

find_package(catkin REQUIRED COMPONENTS

geometry_msgs

nav_msgs

sensor_msgs

roscpp

rospy

std_msgs

pcl_ros

tf

livox_ros_driver # <-修改这里

message_generation

eigen_conversions

)

修改后:

find_package(catkin REQUIRED COMPONENTS

geometry_msgs

nav_msgs

sensor_msgs

roscpp

rospy

std_msgs

pcl_ros

tf

livox_ros_driver2 # <-修改这里

message_generation

eigen_conversions

)

3.2. 修改FAST_LIO的package.xml 修改前:

livox_ros_driver

livox_ros_driver

修改后:

livox_ros_driver2

livox_ros_driver2

3.3. 修改FAST_LIO的头文件引用 分别打开FAST_LIO/src/preprocess.h、FAST_LIO/src/laserMapping.cpp 修改前:

#include

修改后:

#include

3.3. 修改FAST_LIO的命名空间 分别打开FAST_LIO/src/preprocess.h、FAST_LIO/src/preprocess.cpp、FAST_LIO/src/laserMapping.cpp中的命名空间,有多处需要修改 修改前:

livox_ros_driver::

修改后:

livox_ros_driver2::

4. 编译工程

  在工程目录的fast_lio/src/livox_ros_driver2使用下面指令编译,不要直接使用catkin_make

cd src/livox_ros_driver2

./build.sh ROS1

  编译成功如下图   如果还有编译错误提示,那就说明livox_ros_driver::没有全部改成livox_ros_driver2::,如下图:

5. 修改Livox mid360的配置

参考官方教程。

5.1. 修改电脑IP地址   建议电脑ip修改为192.168.1.5,否则需要修改下面的配置文件中对应的电脑ip,DNS地址写不写无所谓。

5.2. 修改Livox mid360 IP   打开文件fast_lio/src/livox_ros_driver2/config/MID360_config.json。Livox mid360的IP是出厂后已经固定下来的,看它上面的二维码下面的 SN 码 ,后两个数字前面再加一个1,便是其对应的ip。(例如 SN 码后两位数字为12,那它对应的ip就是192.168.1.112)。

{

"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.5", # <-这里和修改后的电脑ip一致

"cmd_data_port": 56101,

"push_msg_ip": "192.168.1.5", # <-这里和修改后的电脑ip一致

"push_msg_port": 56201,

"point_data_ip": "192.168.1.5", # <-这里和修改后的电脑ip一致

"point_data_port": 56301,

"imu_data_ip" : "192.168.1.5", # <-这里和修改后的电脑ip一致

"imu_data_port": 56401,

"log_data_ip" : "",

"log_data_port": 56501

}

},

"lidar_configs" : [

{

"ip" : "192.168.1.12", # <-这里是Livox mid360的ip

"pcl_data_type" : 1,

"pattern_mode" : 0,

"extrinsic_parameter" : {

"roll": 0.0,

"pitch": 0.0,

"yaw": 0.0,

"x": 0,

"y": 0,

"z": 0

}

}

]

}

6. 运行测试

  打开两个终端,分别运行

source devel/setup.bash

roslaunch livox_ros_driver2 msg_MID360.launch

  另外一个终端运行

source devel/setup.bash

roslaunch fast_lio mapping_mid360.launch

  运行成功截图如下

查看原文