目标:学习使用 ROS 2 启动文件管理大型项目的最佳实践。
教程级别:中级
时间:20 分钟
目录
背景
先决条件
简介
编写启动文件
1. 顶层组织
2.参数
在启动文件中设置参数
加载 YAML 文件中的参数
在 YAML 文件中使用通配符
3. 命名空间
4. 复用节点
5 .参数覆盖
6. 重映射
7 个配置文件
8 个环境变量
运行启动文件
1. 更新 setup.py
2. 建立并运行
摘要
背景
本教程介绍了一些针对大型项目编写启动文件的技巧。重点是如何构建启动文件,以便在不同情况下尽可能多地复用。此外,它还涵盖了不同 ROS 2 启动工具的使用示例,如参数、YAML 文件、重映射、命名空间、默认参数和 RViz 配置。
先决条件
本教程使用 turtlesim 和 turtle_tf2_py 包。本教程还假设您已经创建了一个名为 launch_tutorial 的 ament_python 类型的新包。
简介
在机器人上的大型应用通常涉及几个相互连接的节点,每个节点都可以有许多参数。多乌龟模拟器中的多乌龟模拟可以作为一个很好的例子。乌龟模拟由多个乌龟节点、世界配置以及 TF 广播器和监听器节点组成。在所有这些节点之间,有大量的 ROS 参数影响这些节点的行为和外观。ROS 2 启动文件允许我们在一个地方启动所有节点并设置相应的参数。在教程的最后,你将在 launch_tutorial 包中构建 launch_turtlesim_launch.py 启动文件。这个启动文件将启动负责两个 turtlesim 模拟的不同节点,启动 TF 广播器和监听器,加载参数,并启动一个 RViz 配置。在本教程中,我们将讨论这个启动文件及其所有相关功能。
编写启动文件
1. 顶层组织
在编写启动文件的过程中,一个目标应该是使它们尽可能地可重用。这可以通过将相关的节点和配置聚集到单独的启动文件中来完成。之后,可以编写一个专用于特定配置的顶层启动文件。这将允许在相同的机器人之间移动而根本不需要更改启动文件。即使是从真实的机器人移动到模拟的机器人这样的更改,也只需做少量的更改。
我们现在将讨论使这成为可能的顶层启动文件结构。首先,我们将创建一个启动文件,该文件将调用单独的启动文件。为此,让我们在我们的 launch_tutorial 包的 /launch 文件夹中创建一个 launch_turtlesim_launch.py 文件。
import os # 导入os模块,这个模块提供了很多与操作系统交互的函数
from ament_index_python.packages import get_package_share_directory # 从ament_index_python.packages导入get_package_share_directory函数,这个函数用于获取包的共享目录
from launch import LaunchDescription # 从launch导入LaunchDescription,这是ROS2中用于描述启动过程的类
from launch.actions import IncludeLaunchDescription # 从launch.actions导入IncludeLaunchDescription,这是一个动作,用于包含其他的启动描述
from launch.launch_description_sources import PythonLaunchDescriptionSource # 从launch.launch_description_sources导入PythonLaunchDescriptionSource,这是一个描述源,用于从Python文件中加载启动描述
def generate_launch_description(): # 定义一个函数,用于生成启动描述
turtlesim_world_1 = IncludeLaunchDescription( # 创建一个IncludeLaunchDescription动作,用于包含turtlesim_world_1的启动描述
PythonLaunchDescriptionSource([os.path.join( # 使用PythonLaunchDescriptionSource从Python文件中加载启动描述
get_package_share_directory('launch_tutorial'), 'launch'), # 使用get_package_share_directory函数获取'launch_tutorial'包的共享目录,然后加上'launch'子目录
'/turtlesim_world_1_launch.py']) # 加上启动文件的名称,得到完整的文件路径
)
turtlesim_world_2 = IncludeLaunchDescription( # 创建一个IncludeLaunchDescription动作,用于包含turtlesim_world_2的启动描述
PythonLaunchDescriptionSource([os.path.join( # 使用PythonLaunchDescriptionSource从Python文件中加载启动描述
get_package_share_directory('launch_tutorial'), 'launch'), # 使用get_package_share_directory函数获取'launch_tutorial'包的共享目录,然后加上'launch'子目录
'/turtlesim_world_2_launch.py']) # 加上启动文件的名称,得到完整的文件路径
)
broadcaster_listener_nodes = IncludeLaunchDescription( # 创建一个IncludeLaunchDescription动作,用于包含broadcaster_listener_nodes的启动描述
PythonLaunchDescriptionSource([os.path.join( # 使用PythonLaunchDescriptionSource从Python文件中加载启动描述
get_package_share_directory('launch_tutorial'), 'launch'), # 使用get_package_share_directory函数获取'launch_tutorial'包的共享目录,然后加上'launch'子目录
'/broadcaster_listener_launch.py']), # 加上启动文件的名称,得到完整的文件路径
launch_arguments={'target_frame': 'carrot1'}.items(), # 设置启动参数,这些参数会传递给被包含的启动描述
)
mimic_node = IncludeLaunchDescription( # 创建一个IncludeLaunchDescription动作,用于包含mimic_node的启动描述
PythonLaunchDescriptionSource([os.path.join( # 使用PythonLaunchDescriptionSource从Python文件中加载启动描述
get_package_share_directory('launch_tutorial'), 'launch'), # 使用get_package_share_directory函数获取'launch_tutorial'包的共享目录,然后加上'launch'子目录
'/mimic_launch.py']) # 加上启动文件的名称,得到完整的文件路径
)
fixed_frame_node = IncludeLaunchDescription( # 创建一个IncludeLaunchDescription动作,用于包含fixed_frame_node的启动描述
PythonLaunchDescriptionSource([os.path.join( # 使用PythonLaunchDescriptionSource从Python文件中加载启动描述
get_package_share_directory('launch_tutorial'), 'launch'), # 使用get_package_share_directory函数获取'launch_tutorial'包的共享目录,然后加上'launch'子目录
'/fixed_broadcaster_launch.py']) # 加上启动文件的名称,得到完整的文件路径
)
rviz_node = IncludeLaunchDescription( # 创建一个IncludeLaunchDescription动作,用于包含rviz_node的启动描述
PythonLaunchDescriptionSource([os.path.join( # 使用PythonLaunchDescriptionSource从Python文件中加载启动描述
get_package_share_directory('launch_tutorial'), 'launch'), # 使用get_package_share_directory函数获取'launch_tutorial'包的共享目录,然后加上'launch'子目录
'/turtlesim_rviz_launch.py']) # 加上启动文件的名称,得到完整的文件路径
)
return LaunchDescription([ # 创建一个LaunchDescription,包含了所有的启动动作
turtlesim_world_1,
turtlesim_world_2,
broadcaster_listener_nodes,
mimic_node,
fixed_frame_node,
rviz_node
])
此启动文件包含一组其他启动文件。这些包含的启动文件中的每一个都包含节点、参数,可能还包含嵌套的包含,这些都与系统的某一部分相关。确切地说,我们启动了两个 turtlesim 仿真世界、TF 广播器、TF 监听器、mimic、固定帧广播器和 RViz 节点。
便条
设计提示:顶层启动文件应该简短,包括对应用程序子组件的其他文件的包含,以及常见的更改参数。
以这种方式编写启动文件可以轻松地更换系统的一部分,正如我们稍后将看到的。然而,由于性能和使用原因,有些节点或启动文件需要单独启动。
便条
设计提示:在决定应用程序需要多少个顶级启动文件时,要注意权衡利弊。
2 参数
在启动文件中设置参数
我们将从编写一个启动文件开始,该文件将启动我们的第一个 turtlesim 仿真。首先,创建一个名为 turtlesim_world_1_launch.py 的新文件。
from launch import LaunchDescription # 从launch导入LaunchDescription,这是ROS2中用于描述启动过程的类
from launch.actions import DeclareLaunchArgument # 从launch.actions导入DeclareLaunchArgument,这是一个动作,用于声明启动参数
from launch.substitutions import LaunchConfiguration, TextSubstitution # 从launch.substitutions导入LaunchConfiguration和TextSubstitution,这些是用于替换启动参数的类
from launch_ros.actions import Node # 从launch_ros.actions导入Node,这是一个动作,用于启动ROS节点
def generate_launch_description(): # 定义一个函数,用于生成启动描述
background_r_launch_arg = DeclareLaunchArgument( # 创建一个DeclareLaunchArgument动作,用于声明'background_r'参数
'background_r', default_value=TextSubstitution(text='0') # 参数的默认值是'0'
)
background_g_launch_arg = DeclareLaunchArgument( # 创建一个DeclareLaunchArgument动作,用于声明'background_g'参数
'background_g', default_value=TextSubstitution(text='84') # 参数的默认值是'84'
)
background_b_launch_arg = DeclareLaunchArgument( # 创建一个DeclareLaunchArgument动作,用于声明'background_b'参数
'background_b', default_value=TextSubstitution(text='122') # 参数的默认值是'122'
)
return LaunchDescription([ # 创建一个LaunchDescription,包含了所有的启动动作
background_r_launch_arg,
background_g_launch_arg,
background_b_launch_arg,
Node( # 创建一个Node动作,用于启动一个ROS节点
package='turtlesim', # 节点所在的包是'turtlesim'
executable='turtlesim_node', # 节点的可执行文件是'turtlesim_node'
name='sim', # 节点的名称是'sim'
parameters=[{ # 设置节点的参数
'background_r': LaunchConfiguration('background_r'), # 'background_r'参数的值是'background_r'启动参数的值
'background_g': LaunchConfiguration('background_g'), # 'background_g'参数的值是'background_g'启动参数的值
'background_b': LaunchConfiguration('background_b'), # 'background_b'参数的值是'background_b'启动参数的值
}]
),
])此启动文件启动 turtlesim_node 节点,该节点启动 turtlesim 仿真,并将定义的仿真配置参数传递给节点。
加载 YAML 文件中的参数
在第二次启动中,我们将启动一个配置不同的第二个 turtlesim 仿真。现在创建一个 turtlesim_world_2_launch.py 文件。
import os # 导入os模块,这个模块提供了很多与操作系统交互的函数
from ament_index_python.packages import get_package_share_directory # 从ament_index_python.packages导入get_package_share_directory函数,这个函数用于获取包的共享目录
from launch import LaunchDescription # 从launch导入LaunchDescription,这是ROS2中用于描述启动过程的类
from launch_ros.actions import Node # 从launch_ros.actions导入Node,这是一个动作,用于启动ROS节点
def generate_launch_description(): # 定义一个函数,用于生成启动描述
config = os.path.join( # 使用os.path.join函数拼接文件路径
get_package_share_directory('launch_tutorial'), # 使用get_package_share_directory函数获取'launch_tutorial'包的共享目录
'config', # 加上'config'子目录
'turtlesim.yaml' # 加上配置文件的名称,得到完整的文件路径
)
return LaunchDescription([ # 创建一个LaunchDescription,包含了所有的启动动作
Node( # 创建一个Node动作,用于启动一个ROS节点
package='turtlesim', # 节点所在的包是'turtlesim'
executable='turtlesim_node', # 节点的可执行文件是'turtlesim_node'
namespace='turtlesim2', # 节点的命名空间是'turtlesim2'
name='sim', # 节点的名称是'sim'
parameters=[config] # 设置节点的参数,参数的值是从配置文件中加载的
)
])此启动文件将启动相同的 turtlesim_node ,参数值直接从 YAML 配置文件加载。在 YAML 文件中定义参数和参数使得存储和加载大量变量变得容易。此外,YAML 文件可以轻松地从当前 ros2 param 列表中导出。要了解如何做到这一点,请参阅理解参数教程。
现在让我们在包的 /config 文件夹中创建一个配置文件 turtlesim.yaml ,它将由我们的启动文件加载。
/turtlesim2/sim:
ros__parameters:
background_b: 255
background_g: 86
background_r: 150如果我们现在启动 turtlesim_world_2_launch.py 启动文件,我们将启动带有预配置背景颜色的 turtlesim_node 。
要了解更多关于使用参数和使用 YAML 文件的信息,请查看“理解参数”教程。
使用通配符在 YAML 文件中
在某些情况下,我们希望在多个节点中设置相同的参数。这些节点可能具有不同的命名空间或名称,但仍然具有相同的参数。定义单独的 YAML 文件来明确指定命名空间和节点名称并不高效。一种解决方案是使用通配符,通配符作为文本值中未知字符的替代,以将参数应用于几个不同的节点。
现在,让我们创建一个新的 turtlesim_world_3_launch.py 文件,类似于 turtlesim_world_2_launch.py ,以包含另一个 turtlesim_node 节点。
...
Node(
package='turtlesim',
executable='turtlesim_node',
namespace='turtlesim3',
name='sim',
parameters=[config]
)加载相同的 YAML 文件,然而,不会影响第三个 turtlesim 世界的外观。其原因是它的参数存储在另一个命名空间下,如下所示:
/turtlesim3/sim:
ros__parameters:
background_b: 255
background_g: 86
background_r: 150因此,我们不需要为使用相同参数的同一节点创建新的配置,我们可以使用通配符语法。 /** 将为每个节点分配所有参数,尽管节点名称和命名空间有所不同。
我们现在将以以下方式更新 turtlesim.yaml ,在 /config 文件夹中:
/**:
ros__parameters:
background_b: 255
background_g: 86
background_r: 150现在在我们的主启动文件中包括 turtlesim_world_3_launch.py 启动描述。使用该配置文件在我们的启动描述中将会把 background_b 、 background_g 和 background_r 参数指定为 turtlesim3/sim 和 turtlesim2/sim 节点中的特定值。
3. 命名空间
您可能已经注意到,我们已经在 turtlesim_world_2_launch.py 文件中为 turtlesim 世界定义了命名空间。唯一的命名空间允许系统启动两个相似的节点,而不会发生节点名称或主题名称冲突。
namespace='turtlesim2',然而,如果启动文件包含大量节点,为每个节点定义命名空间可能会变得乏味。为了解决这个问题,可以使用 PushROSNamespace 操作来为每个启动文件描述定义全局命名空间。每个嵌套节点将自动继承该命名空间。
为了做到这一点,首先,我们需要从 turtlesim_world_2_launch.py 文件中删除 namespace='turtlesim2' 行。之后,我们需要更新 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 。因此, turtlesim_world_2_launch.py 启动描述中的每个节点都将具有 turtlesim2 命名空间。
import os # 导入os模块,这个模块提供了很多与操作系统交互的函数
from ament_index_python.packages import get_package_share_directory # 从ament_index_python.packages导入get_package_share_directory函数,这个函数用于获取包的共享目录
from launch import LaunchDescription # 从launch导入LaunchDescription,这是ROS2中用于描述启动过程的类
from launch.actions import IncludeLaunchDescription # 从launch.actions导入IncludeLaunchDescription,这是一个动作,用于包含其他的启动描述
from launch.launch_description_sources import PythonLaunchDescriptionSource # 从launch.launch_description_sources导入PythonLaunchDescriptionSource,这是一个描述源,用于从Python文件中加载启动描述
def generate_launch_description(): # 定义一个函数,用于生成启动描述
turtlesim_world_1 = IncludeLaunchDescription( # 创建一个IncludeLaunchDescription动作,用于包含turtlesim_world_1的启动描述
PythonLaunchDescriptionSource([os.path.join( # 使用PythonLaunchDescriptionSource从Python文件中加载启动描述
get_package_share_directory('launch_tutorial'), 'launch'), # 使用get_package_share_directory函数获取'launch_tutorial'包的共享目录,然后加上'launch'子目录
'/turtlesim_world_1_launch.py']) # 加上启动文件的名称,得到完整的文件路径
)
turtlesim_world_2 = IncludeLaunchDescription( # 创建一个IncludeLaunchDescription动作,用于包含turtlesim_world_2的启动描述
PythonLaunchDescriptionSource([os.path.join( # 使用PythonLaunchDescriptionSource从Python文件中加载启动描述
get_package_share_directory('launch_tutorial'), 'launch'), # 使用get_package_share_directory函数获取'launch_tutorial'包的共享目录,然后加上'launch'子目录
'/turtlesim_world_2_launch.py']) # 加上启动文件的名称,得到完整的文件路径
)
turtlesim_world_2_with_namespace = GroupAction( # 创建一个GroupAction动作,用于将一组动作组合在一起
actions=[ # 这个动作包含了两个子动作
PushROSNamespace('turtlesim2'), # 第一个子动作是PushROSNamespace,用于将命名空间推送到命名空间堆栈
turtlesim_world_2, # 第二个子动作是turtlesim_world_2的启动描述
]
)
broadcaster_listener_nodes = IncludeLaunchDescription( # 创建一个IncludeLaunchDescription动作,用于包含broadcaster_listener_nodes的启动描述
PythonLaunchDescriptionSource([os.path.join( # 使用PythonLaunchDescriptionSource从Python文件中加载启动描述
get_package_share_directory('launch_tutorial'), 'launch'), # 使用get_package_share_directory函数获取'launch_tutorial'包的共享目录,然后加上'launch'子目录
'/broadcaster_listener_launch.py']), # 加上启动文件的名称,得到完整的文件路径
launch_arguments={'target_frame': 'carrot1'}.items(), # 设置启动参数,这些参数会传递给被包含的启动描述
)
mimic_node = IncludeLaunchDescription( # 创建一个IncludeLaunchDescription动作,用于包含mimic_node的启动描述
PythonLaunchDescriptionSource([os.path.join( # 使用PythonLaunchDescriptionSource从Python文件中加载启动描述
get_package_share_directory('launch_tutorial'), 'launch'), # 使用get_package_share_directory函数获取'launch_tutorial'包的共享目录,然后加上'launch'子目录
'/mimic_launch.py']) # 加上启动文件的名称,得到完整的文件路径
)
fixed_frame_node = IncludeLaunchDescription( # 创建一个IncludeLaunchDescription动作,用于包含fixed_frame_node的启动描述
PythonLaunchDescriptionSource([os.path.join( # 使用PythonLaunchDescriptionSource从Python文件中加载启动描述
get_package_share_directory('launch_tutorial'), 'launch'), # 使用get_package_share_directory函数获取'launch_tutorial'包的共享目录,然后加上'launch'子目录
'/fixed_broadcaster_launch.py']) # 加上启动文件的名称,得到完整的文件路径
)
rviz_node = IncludeLaunchDescription( # 创建一个IncludeLaunchDescription动作,用于包含rviz_node的启动描述
PythonLaunchDescriptionSource([os.path.join( # 使用PythonLaunchDescriptionSource从Python文件中加载启动描述
get_package_share_directory('launch_tutorial'), 'launch'), # 使用get_package_share_directory函数获取'launch_tutorial'包的共享目录,然后加上'launch'子目录
'/turtlesim_rviz_launch.py']) # 加上启动文件的名称,得到完整的文件路径
)
return LaunchDescription([ # 创建一个LaunchDescription,包含了所有的启动动作
turtlesim_world_1,
turtlesim_world_2_with_namespace,
broadcaster_listener_nodes,
mimic_node,
fixed_frame_node,
rviz_node
])4. 重用节点
现在创建一个 broadcaster_listener_launch.py 文件。
# 从launch模块导入LaunchDescription类
from launch import LaunchDescription
# 从launch.actions模块导入DeclareLaunchArgument类
from launch.actions import DeclareLaunchArgument
# 从launch.substitutions模块导入LaunchConfiguration类
from launch.substitutions import LaunchConfiguration
# 从launch_ros.actions模块导入Node类
from launch_ros.actions import Node
# 定义一个名为generate_launch_description的函数
def generate_launch_description():
# 返回一个LaunchDescription对象
return LaunchDescription([
# 声明一个启动参数,参数名为'target_frame',默认值为'turtle1',描述为'Target frame name.'
DeclareLaunchArgument(
'target_frame', default_value='turtle1',
description='Target frame name.'
),
# 创建一个Node对象,包名为'turtle_tf2_py',可执行文件名为'turtle_tf2_broadcaster',节点名为'broadcaster1',参数为{'turtlename': 'turtle1'}
Node(
package='turtle_tf2_py',
executable='turtle_tf2_broadcaster',
name='broadcaster1',
parameters=[
{'turtlename': 'turtle1'}
]
),
# 创建一个Node对象,包名为'turtle_tf2_py',可执行文件名为'turtle_tf2_broadcaster',节点名为'broadcaster2',参数为{'turtlename': 'turtle2'}
Node(
package='turtle_tf2_py',
executable='turtle_tf2_broadcaster',
name='broadcaster2',
parameters=[
{'turtlename': 'turtle2'}
]
),
# 创建一个Node对象,包名为'turtle_tf2_py',可执行文件名为'turtle_tf2_listener',节点名为'listener',参数为{'target_frame': LaunchConfiguration('target_frame')}
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 参数。
5 参数覆盖
请记住,我们在顶级启动文件中调用了 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(),
)这种语法允许我们将默认的目标框架更改为 carrot1 。如果你希望 turtle2 跟随 turtle1 而不是 carrot1 ,只需移除定义 launch_arguments 的那一行。这将会给 target_frame 分配它的默认值,即 turtle1 。
6 重新映射
现在创建一个 mimic_launch.py 文件。
from launch import LaunchDescription # 从launch模块导入LaunchDescription类,用于描述要启动的节点
from launch_ros.actions import Node # 从launch_ros.actions导入Node类,用于描述要启动的ROS节点
def generate_launch_description(): # 定义一个函数,用于生成launch描述
return LaunchDescription([ # 返回一个LaunchDescription实例,包含了所有的节点
Node( # 创建一个Node实例,表示一个ROS节点
package='turtlesim', # 节点所在的包名
executable='mimic', # 节点的可执行文件名
name='mimic', # 节点的名字
remappings=[ # 重新映射的主题名
('/input/pose', '/turtle2/pose'), # 将'/input/pose'主题名映射为'/turtle2/pose'
('/output/cmd_vel', '/turtlesim2/turtle1/cmd_vel'), # 将'/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 。
7 . 配置文件
现在让我们创建一个名为 turtlesim_rviz_launch.py 的文件。
import os # 导入os模块,用于处理文件和目录
from ament_index_python.packages import get_package_share_directory # 从ament_index_python.packages导入get_package_share_directory函数,用于获取包的共享目录
from launch import LaunchDescription # 从launch模块导入LaunchDescription类,用于描述要启动的节点
from launch_ros.actions import Node # 从launch_ros.actions导入Node类,用于描述要启动的ROS节点
def generate_launch_description(): # 定义一个函数,用于生成launch描述
rviz_config = os.path.join( # 使用os.path.join函数连接路径
get_package_share_directory('turtle_tf2_py'), # 获取'turtle_tf2_py'包的共享目录
'rviz', # rviz目录
'turtle_rviz.rviz' # rviz配置文件
)
return LaunchDescription([ # 返回一个LaunchDescription实例,包含了所有的节点
Node( # 创建一个Node实例,表示一个ROS节点
package='rviz2', # 节点所在的包名
executable='rviz2', # 节点的可执行文件名
name='rviz2', # 节点的名字
arguments=['-d', rviz_config] # 启动节点时的命令行参数,'-d'表示加载rviz配置文件
)
])此启动文件将使用 turtle_tf2_py 包中定义的配置文件启动 RViz。此 RViz 配置将设置世界框架,启用 TF 可视化,并以俯视图启动 RViz。
8 . 环境变量
让我们现在在我们的包中创建一个名为 fixed_broadcaster_launch.py 的最后一个启动文件。
from launch import LaunchDescription # 从launch模块导入LaunchDescription类,用于描述要启动的节点
from launch.actions import DeclareLaunchArgument # 从launch.actions导入DeclareLaunchArgument类,用于声明启动参数
from launch.substitutions import EnvironmentVariable, LaunchConfiguration # 从launch.substitutions导入EnvironmentVariable和LaunchConfiguration类,用于获取环境变量和启动配置
from launch_ros.actions import Node # 从launch_ros.actions导入Node类,用于描述要启动的ROS节点
def generate_launch_description(): # 定义一个函数,用于生成launch描述
return LaunchDescription([ # 返回一个LaunchDescription实例,包含了所有的节点
DeclareLaunchArgument( # 创建一个DeclareLaunchArgument实例,表示一个启动参数
'node_prefix', # 参数名
default_value=[EnvironmentVariable('USER'), '_'], # 默认值,这里是用户的环境变量'USER'和一个下划线
description='prefix for node name' # 参数描述
),
Node( # 创建一个Node实例,表示一个ROS节点
package='turtle_tf2_py', # 节点所在的包名
executable='fixed_frame_tf2_broadcaster', # 节点的可执行文件名
name=[LaunchConfiguration('node_prefix'), 'fixed_broadcaster'], # 节点的名字,这里是启动配置'node_prefix'和'fixed_broadcaster'
),
])此启动文件展示了如何在启动文件内调用环境变量。环境变量可用于定义或推送命名空间,以区分不同计算机或机器人上的节点。
此启动文件展示了如何在启动文件内调用环境变量。环境变量可用于定义或推送命名空间,以区分不同计算机或机器人上的节点。
运行启动文件
1. 更新 setup.py 文件
打开 setup.py 并添加以下行,以便从 launch/ 文件夹安装启动文件和来自 config/ 的配置文件。 data_files 字段现在应该如下所示:
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'))),
],2. 构建并运行
为了最终查看我们代码的结果,请构建包并使用以下命令启动顶级启动文件:
ros2 launch launch_tutorial launch_turtlesim_launch.py
cxy@ubuntu2404-cxy:~/ros2_ws$ colcon build --packages-select launch_tutorial
Starting >>> launch_tutorial
Finished <<< launch_tutorial [2.55s]
Summary: 1 package finished [2.81s]
cxy@ubuntu2404-cxy:~/ros2_ws$ . install/setup.bash
cxy@ubuntu2404-cxy:~/ros2_ros2 launch launch_tutorial launch_turtlesim_launch.py
[INFO] [launch]: All log files can be found below /home/cxy/.ros/log/2024-07-10-13-27-41-961767-ubuntu2404-cxy-31019
[INFO] [launch]: D
efault logging verbosity is set to INFO
[INFO] [turtlesim_node-1]: process started with pid [31029]
[INFO] [turtlesim_node-2]: process started with pid [31030]
[INFO] [turtle_tf2_broadcaster-3]: process started with pid [31031]
[INFO] [turtle_tf2_broadcaster-4]: process started with pid [31032]
[INFO] [turtle_tf2_listener-5]: process started with pid [31033]
[INFO] [mimic-6]: process started with pid [31034]
[INFO] [fixed_frame_tf2_broadcaster-7]: process started with pid [31035]
[INFO] [rviz2-8]: process started with pid [31036]
[turtlesim_node-1] [INFO] [1720589262.316426113] [sim]: Starting turtlesim with node name /sim
[turtlesim_node-1] [INFO] [1720589262.323025339] [sim]: Spawning turtle [turtle1] at x=[5.544445], y=[5.544445], theta=[0.000000]
[turtlesim_node-2] [INFO] [1720589262.363931114] [turtlesim2.sim]: Starting turtlesim with node name /turtlesim2/sim
[turtlesim_node-2] [INFO] [1720589262.372001131] [turtlesim2.sim]: Spawning turtle [turtle1] at x=[5.544445], y=[5.544445], theta=[0.000000]
[rviz2-8] [INFO] [1720589262.983923182] [rviz2]: Stereo is NOT SUPPORTED
[rviz2-8] [INFO] [1720589262.984068376] [rviz2]: OpenGl version: 4.6 (GLSL 4.6)
[rviz2-8] [INFO] [1720589263.092694231] [rviz2]: Stereo is NOT SUPPORTED
[turtlesim_node-1] [INFO] [1720589263.923695573] [sim]: Spawning turtle [turtle2] at x=[4.000000], y=[2.000000], theta=[0.000000]
[turtle_tf2_listener-5] [INFO] [1720589264.949106836] [listener]: Successfully spawned turtle2您现在将看到两个 turtlesim 模拟开始了。第一个里有两只乌龟,第二个里有一只。在第一个模拟中, turtle2 出现在世界的左下角。它的目标是到达 carrot1 框架,该框架在 x 轴上相对于 turtle1 框架有五米远。
在第二个中的 turtlesim2/turtle1 旨在模仿 turtle2 的行为。

如果您想要控制 turtle1 ,请运行 teleop 节点。
ros2 run turtlesim turtle_teleop_key
除此之外,RViz 应该已经启动。它将显示所有与 world 框架相关的乌龟框架,其原点位于左下角。

摘要
在本教程中,您学习了使用 ROS 2 启动文件管理大型项目的各种技巧和实践。
笔记
cxy@ubuntu2404-cxy:~/ros2_ws$ source /home/cxy/ros2_jazzy/install/setup.bash
cxy@ubuntu2404-cxy:~/ros2_ws$ colcon build --packages-select launch_tutorial
Starting >>> launch_tutorial
Finished <<< launch_tutorial [2.97s]
Summary: 1 package finished [3.22s]
cxy@ubuntu2404-cxy:~/ros2_ws$ . install/setup.bash
cxy@ubuntu2404-cxy:~/ros2_ws$ ros2 launch launch_tutorial launch_turtlesim_launch.pycxy@ubuntu2404-cxy:~/ros2_ws$ sudo apt-get install ros-jazzy-turtle-tf2-py ros-jazzy-tf2-toolscxy@ubuntu2404-cxy:~$ cd /home/cxy/ros2_ws/src/launch_tutorial/launch
cxy@ubuntu2404-cxy:~/ros2_ws/src/launch_tutorial/launch$ gedit turtlesim_world_1_launch.py
cxy@ubuntu2404-cxy:~/ros2_ws/src/launch_tutorial/launch$ gedit turtlesim_world_2_launch.py
cxy@ubuntu2404-cxy:~/ros2_ws/src/launch_tutorial/launch$ gedit turtlesim_world_3_launch.py
cxy@ubuntu2404-cxy:~/ros2_ws/src/launch_tutorial/launch$ gedit broadcaster_listener_launch.py
cxy@ubuntu2404-cxy:~/ros2_ws/src/launch_tutorial/launch$ gedit mimic_launch.py
cxy@ubuntu2404-cxy:~/ros2_ws/src/launch_tutorial/launch$ gedit turtlesim_rviz_launch.py
cxy@ubuntu2404-cxy:~/ros2_ws/src/launch_tutorial/launch$ gedit fixed_broadcaster_launch.py
cxy@ubuntu2404-cxy:~/ros2_ws/src/launch_tutorial/launch$cxy@ubuntu2404-cxy:~$ cd /home/cxy/ros2_ws/src/launch_tutorial/config
cxy@ubuntu2404-cxy:~/ros2_ws/src/launch_tutorial/config$ gedit turtlesim.yaml
cxy@ubuntu2404-cxy:~/ros2_ws/src/launch_tutorial/config$ gedit turtlesim.yaml
cxy@ubuntu2404-cxy:~/ros2_ws/src/launch_tutorial/config$ gedit turtlesim.yaml
cxy@ubuntu2404-cxy:~/ros2_ws/src/launch_tutorial/config$
6153

被折叠的 条评论
为什么被折叠?



