Reference:
Reference:
下载编译安装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
编译生成的库文件为静态库,库文件安装路径为"/usr/local/lib",头文件安装路径为"/usr/local/include"。
如果需要移除Livox-SDK2:
$ sudo rm -rf /usr/local/lib/liblivox_lidar_sdk_*
$ sudo rm -rf /usr/local/include/livox_lidar_*
mkdir -p catkin_livox_ros_driver2/src/livox_ros_driver2
git clone https://github.com/Livox-SDK/livox_ros_driver2.git
以ROS Noetic环境下编译为例:
source /opt/ros/noetic/setup.sh
cd catkin_livox_ros_driver2/src/livox_ros_driver2
./build.sh ROS1
source /opt/ros/foxy/setup.sh
cd catkin_livox_ros_driver2/src/livox_ros_driver2
./build.sh ROS2
source /opt/ros/humble/setup.sh
source /opt/ros/humble/setup.sh
./build.sh humble
注意,如果运行如下命令后Rviz中没有显示点云数据,则有可能是雷达配置问题。
这里需要的配置包括:
PointXYZRTLT
,对应参数为xfer_format=0
,其位于ROS1的launch文件rviz_MID360.launch
中或ROS2的launch文件rviz_MID360_launch.py
中47MDL960020112
为例,其最后两位即为当前雷达的默认ip地址,即雷达的出厂默认ip地址为192.168.1.112
。对应需要设置参数为文件MID360_config.json
中的ip
。192.168.1.50
,则对应需要在文件MID360_config.json
中指定host_net_info
的ip地址。完整的文件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",
"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.112",
"pcl_data_type" : 1,
"pattern_mode" : 0,
"extrinsic_parameter" : {
"roll": 0.0,
"pitch": 0.0,
"yaw": 0.0,
"x": 0,
"y": 0,
"z": 0
}
}
]
}
cd catkin_livox_ros_driver2
source devel/setup.sh
roslaunch livox_ros_driver2 rviz_MID360.launch
cd catkin_livox_ros_driver2
source install/setup.sh
ros2 launch livox_ros_driver2 rviz_MID360_launch.py
ROS的启动文件位于如下目录:
catkin_livox_ros_driver2/src/livox_ros_driver2/launch_ROS1
ROS2的启动文件位于如下目录:
catkin_livox_ros_driver2/src/livox_ros_driver2/launch_ROS2
不同的启动文件对应不同的雷达和配置,并在不同的场景中使用。
launch file name | Description |
---|---|
rviz_HAP.launch | Connect to HAP LiDAR device Publish pointcloud2 format data Autoload rviz |
msg_HAP.launch | Connect to HAP LiDAR device Publish livox customized pointcloud data |
rviz_MID360.launch | Connect to MID360 LiDAR device Publish pointcloud2 format data Autoload rviz |
msg_MID360.launch | Connect to MID360 LiDAR device Publish livox customized pointcloud data |
rviz_mixed.launch | Connect to HAP and MID360 LiDAR device Publish pointcloud2 format data Autoload rviz |
msg_mixed.launch | Connect to HAP and MID360 LiDAR device Publish livox customized pointcloud data |
Livox_ros_driver2
的所有内部参数配置均位于launch文件中。
如下为三个常用参数的功能描述,包括
Parameter | Detailed description | Default |
---|---|---|
publish_freq | Set the frequency of point cloud publish Floating-point data type, recommended values 5.0, 10.0, 20.0, 50.0, etc. The maximum publish frequency is 100.0 Hz. | 10.0 |
multi_topic | If the LiDAR device has an independent topic to publish pointcloud data 0 – All LiDAR devices use the same topic to publish pointcloud data 1 – Each LiDAR device has its own topic to publish point cloud data | 0 |
xfer_format | Set pointcloud format 0 – Livox pointcloud2( PointXYZRTLT ) pointcloud format 1 – Livox customized pointcloud format 2 – Standard pointcloud2 ( pcl :: PointXYZI ) pointcloud format in the PCL library (just for ROS) | 0 |
打开对应的launch文件,配置参数publish_freq
打开对应的launch文件,配置参数xfer_format
。这里支持以下三种格式:
格式代号 | 消息类型 | 说明 |
---|---|---|
0 | PointXYZRTLT | Livox pointcloud2pointcloud format |
1 | livox_ros_driver2::CustomMsg | Livox customized pointcloud format |
2 | pcl::PointXYZI | Standard pointcloud2 pointcloud format in the PCL library (just for ROS) |
其中,Livox自定义的用于支持PCL库的PointXYZRTLT
点格式的定义如下:
float32 x # X axis, unit:m
float32 y # Y axis, unit:m
float32 z # Z axis, unit:m
float32 intensity # the value is reflectivity, 0.0~255.0
uint8 tag # livox tag
uint8 line # laser number in lidar
float64 timestamp # Timestamp of point
在C++中可以定义如下:
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/impl/pcl_base.hpp>
/**
* @brief Livox Mid360 Point Type
*/
namespace mid360_ros {
struct Point
{
PCL_ADD_POINT4D
PCL_ADD_INTENSITY
std::uint8_t tag; // livox tag --- 对于Mid360, 其取值为[0,1,2,3,4]
std::uint8_t line; // laser number in lidar --- 对于Mid360, 其取值为[0,1,2,3],即总共4条激光线,每次采样四个点的线号依次为0,1,2,3
double timestamp; // 单位为ns的绝对时间戳
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
} EIGEN_ALIGN16;
}
POINT_CLOUD_REGISTER_POINT_STRUCT(mid360_ros::Point,
(float, x, x)(float, y, y)(float, z, z)
(float, intensity, intensity)
(std::uint8_t, tag, tag)
(std::uint8_t, line, line)
(double, timestamp, timestamp)
)
另外一种Livox自定义的点云数据格式为:
std_msgs/Header header # ROS standard message header
uint64 timebase # The time of first point
uint32 point_num # Total number of pointclouds
uint8 lidar_id # Lidar device id number
uint8[3] rsvd # Reserved use
CustomPoint[] points # Pointcloud data
上述点云数据格式中的一个点的格式(CustomPoint
)的定义如下:
uint32 offset_time # offset time relative to the base time
float32 x # X axis, unit:m
float32 y # Y axis, unit:m
float32 z # Z axis, unit:m
uint8 reflectivity # reflectivity, 0~255
uint8 tag # livox tag
uint8 line # laser number in lidar
打开对应的launch文件,配置参数multi_topic
Lidar的IP和端口等设置位于config
文件夹下的json-style的配置文件中。
参数说明如下:
Parameter | Type | Description | Default |
---|---|---|---|
ip | String | Ip of the LiDAR you want to config | 192.168.1.100 |
pcl_data_type | Int | Choose the resolution of the point cloud data to send 1 – Cartesian coordinate data ( 32 bits ) 2 – Cartesian coordinate data ( 16 bits ) 3 --Spherical coordinate data | 1 |
pattern_mode | Int | Space scan pattern 0 – non-repeating scanning pattern mode 1 – repeating scanning pattern mode 2 – repeating scanning pattern mode (low scanning rate) | 0 |
blind_spot_set (Only for HAP LiDAR) | Int | Set blind spot Range from 50 cm to 200 cm | 50 |
extrinsic_parameter | Set extrinsic parameter The data types of “roll” “picth” “yaw” are float The data types of “x” “y” “z” are int |
示例如下:
{
"lidar_summary_info" : {
"lidar_type": 8 # protocol type index, please don't revise this value
},
"HAP": {
"device_type" : "HAP",
"lidar_ipaddr": "",
"lidar_net_info" : {
"cmd_data_port": 56000, # command port
"push_msg_port": 0,
"point_data_port": 57000,
"imu_data_port": 58000,
"log_data_port": 59000
},
"host_net_info" : {
"cmd_data_ip" : "192.168.1.5", # host ip (it can be revised)
"cmd_data_port": 56000,
"push_msg_ip": "",
"push_msg_port": 0,
"point_data_ip": "192.168.1.5", # host ip
"point_data_port": 57000,
"imu_data_ip" : "192.168.1.5", # host ip
"imu_data_port": 58000,
"log_data_ip" : "",
"log_data_port": 59000
}
},
"lidar_configs" : [
{
"ip" : "192.168.1.100", # ip of the LiDAR you want to config
"pcl_data_type" : 1,
"pattern_mode" : 0,
"blind_spot_set" : 50,
"extrinsic_parameter" : {
"roll": 0.0,
"pitch": 0.0,
"yaw": 0.0,
"x": 0,
"y": 0,
"z": 0
}
}
]
}
当连接多个激光雷达时,将不同激光雷达对应的对象添加到 “lidar_configs” 数组中即可。
示例如下:
{
"lidar_summary_info" : {
"lidar_type": 8 # protocol type index, please don't revise this value
},
"HAP": {
"lidar_net_info" : { # HAP ports, please don't revise these values
"cmd_data_port": 56000, # HAP command port
"push_msg_port": 0,
"point_data_port": 57000,
"imu_data_port": 58000,
"log_data_port": 59000
},
"host_net_info" : {
"cmd_data_ip" : "192.168.1.5", # host ip
"cmd_data_port": 56000,
"push_msg_ip": "",
"push_msg_port": 0,
"point_data_ip": "192.168.1.5", # host ip
"point_data_port": 57000,
"imu_data_ip" : "192.168.1.5", # host ip
"imu_data_port": 58000,
"log_data_ip" : "",
"log_data_port": 59000
}
},
"MID360": {
"lidar_net_info" : { # Mid360 ports, please don't revise these values
"cmd_data_port": 56100, # Mid360 command port
"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", # host ip
"cmd_data_port": 56101,
"push_msg_ip": "192.168.1.5", # host ip
"push_msg_port": 56201,
"point_data_ip": "192.168.1.5", # host ip
"point_data_port": 56301,
"imu_data_ip" : "192.168.1.5", # host ip
"imu_data_port": 56401,
"log_data_ip" : "",
"log_data_port": 56501
}
},
"lidar_configs" : [
{
"ip" : "192.168.1.100", # ip of the HAP you want to config
"pcl_data_type" : 1,
"pattern_mode" : 0,
"blind_spot_set" : 50,
"extrinsic_parameter" : {
"roll": 0.0,
"pitch": 0.0,
"yaw": 0.0,
"x": 0,
"y": 0,
"z": 0
}
},
{
"ip" : "192.168.1.12", # ip of the Mid360 you want to config
"pcl_data_type" : 1,
"pattern_mode" : 0,
"extrinsic_parameter" : {
"roll": 0.0,
"pitch": 0.0,
"yaw": 0.0,
"x": 0,
"y": 0,
"z": 0
}
}
]
}
很遗憾,从官方Github上的issues看,MID360当前尚不支持重复扫描模式,即只支持默认的非重复扫描模式!尝试修改pattern_mode
参数并不会起作用。
具体可见: