1 引入
自动导航需要多个雷达来避免盲区和提高定位精度。本文项目使用前后两个velodyne VLD16的雷达。
2 启动两个雷达的驱动
2.1 方案选择
查了网上,看到似乎有两种方案:
- 一种是采用的.launch文件中不同的namespace,去配置不同的参数,参阅:https://zhuanlan.zhihu.com/p/562961358
但这种方式应该是过时了,包括.launch文件启动,以及velodyne的官方新驱动里面几乎看不到nodelet了 - 所以拟采用第二种方式,修改launch.py文件,参阅: https://blog.csdn.net/qq_45701501/article/details/119486110
2.2 实施步骤
- 配置文件
前雷达配置文件VLP1params.yaml:
velodyne_driver_node:
ros__parameters:
device_ip: 192.168.1.201
gps_time: false
time_offset: 0.0
enabled: true
read_once: false
read_fast: false
repeat_delay: 0.0
frame_id: F_laser_link
model: VLP16
rpm: 600.0
port: 2368
timestamp_first_packet: false
后雷达配置文件VLP2params.yaml:
velodyne_driver_node:
ros__parameters:
device_ip: 192.168.1.202
gps_time: false
time_offset: 0.0
enabled: true
read_once: false
read_fast: false
repeat_delay: 0.0
frame_id: B_laser_link
model: VLP16
rpm: 600.0
port: 2368
timestamp_first_packet: false
使用不同IP(两个雷达内部IP要设置好与配置文件一样)192.168.1.201和192.168.1.202
使用不同的frame_id:F_laser_link和B_laser_link
- TF设置,根据雷达安装位置进行设置:在启动文件中加两个tf2_ros的静态TF发布:
Node(
package = "tf2_ros",
namespace="base_to_Flaser",
executable = "static_transform_publisher",
arguments = ["0.87","0","0.58","0","0","0", "base_link","F_laser_link"]
),
Node(
package = "tf2_ros",
namespace="base_to_Flaser",
executable = "static_transform_publisher",
arguments = ["-0.20","0","0.58","0","0","0", "base_link","B_laser_link"]
),
- 修改雷达启动程序
启动程序的编写,参见如何编写一个启动文件(launch file)
import os
import yaml
import ament_index_python.packages
from launch import LaunchDescription
from launch_ros.actions import Node
#velodyne_1
def generate_launch_description():
ld = LaunchDescription()
driver_share_dir = ament_index_python.packages.get_package_share_directory('velodyne_driver')
driver_params_file_F = os.path.join(driver_share_dir, 'config', 'VLP1params.yaml')
velodyne_driver_node_F = Node(
package="velodyne_driver",
executable="velodyne_driver_node",
name="velodyne_driver_node_F",
parameters=[driver_params_file_F],
remappings=[
("velodyne_packets", "velodyne_packets_F")
]
)
convert_share_dir = ament_index_python.packages.get_package_share_directory('velodyne_pointcloud')
convert_params_file = os