往往现实中的工程都是会包含很多节点很多参数很多主题的那种,如果单独通过各种ros2 run命令进行启动管理,恐怕难以招架,主要还是通过launch文件的方式进行管理,而launch文件也可以像节点那样按功能的不同模块化,最终利用一个(或多个,根据实际需要)所谓顶级launch文件去调用管理这些模块化的子launch文件(还有其他ROS中提供的如参数、YAML文件、重映射、命名空间、RViz参数等项),化零为整,化繁为简。
我们还是在launch_tutorial这个功能包内进行练习。
在编写launch文件的过程中,目标之一应该是使它们尽可能地可重复使用。这可以通过将相关节点和配置集群到单独的launch文件中来实现。之后,可以编写专用于特定配置的顶级launch文件。这将允许在完全不改变launch文件(或很少改动)的情况下在相同的机器人之间通用。
我们接下来要在launch_tutorial包的launch文件夹下编写launch_turtlesim_launch.py(即是顶级launch文件)用来调用管理其他单独的launch文件(随后我们会逐一编写里面调用的其他的launch文件),内容如下:
- 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():
- turtlesim_world_1 = IncludeLaunchDescription(
- PythonLaunchDescriptionSource([os.path.join(
- get_package_share_directory('launch_tutorial'), 'launch'),
- '/turtlesim_world_1_launch.py'])
- )
- turtlesim_world_2 = IncludeLaunchDescription(
- PythonLaunchDescriptionSource([os.path.join(
- get_package_share_directory('launch_tutorial'), 'launch'),
- '/turtlesim_world_2_launch.py'])
- )
- broadcaster_listener_nodes = IncludeLaunchDescription(
- PythonLaunchDescriptionSource([os.path.join(
- get_package_share_directory('launch_tutorial'), 'launch'),
- '/broadcaster_listener_launch.py']),
- launch_arguments={'target_frame': 'carrot1'}.items(),
- )
- mimic_node = IncludeLaunchDescription(
- PythonLaunchDescriptionSource([os.path.join(
- get_package_share_directory('launch_tutorial'), 'launch'),
- '/mimic_launch.py'])
- )
- fixed_frame_node = IncludeLaunchDescription(
- PythonLaunchDescriptionSource([os.path.join(
- get_package_share_directory('launch_tutorial'), 'launch'),
- '/fixed_broadcaster_launch.py'])
- )
- rviz_node = IncludeLaunchDescription(
- PythonLaunchDescriptionSource([os.path.join(
- get_package_share_directory('launch_tutorial'), 'launch'),
- '/turtlesim_rviz_launch.py'])
- )
-
- return LaunchDescription([
- turtlesim_world_1,
- turtlesim_world_2,
- broadcaster_listener_nodes,
- mimic_node,
- fixed_frame_node,
- rviz_node
- ])
此启动文件包括一组其他启动文件。这些包含的启动文件中的每一个都包含节点、参数,可能还有嵌套的包含,它们属于系统的一个部分。确切地说,我们推出了两个turtlesim模拟世界,TF广播器(TF broadcaster)、TF侦听器(TF listener)、仿态(mimic)、固定帧广播器(fixed frame broadcaster)和RViz节点(TF、RViz这些后续内容会有介绍)。
需要注意是,顶级启动文件应该能短则短,包括与应用程序的子组件相对应的其他文件的包含,以及通常更改的参数。
按照以下方式编写启动文件可以很容易地交换系统的一部分,我们稍后将看到这一点。但是,有时由于性能和使用原因,某些节点或启动文件必须单独启动。
在决定应用程序需要多少顶级启动文件时,要注意权衡。
关于参数相关的详细信息,可以参见官方说明或前期相关文章。
我们创建一个名为turtlesim_world_1_launch.py的启动文件来实现启动第一个海龟仿真模拟,内容如下:
- 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():
- background_r_launch_arg = DeclareLaunchArgument(
- 'background_r', default_value=TextSubstitution(text='0')
- )
- background_g_launch_arg = DeclareLaunchArgument(
- 'background_g', default_value=TextSubstitution(text='84')
- )
- background_b_launch_arg = DeclareLaunchArgument(
- 'background_b', default_value=TextSubstitution(text='122')
- )
-
- return LaunchDescription([
- background_r_launch_arg,
- background_g_launch_arg,
- background_b_launch_arg,
- Node(
- package='turtlesim',
- executable='turtlesim_node',
- name='sim',
- parameters=[{
- 'background_r': LaunchConfiguration('background_r'),
- 'background_g': LaunchConfiguration('background_g'),
- 'background_b': LaunchConfiguration('background_b'),
- }]
- ),
- ])
此启动文件启动turtlesim_node节点,该节点启动turtlesim模拟,并定义模拟配置参数并将其传递给节点。
我们再来创建第二个海龟仿真模拟节点,只不过不像第一只海龟提供在启动文件中设置了一些背景颜色参数值来改变背景,而第二只则是通过加载读取配置文件的方式来修改背景颜色参数值来改变背景,turtlesim_world_2_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('launch_tutorial'),
- 'config',
- 'turtlesim.yaml'
- )
-
- return LaunchDescription([
- Node(
- package='turtlesim',
- executable='turtlesim_node',
- namespace='turtlesim2',
- name='sim',
- parameters=[config]
- )
- ])
从上可以看到该启动文件加载了launch/config下的turtlesim.yaml文件,该文件保存了相关参数(YAML文件可以很方便地从当前的ros2 parm 中导出,详情见文档的5 ros2 param dump),我们再来创建这个turtlesim.yaml文件,内容如下:
- /turtlesim:
- ros__parameters:
- background_b: 255
- background_g: 86
- background_r: 150
- qos_overrides:
- /parameter_events:
- publisher:
- depth: 1000
- durability: volatile
- history: keep_last
- reliability: reliable
- use_sim_time: false
在某些情况下,我们希望在多个节点中设置相同的参数。这些节点可以具有不同的名称空间或名称,但仍然具有相同的参数。定义单独的YAML文件来显式定义名称空间和节点名称是低效的。一种解决方案是使用通配符,作为文本值中未知字符的替换,将参数应用于几个不同的节点。
我们像turtlesim_world_2_launch.py那样创建第三个海龟仿真节点启动文件turtlesim_world_3_launch.py,只不过呢,要包含更多的turtlesim_node节点,内容如下:
- 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('launch_tutorial'),
- 'config',
- 'turtlesim.yaml'
- )
-
- return LaunchDescription([
- Node(
- package='turtlesim',
- executable='turtlesim_node',
- namespace='turtlesim3',
- name='sim',
- parameters=[config]
- )
- ])
也是同样从同一个YAML文件中读取参数启动,如果有多个节点读取同一份YAML文件时,会根据里面的命名空间来找到匹配自己的参数,比如针对turtlesim3,正常情况我们需要在之前节点的参数后面加上:
- /turtlesim3/sim:
- background_b
- background_g
- background_r
功能是做到了,但是是不是显得有点啰嗦了而且还占用了空间,这时我们的通配符就可以出场一显身手啦,对于那些共用的参数内容,我们不需再另起一行复制一遍那些参数内容,只需将这些参数最上面的“/namespace/nodename:”替换为“/**:”即可,省了空间也精简了代码内容。修改后的turtlesim.yaml文件内容如下:
- /**:
- ros__parameters:
- background_b: 255
- background_g: 86
- background_r: 150
- qos_overrides:
- /parameter_events:
- publisher:
- depth: 1000
- durability: volatile
- history: keep_last
- reliability: reliable
- use_sim_time: false
不同命名空间下的节点可以拥有相同的节点名字、主题名称,不会发生冲突,比如我们上面创建的/turtlesim2/sim和/turtlesim3/sim,这就是两个不同命名空间下有相同名字的节点。在每个节点的启动文件里面都有显示填写了所属的命名空间,比如turtlesim_world_2_launch.py里面的namespace='turtlesim2',如果我们有很多很多(可能恒河沙数)的节点(名字可能会相同)launch文件,都要在每个launch文件里定义各自的命名空间,有没有感觉到有点无趣呢?有没有一种办法能够让我们省去这套乏味的操作呢?为了解决这个问题,PushROSNamespace操作可以用于为每个启动文件描述定义全局命名空间。每个嵌套节点都将自动继承该名称空间。
如何做呢,首先,我们需要从turtlesim_world_2_launch.py文件中删除namespace='turtlesim2'行(turtlesim_world_3_launch.py也同样操作)。之后,我们需要更新launch_turtlesim_launch.py以包括以下行:
- from launch.actions import GroupAction
- from launch_ros.actions import PushROSNamespace
-
- ...
- turtlesim_world_2 = IncludeLaunchDescription(
- PythonLaunchDescriptionSource([os.path.join(
- get_package_share_directory('launch_tutorial'), 'launch'),
- '/turtlesim_world_2_launch.py'])
- )
- turtlesim_world_2_with_namespace = GroupAction(
- actions=[
- PushROSNamespace('turtlesim2'),
- turtlesim_world_2,
- ]
- )
最后将return LaunchDescription里面的turtlesim_world_2替换为turtlesim_world_2_with_namespace,最终的launch_turtlesim_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():
- turtlesim_world_1 = IncludeLaunchDescription(
- PythonLaunchDescriptionSource([os.path.join(
- get_package_share_directory('launch_tutorial'), 'launch'),
- '/turtlesim_world_1_launch.py'])
- )
- broadcaster_listener_nodes = IncludeLaunchDescription(
- PythonLaunchDescriptionSource([os.path.join(
- get_package_share_directory('launch_tutorial'), 'launch'),
- '/broadcaster_listener_launch.py']),
- launch_arguments={'target_frame': 'carrot1'}.items(),
- )
- mimic_node = IncludeLaunchDescription(
- PythonLaunchDescriptionSource([os.path.join(
- get_package_share_directory('launch_tutorial'), 'launch'),
- '/mimic_launch.py'])
- )
- fixed_frame_node = IncludeLaunchDescription(
- PythonLaunchDescriptionSource([os.path.join(
- get_package_share_directory('launch_tutorial'), 'launch'),
- '/fixed_broadcaster_launch.py'])
- )
- rviz_node = IncludeLaunchDescription(
- PythonLaunchDescriptionSource([os.path.join(
- get_package_share_directory('launch_tutorial'), 'launch'),
- '/turtlesim_rviz_launch.py'])
- )
-
- turtlesim_world_2 = IncludeLaunchDescription(
- PythonLaunchDescriptionSource([os.path.join(
- get_package_share_directory('launch_tutorial'), 'launch'),
- '/turtlesim_world_2_launch.py'])
- )
- turtlesim_world_2_with_namespace = GroupAction(
- actions=[
- PushROSNamespace('turtlesim2'),
- turtlesim_world_2,
- ]
- )
-
- turtlesim_world_3 = IncludeLaunchDescription(
- PythonLaunchDescriptionSource([os.path.join(
- get_package_share_directory('launch_tutorial'), 'launch'),
- '/turtlesim_world_3_launch.py'])
- )
- turtlesim_world_3_with_namespace = GroupAction(
- actions=[
- PushROSNamespace('turtlesim3'),
- turtlesim_world_3,
- ]
- )
-
- return LaunchDescription([
- turtlesim_world_1,
- turtlesim_world_2_with_namespace,
- turtlesim_world_3_with_namespace,
- broadcaster_listener_nodes,
- mimic_node,
- fixed_frame_node,
- rviz_node
- ])
最终,turtlesim_world_2_launch.py启动描述中的每个节点都将具有一个turtlesim2名称空间(同样turtlesim_world_3_launch.py也一样)。
创建一个broadcaster_listener_launch.py文件,内容如下:
- from launch import LaunchDescription
- from launch.actions import DeclareLaunchArgument
- from launch.substitutions import LaunchConfiguration
-
- from launch_ros.actions import Node
-
-
- def generate_launch_description():
- return LaunchDescription([
- DeclareLaunchArgument(
- 'target_frame', default_value='turtle1',
- description='Target frame name.'
- ),
- Node(
- package='turtle_tf2_py',
- executable='turtle_tf2_broadcaster',
- name='broadcaster1',
- parameters=[
- {'turtlename': 'turtle1'}
- ]
- ),
- Node(
- package='turtle_tf2_py',
- executable='turtle_tf2_broadcaster',
- name='broadcaster2',
- parameters=[
- {'turtlename': 'turtle2'}
- ]
- ),
- Node(
- package='turtle_tf2_py',
- executable='turtle_tf2_listener',
- name='listener',
- parameters=[
- {'target_frame': LaunchConfiguration('target_frame')}
- ]
- ),
- ])
在这个文件中,我们声明了target_frame启动参数,默认值为turtle1。默认值意味着启动文件可以接收一个参数以转发到其节点,或者如果未提供该参数,则会将默认值传递给其节点。
之后,我们在启动时使用两个不同的名称和参数来使用turtle_tf2_broadcaster节点两次。这允许我们复制相同的节点而不会发生冲突。
我们还启动了一个turtle_tf2_listener节点,并设置其target_frame参数,该参数是我们在上面声明和获取的。
回想一下,我们在顶级启动文件中调用了broadcaster_listener_launch.py文件。除此之外,我们还为其传递了target_frame启动参数,如下所示:
- broadcaster_listener_nodes = IncludeLaunchDescription(
- PythonLaunchDescriptionSource([os.path.join(
- get_package_share_directory('launch_tutorial'), 'launch'),
- '/broadcaster_listener_launch.py']),
- launch_arguments={'target_frame': 'carrot1'}.items(),
- )
如果删除launch_arguments这行,此节点就会使用默认的名字turtle1作为其target_frame的参数值。
我们来创建mimic_launch.py文件来启动mimic节点,mimic的意思就是模仿,比如之前的文章里面提到的,第二只海龟的运动轨迹完全跟随着第一只海龟,这里面就利用了重映射的功能。内容如下:
- from launch import LaunchDescription
- from launch_ros.actions import Node
-
-
- def generate_launch_description():
- return LaunchDescription([
- Node(
- package='turtlesim',
- executable='mimic',
- name='mimic',
- remappings=[
- ('/input/pose', '/turtle2/pose'),
- ('/output/cmd_vel', '/turtlesim2/turtle1/cmd_vel'),
- ]
- )
- ])
这个启动文件将启动mimic节点,该节点将向一个turtlesim发送命令,使其跟随另一个turtlesim。该节点被设计为接收主题/input/pose上的目标姿态。在我们的案例中,我们想要将目标姿态从/turtle2/pose主题重新映射。最后,我们将/output/cmd_vel主题重新映射到/turtlesim2/turtle1/cmd_vel。这样,在我们turtlesim2模拟世界中的turtle1就会跟随我们初始turtlesim世界中的turtle2。
我们再来创建一个启动文件turtlesim_rviz_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():
- rviz_config = os.path.join(
- get_package_share_directory('turtle_tf2_py'),
- 'rviz',
- 'turtle_rviz.rviz'
- )
-
- return LaunchDescription([
- Node(
- package='rviz2',
- executable='rviz2',
- name='rviz2',
- arguments=['-d', rviz_config]
- )
- ])
这个启动文件将使用turtle_tf2_py包中定义的配置文件来启动RViz。这个RViz配置将设置世界坐标系,启用TF可视化,并以从上往下的视角启动RViz。
创建fixed_broadcaster_launch.py:
- from launch import LaunchDescription
- from launch.actions import DeclareLaunchArgument
- from launch.substitutions import EnvironmentVariable, LaunchConfiguration
- from launch_ros.actions import Node
-
-
- def generate_launch_description():
- return LaunchDescription([
- DeclareLaunchArgument(
- 'node_prefix',
- default_value=[EnvironmentVariable('USER'), '_'],
- description='prefix for node name'
- ),
- Node(
- package='turtle_tf2_py',
- executable='fixed_frame_tf2_broadcaster',
- name=[LaunchConfiguration('node_prefix'), 'fixed_broadcaster'],
- ),
- ])
这个启动文件展示了如何在启动文件中调用环境变量的方法。环境变量可以用来定义或推送命名空间,以便区分不同计算机或机器人上的节点。
setup.py文件是在功能包launch_tutorial根路径下,如果你发现没有,那么原因之一就是这个功能包之前是ament_cmake生成的,我们得重新生成python的包launch_tutorial,然后将之前包里面的launch文件夹整个拷贝到新包根路径下即可,再来修改自动生成的setup.py,需要添加的内容如下,以便安装launch/文件夹中的启动文件和config/文件夹中的配置文件。:
- import os
- from glob import glob
- from setuptools import setup
- ...
-
- data_files=[
- ...
- (os.path.join('share', package_name, 'launch'),
- glob(os.path.join('launch', '*launch.[pxy][yma]*'))),
- (os.path.join('share', package_name, 'config'),
- glob(os.path.join('config', '*.yaml'))),
- ],
完整的setup.py文件内容为:
- import os
- from glob import glob
- from setuptools import find_packages, setup
-
- package_name = 'launch_tutorial'
-
- setup(
- name=package_name,
- version='0.0.0',
- packages=find_packages(exclude=['test']),
- data_files=[
- ('share/ament_index/resource_index/packages',
- ['resource/' + package_name]),
- ('share/' + package_name, ['package.xml']),
- (os.path.join('share', package_name, 'launch'),
- glob(os.path.join('launch', '*launch.[pxy][yma]*'))),
- (os.path.join('share', package_name, 'config'),
- glob(os.path.join('config', '*.yaml'))),
- ],
- install_requires=['setuptools'],
- zip_safe=True,
- maintainer='mike',
- maintainer_email='mike@todo.todo',
- description='TODO: Package description',
- license='Apache-2.0',
- tests_require=['pytest'],
- entry_points={
- 'console_scripts': [
- ],
- },
- )
我们返回到工作空间根路径下执行colcon build,构建完成后,先source install/setup.bash,然后启动下顶级launch文件:
$ros2 launch launch_tutorial launch_turtlesim_launch.py
如果不凑巧,出现如下错误:

那就是python文件里面内容的缩进问题了,python对这个很严苛,我们可以根据提示找到对应的行,对照上下文进行缩进即可。
如果出现如下错误:

找不到turtle_tf2_py,可通过如下命令进行下载安装:
$sudo apt-get install ros-iron-rviz2 ros-iron-turtle-tf2-py ros-iron-tf2-ros ros-iron-tf2-tools ros-iron-turtlesim
(tf2相关知识点从下篇文章会介绍)
都准备好了之后再次启动顶级launch文件,看看效果:

左边的是第一个海龟仿真,有两只海龟,开始无轨迹的是turtle1,右边的是第二个海龟仿真,有一只海龟,它是模仿turtle1的,中间的是rviz窗口,刚启动的时候,小海龟已经跑了一点路径了,为了进一步确定效果,我们可以再开一个终端,运行之前的turtle_teletop_key来控制小海龟turtle1的移动:
$ros2 run turtlesim turtle_teleop_key


通过rqt_graph来查看这些节点之间的关系:

今天的内容有点超标,有些后面的内容提前放了上来,还是那句话,先大概了解即可。
本篇完。