Key: 用launch文件的group标签
理论上一个驱动可以解析若干台雷达
一、前置内容
我们都知道如果启动两个相同的节点,后一个节点会把前一个节点干掉!但如何两个都启动呢?
那就需要使用group这个标签了!
<launch>
<group ns="first">
<!-- 启动显示界面节点 -->
<node pkg="turtlesim" type="turtlesim_node" name="my_turtle" output="screen" />
<!-- 启动键盘控制节点 -->
<node pkg="turtlesim" type="turtle_teleop_key" name="my_key" output="screen"/>
</group>
<group ns="second">
<!-- 启动显示界面节点 -->
<node pkg="turtlesim" type="turtlesim_node" name="my_turtle" output="screen" />
<!-- 启动键盘控制节点 -->
<node pkg="turtlesim" type="turtle_teleop_key" name="my_key" output="screen"/>
</group>
</launch>
我们可以发现启动了两个小乌龟界面,话题也更新了两个不一样的命名空间的话题!这样就可以两个相同的节点同时启动了!
因此,我们用launch文件的group标签来实现一个launch文件同时驱动多台雷达!
二、修改launch文件
原launch文件:
<launch>
<arg name="pcap_file" default=""/>
<arg name="server_ip" default="192.168.1.201"/>
<arg name="lidar_recv_port" default="2368"/>
<arg name="gps_port" default="10110"/>
<arg name="start_angle" default="0"/>
<!--“lidar_type” represents the model of the lidar-->
<arg name="lidar_type" default=""/>
<!--"frame_id" represents the id of the point cloud data published to ROS-->
<arg name="frame_id" default=""/>
<arg name="pcldata_type" default="0"/>
<arg name="publish_type" default="points"/>
<arg name="timestamp_type" default=""/>
<arg name="data_type" default=""/>
<arg name="namespace" default="hesai"/>
<arg name="lidar_correction_file" default="$(find hesai_lidar)/config/Pandar64.csv"/>
<arg name="multicast_ip" default=""/>
<arg name="coordinate_correction_flag" default="false"/>
<arg name="fixed_frame" default=""/>
<arg name="target_frame" default=""/><node pkg="hesai_lidar" name="hesai_lidar" ns="$(arg namespace)" type="hesai_lidar_node" output="screen" >
<param name="pcap_file" type="string" value="$(arg pcap_file)"/>
<param name="server_ip" type="string" value="$(arg server_ip)"/>
<param name="lidar_recv_port" type="int" value="$(arg lidar_recv_port)"/>
<param name="gps_port" type="int" value="$(arg gps_port)"/>
<param name="start_angle" type="double" value="$(arg start_angle)"/>
<param name="lidar_type" type="string" value="$(arg lidar_type)"/>
<param name="frame_id" type="string" value="$(arg frame_id)"/>
<param name="pcldata_type" type="int" value="$(arg pcldata_type)"/>
<param name="publish_type" type="string" value="$(arg publish_type)"/>
<param name="timestamp_type" type="string" value="$(arg timestamp_type)"/>
<param name="data_type" type="string" value="$(arg data_type)"/>
<param name="lidar_correction_file" type="string" value="$(arg lidar_correction_file)"/>
<param name="multicast_ip" type="string" value="$(arg multicast_ip)"/>
<param name="coordinate_correction_flag" type="bool" value="$(arg coordinate_correction_flag)"/>
<param name="fixed_frame" type="string" value="$(arg fixed_frame)"/>
<param name="target_frame" type="string" value="$(arg target_frame)"/>
</node>
</launch>
以同时显示一台XT雷达数据及一台QT雷达数据为例:
(显示效果预览)
修改后的launch:
<launch>
<!-- FOR first Pandar -->
<group ns="PandarXT">
<arg name="pcap_file" default="/home/dexshui/Dual_LiDAR/XT16 open road.pcap"/>
<arg name="server_ip" default="192.168.1.201"/>
<arg name="lidar_recv_port" default="2368"/>
<arg name="gps_port" default="10110"/>
<arg name="start_angle" default="0"/>
<!--“lidar_type” represents the model of the lidar-->
<arg name="lidar_type" default="PandarXT-16"/>
<!--"frame_id" represents the id of the point cloud data published to ROS-->
<arg name="frame_id" default="Pandar0"/>
<arg name="pcldata_type" default="0"/>
<arg name="publish_type" default="points"/>
<arg name="timestamp_type" default="realtime"/>
<arg name="data_type" default=""/>
<arg name="namespace" default="hesailidar1"/>
<arg name="lidar_correction_file" default="$(find hesai_lidar)/config/PandarXT-16.csv"/>
<arg name="multicast_ip" default=""/>
<arg name="coordinate_correction_flag" default="false"/>
<arg name="fixed_frame" default=""/>
<arg name="target_frame" default=""/>
<node pkg="hesai_lidar" name="hesai_lidar" ns="$(arg namespace)" type="hesai_lidar_node" output="screen" >
<param name="pcap_file" type="string" value="$(arg pcap_file)"/>
<param name="server_ip" type="string" value="$(arg server_ip)"/>
<param name="lidar_recv_port" type="int" value="$(arg lidar_recv_port)"/>
<param name="gps_port" type="int" value="$(arg gps_port)"/>
<param name="start_angle" type="double" value="$(arg start_angle)"/>
<param name="lidar_type" type="string" value="$(arg lidar_type)"/>
<param name="frame_id" type="string" value="Pandar0"/>
<param name="pcldata_type" type="int" value="$(arg pcldata_type)"/>
<param name="publish_type" type="string" value="$(arg publish_type)"/>
<param name="timestamp_type" type="string" value="$(arg timestamp_type)"/>
<param name="data_type" type="string" value="$(arg data_type)"/>
<param name="lidar_correction_file" type="string" value="$(arg lidar_correction_file)"/>
<param name="multicast_ip" type="string" value="$(arg multicast_ip)"/>
<param name="coordinate_correction_flag" type="bool" value="$(arg coordinate_correction_flag)"/>
<param name="fixed_frame" type="string" value="$(arg fixed_frame)"/>
<param name="target_frame" type="string" value="$(arg target_frame)"/>
</node>
</group>
<!-- FOR second Pandar -->
<group ns="PandarQT">
<arg name="pcap_file" default="/home/dexshui/Dual_LiDAR/Roads_PandarQT.pcap"/>
<arg name="server_ip" default="192.168.1.201"/>
<arg name="lidar_recv_port" default="2368"/>
<arg name="gps_port" default="10110"/>
<arg name="start_angle" default="0"/>
<!--“lidar_type” represents the model of the lidar-->
<arg name="lidar_type" default="PandarQT"/>
<!--"frame_id" represents the id of the point cloud data published to ROS-->
<arg name="frame_id" default="Pandar1"/>
<arg name="pcldata_type" default="0"/>
<arg name="publish_type" default="points"/>
<arg name="timestamp_type" default="realtime"/>
<arg name="data_type" default=""/>
<arg name="namespace" default="hesailidar2"/>
<arg name="lidar_correction_file" default="$(find hesai_lidar)/config/PandarQT.csv"/>
<arg name="multicast_ip" default=""/>
<arg name="coordinate_correction_flag" default="false"/>
<arg name="fixed_frame" default=""/>
<arg name="target_frame" default=""/>
<node pkg="hesai_lidar" name="hesai_lidar" ns="$(arg namespace)" type="hesai_lidar_node" output="screen" >
<param name="pcap_file" type="string" value="$(arg pcap_file)"/>
<param name="server_ip" type="string" value="$(arg server_ip)"/>
<param name="lidar_recv_port" type="int" value="$(arg lidar_recv_port)"/>
<param name="gps_port" type="int" value="$(arg gps_port)"/>
<param name="start_angle" type="double" value="$(arg start_angle)"/>
<param name="lidar_type" type="string" value="$(arg lidar_type)"/>
<param name="frame_id" type="string" value="Pandar1"/>
<param name="pcldata_type" type="int" value="$(arg pcldata_type)"/>
<param name="publish_type" type="string" value="$(arg publish_type)"/>
<param name="timestamp_type" type="string" value="$(arg timestamp_type)"/>
<param name="data_type" type="string" value="$(arg data_type)"/>
<param name="lidar_correction_file" type="string" value="$(arg lidar_correction_file)"/>
<param name="multicast_ip" type="string" value="$(arg multicast_ip)"/>
<param name="coordinate_correction_flag" type="bool" value="$(arg coordinate_correction_flag)"/>
<param name="fixed_frame" type="string" value="$(arg fixed_frame)"/>
<param name="target_frame" type="string" value="$(arg target_frame)"/>
</node>
</group>
<node pkg="tf" type="static_transform_publisher" name="tf_trans1" args="3 0 0 3 3 2 -1 Pandar0 Pandar1 100" />
</launch>
主要修改点:
-
将原launch文件中的配置参数复制一遍;
-
使用group标签, 例如:4行 <group ns="PandarXT">;48行 <group ns="PandarQT">
-
直连雷达的话,ip等不能重复,这里我是回放.pcap文件,记得指定校准文件哦
-
两个lidar_type可以声明下,不声明也行,第12行
-
if <需要标定雷达外参,则设置两个group为不同的frame_id, 例如设置PandarXT为Pandar0,设置PandarQT为Pandar1>; (用于后续标定时定义坐标关系, parent / child)
else if <不需要标定雷达外参,把frame_id设置为一样的就可以,这样只用在Rviz中Fixed Frame改成这个frame_id,就可以显示两个雷达的点云了>
-
值得注意的是: 要在Rviz中显示,需要两个雷达的时间保持一致,也就是同步上,不然ROS Time中以哪个为准呢? 如果两个雷达是同步上的,那没有问题;如果没有同步,那我们就需要用launch中定义的一个参数 <arg name="timestamp_type" default="realtime"/> 第36行
|timestamp_type|default "": use timestamp from Lidar "realtime" use timestamp from the system driver running on|
将timestamp_type改为realtime, 雷达时间戳会利用驱动的系统时间
-
第90行 代码 <node pkg="tf" type="static_transform_publisher" name="tf_trans1" args="3 0 0 3 3 2 -1 Pandar0 Pandar1 100" />为用于标定的代码,定义两个雷达的外参,这个部分在下一节介绍。 (若不需要标定,则可以不要这行)
把launch文件修改好后,放在launch文件夹下,然后launch一下:
## Run as independent node
1. Make sure current path in the `rosworkspace` directory
```
$ source devel/setup.bash
```
```
for PandarXT and PandarQT
$ roslaunch hesai_lidar hesai_lidar_dual.launch
在Rviz中Add多台雷达的topic:
如果设置了标定坐标变化static_transform_publisher
将Fixed Frame修改为Parent坐标的frame_id, 比如上面的是Pandar0:
(这是带坐标变化的情况,Pandar0为Parent坐标,Pandar1为Child坐标)
可以查看TF Tree看一下坐标变换关系:
如果刚刚没设置坐标变化,只需要简单显示一下:
将Fixed_frame设置为launch文件中多台雷达共用的frame_id,比如Pandar或者baselink, 就可以直接显示两个雷达的数据
三、标定
About TF:
TF is a ROS package that lets the user keep track of multiple coordinate frames over time. tf maintains the relationship between coordinate frames in a tree structure buffered in time, and lets the user transform points, vectors, etc between any two coordinate frames at any desired point in time.ect
Start tf transformation to transform the point clouds form multiple LiDARs into the same coordination system:
As an example: shown on the pictures, start the transformation using matric 0 0 0 0 0 0 to transform Pandar0(the frame_id of PandarXT) to Pandar1(the frame_id of PandarQT )
0 0 0 0 0 0
参数解释:
-
前边的x y z分别代表着相应轴的平移,单位是 米 。
-
yaw pitch roll 分别代表着绕三个轴的转动,单位是 弧度 。
-
再之后的frame_id为坐标系变换中的父坐标系, child_frame_id为坐标系变换中的子坐标系。
-
最后一个参数为发布频率,单位为 毫秒。通常取100;一毫秒为一秒的千分之一,100毫秒即为0.1秒,也就是10Hz。