一、单激光雷达的启动
#安装velodyne的ros依赖
sudo apt-get install ros-melodic-velodyne
#进入工作空间克隆velodyne包
git clone https://github.com/ros-drivers/velodyne.git
#完成编译
cd ..
catkin_make
source devel/setup.bash
velodyne16通电,用网线将激光雷达与主机相连(断掉无线网),点击右上角网络标志→ 编辑网络连接→ 点击左下角"+"号添加以太网→ 点击IPv4 Setting→ 将Adress、Netmask与Gateway分别设置为"192.168.1.100"(100是我自己设的,可以设置为1~254内除了201外的所有值,201是激光雷达的IP)、"255.255.255.0"与"192.168.1.1"。保存即可。浏览器进入192.168.1.201可以打开激光雷达配置界面,将转速"rpm"改为600,将Host(Destination)里的IP Adress改为网络设置中的Adress,用于向主机发送数据。在配置界面中看到"Data Port"的端口数字,默认是2368,如果不是,则记录该端口数字。并:
#打开velodyne启动launch文件
roscd velodyne_pointcloud/launch
gedit VLP16_points.launch
在其中修改"port"参数值为刚记录的"Data port"数字,至此单激光雷达配置完成,启动激光雷达:
roslaunch velodyne_pointclouds VLP16_points.launch
rosrun rviz rviz -f velodyne
可以在rviz中看到当前激光雷达的扫描信息。
二、双激光雷达的启动
双激光雷达启动与单激光雷达基本相同,但需要对激光雷达IP先做修改:先连接一只激光雷达,进入192.168.1.201激光雷达配置界面,将"Network(Sensor)"中的IP Adress修改为"192.168.1.200"。配置完成,接下来就是接线方式了:需要交换机或路由器,用三根网线分别将主机、两激光雷达连接至交换机或路由器。断开无线网,将主机网络连接至有线以太网。启动包下载:双激光雷达启动,提取码:0fit
multi_VLP16_points.launch需要修改:
<!-- Run two Velodyne VLP-16 LiDARs -->
<launch>
<!-- Name lidar devices -->
<arg name="lidar1_name" default="lidar_parent" />
<arg name="lidar2_name" default="lidar_child" />
<!-- FOR first VLP16 -->
<group ns="$(arg lidar1_name)">
<!-- hardware parameters -->
<arg name="calibration" default="$(find velodyne_pointcloud)/params/VLP16db.yaml"/>
<arg name="device_ip" default="192.168.1.201" />
<arg name="port" default="xxxx" />#这是ip为"192.168.1.201" 的激光雷达的"Data Port"值
<arg name="frame_id" default="velodyne" />#可修改
<arg name="manager" default="$(arg frame_id)_nodelet_manager" />
<arg name="max_range" default="130.0" />
<arg name="min_range" default="0.4" />
<arg name="pcap" default="" />
<arg name="read_fast" default="false" />
<arg name="read_once" default="false" />
<arg name="repeat_delay" default="0.0" />
<arg name="rpm" default="600.0" />
<arg name="cut_angle" default="-0.01" />
<arg name="laserscan_ring" default="-1" />
<arg name="laserscan_resolution" default="0.007" />
<!-- start nodelet manager and driver nodelets -->
<include file="$(find velodyne_driver)/launch/nodelet_manager.launch">
<arg name="device_ip" value="192.168.1.201"/>
<arg name="frame_id" value="velodyne"/>#同上frame_id
<arg name="manager" value="$(arg frame_id)_nodelet_manager" />
<arg name="model" value="VLP16"/>
<arg name="pcap" value="$(arg pcap)"/>
<arg name="port" value="$(arg port)"/>
<arg name="read_fast" value="$(arg read_fast)"/>
<arg name="read_once" value="$(arg read_once)"/>
<arg name="repeat_delay" value="$(arg repeat_delay)"/>
<arg name="rpm" value="$(arg rpm)"/>
<arg name="cut_angle" value="$(arg cut_angle)"/>
</include>
<!-- start cloud nodelet -->
<include file="$(find velodyne_pointcloud)/launch/cloud_nodelet.launch">
<arg name="calibration" value="$(arg calibration)"/>
<arg name="manager" value="$(arg frame_id)_nodelet_manager" />
<arg name="max_range" value="$(arg max_range)"/>
<arg name="min_range" value="$(arg min_range)"/>
</include>
</group>
<!--For VELODYNE 02 -->
<group ns="$(arg lidar2_name)">
<!-- declare arguments with default values -->
<arg name="calibration" default="$(find velodyne_pointcloud)/params/VLP16db.yaml"/>
<arg name="device_ip" default="192.168.1.200" />#我们将该激光雷达的ip修改了
<arg name="port" default="xxxx" />#ip为"192.168.1.200"的激光雷达的"Data Port"
<arg name="frame_id" default="velodyne" />
<arg name="manager" default="$(arg frame_id)_nodelet_manager" />
<arg name="max_range" default="130.0" />
<arg name="min_range" default="0.4" />
<arg name="pcap" default="" />
<arg name="read_fast" default="false" />
<arg name="read_once" default="false" />
<arg name="repeat_delay" default="0.0" />
<arg name="rpm" default="600.0" />
<arg name="cut_angle" default="-0.01" />
<arg name="laserscan_ring" default="-1" />
<arg name="laserscan_resolution" default="0.007" />
<!-- start nodelet manager and driver nodelets -->
<include file="$(find velodyne_driver)/launch/nodelet_manager.launch">
<arg name="device_ip" value="192.168.1.111"/>
<arg name="frame_id" value="velodyne"/>
<arg name="manager" value="$(arg frame_id)_nodelet_manager" />
<arg name="model" value="VLP16"/>
<arg name="pcap" value="$(arg pcap)"/>
<arg name="port" value="$(arg port)"/>
<arg name="read_fast" value="$(arg read_fast)"/>
<arg name="read_once" value="$(arg read_once)"/>
<arg name="repeat_delay" value="$(arg repeat_delay)"/>
<arg name="rpm" value="$(arg rpm)"/>
<arg name="cut_angle" value="$(arg cut_angle)"/>
</include>
<!-- start cloud nodelet -->
<include file="$(find velodyne_pointcloud)/launch/cloud_nodelet.launch">
<arg name="calibration" value="$(arg calibration)"/>
<arg name="manager" value="$(arg frame_id)_nodelet_manager" />
<arg name="max_range" value="$(arg max_range)"/>
<arg name="min_range" value="$(arg min_range)"/>
</include>
</group>
</launch>
下面是包里针对velodyne修改后的:
<!-- -*- mode: XML -*- -->
<!-- run velodyne_pointcloud/CloudNodelet in a nodelet manager for a VLP-16 -->
<!-- Run two Velodyne VLP-16 LiDARs -->
<launch>
<!-- Name lidar devices -->
<arg name="lidar1_name" default="lidar_parent" />
<arg name="lidar2_name" default="lidar_child" />
<!-- FOR first VLP16 -->
<group ns="$(arg lidar1_name)">
<!-- hardware parameters -->
<arg name="calibration" default="$(find velodyne_pointcloud)/params/VLP16db.yaml"/>
<arg name="device_ip" default="192.168.1.201" />
<arg name="port" default="2369" />
<arg name="frame_id" default="velodyne1" />
<arg name="manager" default="$(arg frame_id)_nodelet_manager" />
<arg name="max_range" default="130.0" />
<arg name="min_range" default="0.4" />
<arg name="pcap" default="" />
<arg name="read_fast" default="false" />
<arg name="read_once" default="false" />
<arg name="repeat_delay" default="0.0" />
<arg name="rpm" default="600.0" />
<arg name="cut_angle" default="-0.01" />
<arg name="laserscan_ring" default="-1" />
<arg name="laserscan_resolution" default="0.007" />
<!-- start nodelet manager and driver nodelets -->
<include file="$(find velodyne_driver)/launch/nodelet_manager.launch">
<arg name="device_ip" value="192.168.1.201"/>
<arg name="frame_id" value="velodyne1"/>
<arg name="manager" value="$(arg frame_id)_nodelet_manager" />
<arg name="model" value="VLP16"/>
<arg name="pcap" value="$(arg pcap)"/>
<arg name="port" value="$(arg port)"/>
<arg name="read_fast" value="$(arg read_fast)"/>
<arg name="read_once" value="$(arg read_once)"/>
<arg name="repeat_delay" value="$(arg repeat_delay)"/>
<arg name="rpm" value="$(arg rpm)"/>
<arg name="cut_angle" value="$(arg cut_angle)"/>
</include>
<!-- start cloud nodelet -->
<include file="$(find velodyne_pointcloud)/launch/cloud_nodelet.launch">
<arg name="calibration" value="$(arg calibration)"/>
<arg name="manager" value="$(arg frame_id)_nodelet_manager" />
<arg name="max_range" value="$(arg max_range)"/>
<arg name="min_range" value="$(arg min_range)"/>
</include>
</group>
<!--For VELODYNE 02 -->
<group ns="$(arg lidar2_name)">
<!-- declare arguments with default values -->
<arg name="calibration" default="$(find velodyne_pointcloud)/params/VLP16db.yaml"/>
<arg name="device_ip" default="192.168.1.200" />
<arg name="port" default="2368" />
<arg name="frame_id" default="velodyne2" />
<arg name="manager" default="$(arg frame_id)_nodelet_manager" />
<arg name="max_range" default="130.0" />
<arg name="min_range" default="0.4" />
<arg name="pcap" default="" />
<arg name="read_fast" default="false" />
<arg name="read_once" default="false" />
<arg name="repeat_delay" default="0.0" />
<arg name="rpm" default="600.0" />
<arg name="cut_angle" default="-0.01" />
<arg name="laserscan_ring" default="-1" />
<arg name="laserscan_resolution" default="0.007" />
<!-- start nodelet manager and driver nodelets -->
<include file="$(find velodyne_driver)/launch/nodelet_manager1.launch">
<arg name="device_ip" value="192.168.1.200"/>
<arg name="frame_id" value="velodyne2"/>
<arg name="manager" value="$(arg frame_id)_nodelet_manager" />
<arg name="model" value="VLP16"/>
<arg name="pcap" value="$(arg pcap)"/>
<arg name="port" value="$(arg port)"/>
<arg name="read_fast" value="$(arg read_fast)"/>
<arg name="read_once" value="$(arg read_once)"/>
<arg name="repeat_delay" value="$(arg repeat_delay)"/>
<arg name="rpm" value="$(arg rpm)"/>
<arg name="cut_angle" value="$(arg cut_angle)"/>
</include>
<!-- start cloud nodelet -->
<include file="$(find velodyne_pointcloud)/launch/cloud_nodelet1.launch">
<arg name="calibration" value="$(arg calibration)"/>
<arg name="manager" value="$(arg frame_id)_nodelet_manager" />
<arg name="max_range" value="$(arg max_range)"/>
<arg name="min_range" value="$(arg min_range)"/>
</include>
</group>
</launch>
至此,双激光雷达可以正常启动,但用NDT方法进行标定时,rviz报错"Ignoring transform from authority 'unknown_publisher' with frame_id and child_frame_id 'velodyne', because they are the same",是因为两个激光雷达默认的Fixed_Frame都是"velodyne"造成重复,应该修改激光雷达驱动发布的点云数据的坐标系名称.具体解决方式见下:
=======================================================
双激光雷达标定需要修改几个文件(提供的包里已改)
1.激光雷达启动文件:将两个激光雷达的frame_id分别改为velodyne1与velodyne2;将第二个激光雷达的"nodelet_manager.launch"与"cloud_nodelet.launch"改为"nodelet_manager1.launch"与"cloud_nodelet1.launch"
2.在velodyne_pointcloud的launch文件夹中新建一个"cloud_nodelet1.launch"文件,将cloud_nodelet.launch文件内容复制进去,然后将cloud_nodelet.launch中的"frame_id"与"target_id"名称"velodyne1",将cloud_nodelet.launch中的"frame_id"与"target_id"名称改为"velodyne2"。
3.在velodyne_driver的launch文件夹中新建一个"nodelet_manager1.launch"文件,将nodelet_manager.launch文件内容复制进去,然后将nodelet_manager.launch中的"frame_id"改成"velodyne1",将"port"改为velodyne1对应的端口数字;将nodelet_manager1.launch中的"frame_id"改成"velodyne2",将"port"改为velodyne2对应的端口数字;
=========================================================
启动该launch文件就可以启动两个激光雷达啦!
roslaunch velodyne_points multi_VLP16_points.launch
三、双激光雷达标定
本方法采用的双激光雷达标定方法是NDT扫描匹配算法,算法详解见
首先在github上克隆标定包,并编译:
#创建工作空间
mkdir -p ~/calibration_ws/src
cd ~/calibration_ws/src
catkin_init_workspace
#克隆标定代码包并编译
git clone https://github.com/AbangLZU/multi_lidar_calibration
cd ..
catkin_make
编译成功后给双激光雷达外参一个初始值,该初始值可以通过大致的测量获得。
cd ~/calibration_ws/src/multi_lidar_calibration/cfg
gedit child_topic_list
该文件是运行文末rosbag对6个激光雷达进行标定时的初始值设定,我们现在对双激光雷达进行标定。第一行表示child frame的个数,即子激光雷达个数;第二行是子激光雷达的点云数据topic;第三行为子激光雷达到父激光雷达的坐标变换初始估计值,顺序为(x,y,z,yaw,pitch,roll) 。
根据前文对双激光雷达的启动设置,将文件改为:
1
/lidar_child/velodyne_points
#下面是我的双激光雷达位姿初始估计值,注意是子激光雷达到父激光雷达的变换
0.2 0.0 0.25 0.0 0.0 0.0
修改完成后,启动roscore
roscore
另起终端启动rviz
#进入标定包并启动rviz
roscd multi_lidar_calibration
rviz -d rviz/multi_lidar_calibration.rviz
另起新终端启动标定包
source ~/calibration_ws/devel/setup.bash
roslaunch multi_lidar_calibration multi_lidar_calibration.launch
至此,标定完成!此时可以看到程序会不断输出两个激光雷达标定的结果,rviz中会显示两只激光雷达标定完成的点云数据!
采用rosbag标定结果rviz显示为: