使用ROS 2 launch启动可组合节点
在:doc:`组合教程<../Tutorials/Intermediate/Composition>`中,您了解了可组合节点以及如何从命令行中使用它们。在:doc:`启动教程<../Tutorials/Intermediate/Launch/Launch-Main>`中,您了解了启动文件以及如何使用它们来管理多个节点。
本指南将结合上述两个主题,教您如何为可组合节点编写启动文件。
设置
有关在安装ROS 2上的详细信息,请参阅:doc:安装说明。
如果您从软件包安装了ROS 2,请确保已安装``ros-humble-image-tools``。如果您下载了存档文件或从源代码构建了ROS 2,它已经是安装的一部分。
启动文件示例
下面是一个启动文件,用于在Python、XML和YAML中启动可组合节点。所有的启动文件都执行以下操作:
实例化一个带有重新映射、自定义参数和额外参数的cam2image可组合节点
实例化一个带有重新映射、自定义参数和额外参数的showimage可组合节点
import launch
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode
def generate_launch_description():
"""Generate launch description with multiple components."""
container = ComposableNodeContainer(
name='image_container',
namespace='',
package='rclcpp_components',
executable='component_container',
composable_node_descriptions=[
ComposableNode(
package='image_tools',
plugin='image_tools::Cam2Image',
name='cam2image',
remappings=[('/image', '/burgerimage')],
parameters=[{'width': 320, 'height': 240, 'burger_mode': True, 'history': 'keep_last'}],
extra_arguments=[{'use_intra_process_comms': True}]),
ComposableNode(
package='image_tools',
plugin='image_tools::ShowImage',
name='showimage',
remappings=[('/image', '/burgerimage')],
parameters=[{'history': 'keep_last'}],
extra_arguments=[{'use_intra_process_comms': True}])
],
output='both',
)
return launch.LaunchDescription([container])
<launch>
<node_container pkg="rclcpp_components" exec="component_container" name="image_container" namespace="">
<composable_node pkg="image_tools" plugin="image_tools::Cam2Image" name="cam2image" namespace="">
<remap from="/image" to="/burgerimage" />
<param name="width" value="320" />
<param name="height" value="240" />
<param name="burger_mode" value="true" />
<param name="history" value="keep_last" />
<extra_arg name="use_intra_process_comms" value="true" />
</composable_node>
<composable_node pkg="image_tools" plugin="image_tools::ShowImage" name="showimage" namespace="">
<remap from="/image" to="/burgerimage" />
<param name="history" value="keep_last" />
<extra_arg name="use_intra_process_comms" value="true" />
</composable_node>
</node_container>
</launch>
launch:
- node_container:
pkg: rclcpp_components
exec: component_container
name: image_container
namespace: ''
composable_node:
- pkg: image_tools
plugin: image_tools::Cam2Image
name: cam2image
namespace: ''
remap:
- from: /image
to: /burgerimage
param:
- name: width
value: 320
- name: height
value: 240
- name: burger_mode
value: true
- name: history
value: keep_last
extra_arg:
- name: use_intra_process_comms
value: 'true'
- pkg: image_tools
plugin: image_tools::ShowImage
name: showimage
namespace: ''
remap:
- from: /image
to: /burgerimage
param:
- name: history
value: keep_last
extra_arg:
- name: use_intra_process_comms
value: 'true'
将可组合节点加载到现有容器中
有时候容器可以由其他启动文件或命令行启动。在这种情况下,您需要将您的组件添加到现有容器中。为此,您可以使用``LoadComposableNodes``将组件加载到给定的容器中。下面的示例启动与上述相同的节点。
from launch import LaunchDescription
from launch_ros.actions import LoadComposableNodes, Node
from launch_ros.descriptions import ComposableNode
def generate_launch_description():
container = Node(
name='image_container',
package='rclcpp_components',
executable='component_container',
output='both',
)
load_composable_nodes = LoadComposableNodes(
target_container='image_container',
composable_node_descriptions=[
ComposableNode(
package='image_tools',
plugin='image_tools::Cam2Image',
name='cam2image',
remappings=[('/image', '/burgerimage')],
parameters=[{'width': 320, 'height': 240, 'burger_mode': True, 'history': 'keep_last'}],
extra_arguments=[{'use_intra_process_comms': True}],
),
ComposableNode(
package='image_tools',
plugin='image_tools::ShowImage',
name='showimage',
remappings=[('/image', '/burgerimage')],
parameters=[{'history': 'keep_last'}],
extra_arguments=[{'use_intra_process_comms': True}]
),
],
)
return LaunchDescription([container, load_composable_nodes])
<launch>
<node pkg="rclcpp_components" exec="component_container" name="image_container">
</node>
<load_composable_node target="image_container">
<composable_node pkg="image_tools" plugin="image_tools::Cam2Image" name="cam2image">
<remap from="/image" to="/burgerimage" />
<param name="width" value="320" />
<param name="height" value="240" />
<param name="burger_mode" value="true" />
<param name="history" value="keep_last" />
<extra_arg name="use_intra_process_comms" value="true" />
</composable_node>
<composable_node pkg="image_tools" plugin="image_tools::ShowImage" name="showimage" namespace="">
<remap from="/image" to="/burgerimage" />
<param name="history" value="keep_last" />
<extra_arg name="use_intra_process_comms" value="true" />
</composable_node>
</load_composable_node>
</launch>
launch:
- node_container:
pkg: rclcpp_components
exec: component_container
name: image_container
namespace: ''
composable_node:
- pkg: image_tools
plugin: image_tools::Cam2Image
name: cam2image
namespace: ''
remap:
- from: /image
to: /burgerimage
param:
- name: width
value: 320
- name: height
value: 240
- name: burger_mode
value: true
- name: history
value: keep_last
extra_arg:
- name: use_intra_process_comms
value: 'true'
- pkg: image_tools
plugin: image_tools::ShowImage
name: showimage
namespace: ''
remap:
- from: /image
to: /burgerimage
param:
- name: history
value: keep_last
extra_arg:
- name: use_intra_process_comms
value: 'true'
从命令行使用启动文件
上述任何一个启动文件都可以使用``ros2 launch``命令来运行。将数据复制到一个本地文件中,然后运行:
ros2 launch <path_to_launch_file>
Python、XML 或 YAML:我应该使用哪个?
有关更多信息,请参阅:doc:启动文件不同格式的讨论。