MID-360雷达使用指南
注意事项:Jetson orin nano中,如果使用宇树雷达,则添加ws_livox工作空间,如果是mid-360z则添加mid_ws工作空间,同时添加可能会出现功能包的冲突,导致启动调用出错
简介:在实际使用3维激光定位的过程中,测试了宇树雷达和MID-360雷达。实测宇树雷达震动太大,在无人机可以科研使用,不建议工业级产品使用,MID-360相对效果要好得多,稳定性等方面也远高于宇树雷达
前言:Livox mid360需要使用Livox-SDK2,而非Livox-SDK,以及对应的livox_ros_driver2 。并需要修改FAST_LIO中部分代码。相反宇树雷达则使用Livox-SDK和livox_ros_driver。为了方便共存使用,jetson orin nano镜像设置了两个工作空间,其中ws_livox安装了宇树对应的功能包和FAST-LIO算法,mid_ws工作空间安装了MID-360雷达对应的功能包。
在使用过程重,出现一次黄色警告,No point,skip this scan,此处不影响定位效果,猜测可能是启动响应问题
No point,skip this scan
硬件雷达:
一、接线连接
livox MID-360航插一分三线,其中航空母头连接激光雷达,网线连接PC,电源需要DC 9~27 V,推荐使用 12 V,注意正负极
一、安装Livox-SDK2
1.1、安装CMake
sudo apt install cmake
1.2、 安装编译Livox-SDK2和livox_ros_driver2(也可以先安装FAST-LIO)
新建或者到ROS工作空间下的src
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安装在ROS工作空间下,理论上可以在任何位置下载并编译安装,同时最好将FAST-LIO也一起安装在同一个工作空间下,使用管理方便
二、编译FAST_LIO工程
此处我使用的自己修改的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代码
注意:目的就是把所有livox_ros_driver 改成livox_ros_driver2,否则消息格式对不上
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
修改前:
<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_LIO的头文件引用
分别打开FAST_LIO/src/preprocess.h、FAST_LIO/src/laserMapping.cpp
修改前:
#include <livox_ros_driver/CustomMsg.h>
修改后:
#include <livox_ros_driver2/CustomMsg.h>
3.4、修改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
注:第一次使用为了减少工作量,我将电脑IP改成了192.168.1.5,并且我雷达SN后两位是30,故雷达对应的完整IP为192.168.1.130
打开文件fast_lio/src/livox_ros_driver2/config/MID360_config.json。Livox mid360的IP是出厂后已经固定下来的,看它上面的二维码下面的 SN 码 ,后两个数字前面再加一个1,便是其对应的ip。(例如 SN 码后两位数字为30,那它对应的ip就是192.168.1.130)。
{
"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.130", # <-这里是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. 运行测试
注意:FAST-LIO源码已经做了修改,可以直接输出odom里程计信息,不建议使用官方的代码
打开两个终端,分别运行
注:launch文件,也需要将雷达对应的SN码进行修改,然后才能使用,此步骤千万不能遗忘,默认功能包参数是100000000000,修改成雷达对应的SN码
roslaunch livox_ros_driver2 msg_MID360.launch
话题查看:出现以下话题,并且按照一定频率发布则表明雷达启动成功
另外一个终端运行
roslaunch fast_lio mapping_mid360.launch