简介:接触过ROS1的同学对launch肯定不陌生,在ROS1中,我们常用launch实现node和master同时启动、多节点同时启动配置等功能,ROS2中的launch也是用于多节点启动、配置功能,但是在使用方法上有了很多不同,ROS1只支持xml格式的.launch文件配置,ROS2在兼容xml的基础上,还支持yaml和python格式,而python格式的launch是我的学习重点,因为相对于另外两种配置方式,使用python更加灵活:
- python拥有众多的函数库,可以在启动文件中使用;
- ROS2通用启动特性和特定启动特性是用Python编写的,因此可以访问XML和YAML可能没有公开的启动特性;
注:ROS1到ROS2的启动文件迁移,可以参考官方文档相关教程。
接下来,我们先学习launch常规简单的用法。
目录
1、创建launch文件启动多个节点
与ROS1类似,我们可以把多个节点启动配置直接写到同一个launch文件内直接启动,例如同时启动duckiebot和control两个节点:
$ cd ~/ros2_ws
$ mkdir launch
$ touch launch/both_launch.py
编辑both_launch.py文件内容如下:
from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
return LaunchDescription([
Node(
package='duckiebot',
namespace='duckietown',
executable='duckiebot_node',
name='duckiebot_node1'
),
Node(
package='control',
namespace='duckietown',
executable='control_node',
name='control_node1'
)
])
该文件配置启动了两个节点,同时设定了一些配置,其中package和executable我们对比ros2 run命令来理解:
$ ros2 run <package> <executable>
namespace和name我们用一个实际例子来理解,保存上述文件,配置环境变量,通过ros2 launch命令启动该文件:
$ source install/setup.bash
$ ros2 launch launch/both_launch.py
启动后,可以通过方向键控制小车行走,可以通过tab键切换地图,可以通过W/A/D键实现直行、左转与右转,这些都是我们之前完成的功能。
然后新开一个终端,执行几个命令:
$ ros2 node list
$ ros2 node info /duckietown/duckiebot_node1
由以上测试可知,namespace就是在节点的名称、主题、服务、动作原有名称之前增加了一个字段,这个功能可以用来区分多个相同功能的节点,例如在同一个域内有若干台相同的机器人,那么每个机器人都应该有自己的namespace,否则就乱套了;而name就是重新指定了节点运行时的名称,会覆盖代码中的设定。
2、为每个节点创建自己的launch文件
上文介绍了一个launch文件启动多个节点的方法,但是在大型项目中,一般不会使用上述方法,原因是可维护性太差,大型项目功能节点会比较多,每个功能节点都可能有自己的特殊配置,而且节点的实现可能来自于多个开发人员,由一个启动文件来启动配置所有节点就不太方便了,所以一般的做法是每个节点都维护自己启动文件,然后用一个启动文件统一调用各节点的启动文件。
2.1 单节点启动文件
先以duckiebot节点为例,在节点包内创建launch目录,在目录下新建duckiebot_node_launch.py文件,一般文件名以_launch结尾(非必要,只是为了方便在setup.py中配置):
编辑该文件内容如下:
from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
return LaunchDescription([
Node(
package='duckiebot',
executable='duckiebot_node',
name='duckiebot_node'
),
])
修改setup.py,添加以下代码:
import os
from glob import glob
(os.path.join('share', package_name, 'launch'), glob(os.path.join('launch', '*launch.py'))),
完整配置文件如下图:
返回工作空间编译并重新设置环境变量,然后通过ros2 launch命令启动该节点:
$ ros2 launch duckiebot duckiebot_node_launch.py
同样的方法为control节点创建启动文件并编译配置。
注:单节点启动文件中可以直接指定namespace,也可以在多节点启动文件中统一配置,二者冲突,所以单节点launch文件中不进行配置,留到多节点启动文件中统一配置。
2.2 多节点启动文件
在工作空间目录下的launch目录下新建all_launch.py,编辑内容如下:
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
def generate_launch_description():
duckiebot_node = IncludeLaunchDescription(
PythonLaunchDescriptionSource([os.path.join(
get_package_share_directory('duckiebot'), 'launch'),
'/duckiebot_node_launch.py'])
)
control_node = IncludeLaunchDescription(
PythonLaunchDescriptionSource([os.path.join(
get_package_share_directory('control'), 'launch'),
'/control_node_launch.py'])
)
return LaunchDescription([
duckiebot_node,
control_node
])
通过all_launch.py启动两个节点,这种情况下,节点本身的配置可以写在自己的启动文件内,群体启动文件内不需要关心节点自身的启动配置参数。
$ ros2 launch launch/all_launch.py
如果要统一命名空间,在all_launch.py中添加以下代码:
from launch.actions import GroupAction
from launch_ros.actions import PushRosNamespace
def generate_launch_description():
......
node_with_namespace = GroupAction(
actions=[
PushRosNamespace('duckietown'),
duckiebot_node,
control_node,
]
)
#返回值由node_with_namespace代替之前的节点
return LaunchDescription([
node_with_namespace
])
3、启动文件的其他配置功能
上文我们只介绍了启动文件中package、namespace、executable和name的配置,而在实际应用中还会有其他需求,常用的比如配置参数的加载、主题的重映射等,另外还有一些复杂的用法,详细内容请参考官方文档。
3.1 节点参数配置
节点参数的使用是在line_detect节点中实现的,之前如果要修改默认配置,需要修改源码或者通过命令行加载已有参数配置,当节点通过launch文件启动时,修改默认配置就有了新的方法。
3.1.1 在启动文件中设置
假设现在需要在节点启动时,默认显示黄色道路识别结果,line_detect节点的启动文件应该这么写:
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration, TextSubstitution
from launch_ros.actions import Node
def generate_launch_description():
color_select_launch_arg = DeclareLaunchArgument(
'color_select', default_value=TextSubstitution(text='yellow')
)
return LaunchDescription([
color_select_launch_arg,
Node(
package='line_detect',
executable='line_detect_node',
name='line_detect_node',
parameters=[{
'color_select': LaunchConfiguration('color_select'),
}]
),
])
同时修改setup.py文件,然后在all_launch.py中添加修改以下内容:
line_detect_node = IncludeLaunchDescription(
PythonLaunchDescriptionSource([os.path.join(
get_package_share_directory('line_detect'), 'launch'),
'/line_detect_node_launch.py'])
)
node_with_namespace = GroupAction(
actions=[
PushRosNamespace('duckietown'),
duckiebot_node,
control_node,
line_detect_node,
]
)
编译配置后启动all_launch.py,可以看到新节点默认显示黄色道路识别结果,同样方法也可以直接设定各种颜色的分量数值。
3.1.2 在启动文件中加载yaml配置文件
在参数功能讲解中,我们将调试过的参数进行导出保存为yaml格式文件,导出的参数(也可以是手动配置参数)也可以通过启动文件加载,参数配置文件我们一般放在config目录下,在节点包内新建config目录,将导出参数文件放到config目录下,参数文件line_detect_node.yaml内容如下:
/duckietown/line_detect_node:
ros__parameters:
color_select: red
red_h_high: 10
red_h_low: 156
red_s_high: 255
red_s_low: 43
red_v_high: 255
red_v_low: 46
use_sim_time: false
white_h_high: 180
white_h_low: 0
white_s_high: 50
white_s_low: 0
white_v_high: 255
white_v_low: 100
yellow_h_high: 34
yellow_h_low: 26
yellow_s_high: 255
yellow_s_low: 43
yellow_v_high: 255
yellow_v_low: 46
修改line_detect_node_launch.py:
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
config = os.path.join(
get_package_share_directory('line_detect'),
'config',
'line_detect_node.yaml'
)
return LaunchDescription([
Node(
package='line_detect',
executable='line_detect_node',
name='line_detect_node',
parameters=[config]
),
])
修改setup.py,在data_files中添加以下代码:
(os.path.join('share', package_name, 'config'), glob(os.path.join('config', '*.yaml'))),
重新编译配置启动all_launch.py,可以看到直接显示红色道路识别结果。
3.2 主题的重映射
在功能更新、节点话题命名重复、临时调试等情况下,节点内的主题可能需要临时或者永久修改名称,直接修改源码并不是很友好的办法,这种情况就可以用启动文件内的主题重映射来实现,我们以修改control节点中的action主题为例来说明使用方法,直接看启动文件配置:
from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
return LaunchDescription([
Node(
package='control',
executable='control_node',
name='control_node',
remappings=[
('/duckietown/control_node/action', '/duckietown/control_node1/control_action'),
]
),
])
重新编译配置启动all_launch.py,查看topic list:
3.3 环境变量引用
启动文件中调用环境变量的方式可以用来定义或推送名称空间,以区分不同计算机或机器人上的节点。
还是以control节点为例:
from launch import LaunchDescription
from launch_ros.actions import Node
from launch.actions import DeclareLaunchArgument
from launch.substitutions import EnvironmentVariable, LaunchConfiguration
def generate_launch_description():
return LaunchDescription([
DeclareLaunchArgument(
'node_prefix',
default_value=[EnvironmentVariable('USER'), '_'],
description='prefix for node name'
),
Node(
package='control',
executable='control_node',
name=[LaunchConfiguration('node_prefix'), 'control_node']
),
])
编译运行查看节点列表:
另外,也可以用在多节点启动文件中,统一命名namespace,用法如下:
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.actions import GroupAction
from launch_ros.actions import PushRosNamespace
from launch.actions import DeclareLaunchArgument
from launch.substitutions import EnvironmentVariable, LaunchConfiguration
def generate_launch_description():
duckiebot_node = IncludeLaunchDescription(
PythonLaunchDescriptionSource([os.path.join(
get_package_share_directory('duckiebot'), 'launch'),
'/duckiebot_node_launch.py'])
)
control_node = IncludeLaunchDescription(
PythonLaunchDescriptionSource([os.path.join(
get_package_share_directory('control'), 'launch'),
'/control_node_launch.py'])
)
line_detect_node = IncludeLaunchDescription(
PythonLaunchDescriptionSource([os.path.join(
get_package_share_directory('line_detect'), 'launch'),
'/line_detect_node_launch.py'])
)
node_with_namespace = GroupAction(
actions=[
DeclareLaunchArgument(
'namespace',
default_value=[EnvironmentVariable('USER'),'_robot'],
description='prefix for node name'
),
PushRosNamespace(LaunchConfiguration('namespace')),
duckiebot_node,
control_node,
line_detect_node,
]
)
return LaunchDescription([
node_with_namespace
])
编译运行查看节点列表: