使用事件处理程序

**目标:**了解ROS 2启动文件中的事件处理程序

教程级别: 中级

时间: 15分钟

背景

在ROS 2中,启动是执行和管理用户定义的进程的系统。它负责监视其启动的进程的状态,以及报告和响应这些进程状态的变化。这些变化称为事件,并可以通过向启动系统注册事件处理程序来处理。事件处理程序可以注册为特定事件,并且对于监视进程的状态非常有用。此外,它们可以用于定义一组复杂的规则,用于动态修改启动文件。

本教程展示了ROS 2启动文件中事件处理程序的使用示例。

先决条件

本教程使用 turtlesim 包。本教程还假设您已经 创建了一个名为“launch_tutorial”的新包,其构建类型为``ament_python``。

本教程扩展了 在启动文件中使用替换 教程中展示的代码。

使用事件处理程序

1 事件处理程序示例启动文件

在“launch_tutorial”包的“launch”文件夹中创建一个名为“example_event_handlers.launch.py”的新文件。

from launch_ros.actions import Node

from launch import LaunchDescription
from launch.actions import (DeclareLaunchArgument, EmitEvent, ExecuteProcess,
                            LogInfo, RegisterEventHandler, TimerAction)
from launch.conditions import IfCondition
from launch.event_handlers import (OnExecutionComplete, OnProcessExit,
                                OnProcessIO, OnProcessStart, OnShutdown)
from launch.events import Shutdown
from launch.substitutions import (EnvironmentVariable, FindExecutable,
                                LaunchConfiguration, LocalSubstitution,
                                PythonExpression)


def generate_launch_description():
    turtlesim_ns = LaunchConfiguration('turtlesim_ns')
    use_provided_red = LaunchConfiguration('use_provided_red')
    new_background_r = LaunchConfiguration('new_background_r')

    turtlesim_ns_launch_arg = DeclareLaunchArgument(
        'turtlesim_ns',
        default_value='turtlesim1'
    )
    use_provided_red_launch_arg = DeclareLaunchArgument(
        'use_provided_red',
        default_value='False'
    )
    new_background_r_launch_arg = DeclareLaunchArgument(
        'new_background_r',
        default_value='200'
    )

    turtlesim_node = Node(
        package='turtlesim',
        namespace=turtlesim_ns,
        executable='turtlesim_node',
        name='sim'
    )
    spawn_turtle = ExecuteProcess(
        cmd=[[
            FindExecutable(name='ros2'),
            ' service call ',
            turtlesim_ns,
            '/spawn ',
            'turtlesim/srv/Spawn ',
            '"{x: 2, y: 2, theta: 0.2}"'
        ]],
        shell=True
    )
    change_background_r = ExecuteProcess(
        cmd=[[
            FindExecutable(name='ros2'),
            ' param set ',
            turtlesim_ns,
            '/sim background_r ',
            '120'
        ]],
        shell=True
    )
    change_background_r_conditioned = ExecuteProcess(
        condition=IfCondition(
            PythonExpression([
                new_background_r,
                ' == 200',
                ' and ',
                use_provided_red
            ])
        ),
        cmd=[[
            FindExecutable(name='ros2'),
            ' param set ',
            turtlesim_ns,
            '/sim background_r ',
            new_background_r
        ]],
        shell=True
    )

    return LaunchDescription([
        turtlesim_ns_launch_arg,
        use_provided_red_launch_arg,
        new_background_r_launch_arg,
        turtlesim_node,
        RegisterEventHandler(
            OnProcessStart(
                target_action=turtlesim_node,
                on_start=[
                    LogInfo(msg='Turtlesim started, spawning turtle'),
                    spawn_turtle
                ]
            )
        ),
        RegisterEventHandler(
            OnProcessIO(
                target_action=spawn_turtle,
                on_stdout=lambda event: LogInfo(
                    msg='Spawn request says "{}"'.format(
                        event.text.decode().strip())
                )
            )
        ),
        RegisterEventHandler(
            OnExecutionComplete(
                target_action=spawn_turtle,
                on_completion=[
                    LogInfo(msg='Spawn finished'),
                    change_background_r,
                    TimerAction(
                        period=2.0,
                        actions=[change_background_r_conditioned],
                    )
                ]
            )
        ),
        RegisterEventHandler(
            OnProcessExit(
                target_action=turtlesim_node,
                on_exit=[
                    LogInfo(msg=(EnvironmentVariable(name='USER'),
                            ' closed the turtlesim window')),
                    EmitEvent(event=Shutdown(
                        reason='Window closed'))
                ]
            )
        ),
        RegisterEventHandler(
            OnShutdown(
                on_shutdown=[LogInfo(
                    msg=['Launch was asked to shutdown: ',
                        LocalSubstitution('event.reason')]
                )]
            )
        ),
    ])

在启动描述中定义了“OnProcessStart”、“OnProcessIO”、“OnExecutionComplete”、“OnProcessExit”和“OnShutdown”事件的“RegisterEventHandler”操作。

“OnProcessStart”事件处理程序用于注册在turtlesim节点启动时执行的回调函数。它在turtlesim节点启动时向控制台记录一条消息,并执行“spawn_turtle”操作。

RegisterEventHandler(
    OnProcessStart(
        target_action=turtlesim_node,
        on_start=[
            LogInfo(msg='Turtlesim started, spawning turtle'),
            spawn_turtle
        ]
    )
),

“OnProcessIO”事件处理程序用于注册在“spawn_turtle”操作写入其标准输出时执行的回调函数。它记录生成请求的结果。

RegisterEventHandler(
    OnProcessIO(
        target_action=spawn_turtle,
        on_stdout=lambda event: LogInfo(
            msg='Spawn request says "{}"'.format(
                event.text.decode().strip())
        )
    )
),

“OnExecutionComplete”事件处理程序用于注册在“spawn_turtle”操作完成时执行的回调函数。它在生成操作完成时向控制台记录一条消息,并执行“change_background_r”和“change_background_r_conditioned”操作。

RegisterEventHandler(
    OnExecutionComplete(
        target_action=spawn_turtle,
        on_completion=[
            LogInfo(msg='Spawn finished'),
            change_background_r,
            TimerAction(
                period=2.0,
                actions=[change_background_r_conditioned],
            )
        ]
    )
),

OnProcessExit 事件处理程序用于注册一个回调函数,当 turtlesim 节点退出时执行该函数。它将一条消息记录到控制台,并执行 EmitEvent 操作以在 turtlesim 节点退出时触发一个 Shutdown 事件。这意味着当 turtlesim 窗口关闭时,启动过程将会关闭。

RegisterEventHandler(
    OnProcessExit(
        target_action=turtlesim_node,
        on_exit=[
            LogInfo(msg=(EnvironmentVariable(name='USER'),
                    ' closed the turtlesim window')),
            EmitEvent(event=Shutdown(
                reason='Window closed'))
        ]
    )
),

最后,OnShutdown 事件处理程序用于注册一个回调函数,在要求关闭启动文件时执行该函数。它将一条消息记录到控制台,说明为什么要求关闭启动文件。它将消息记录为关闭的原因,例如 turtlesim 窗口的关闭或用户发出的 ctrl-c 信号。

RegisterEventHandler(
    OnShutdown(
        on_shutdown=[LogInfo(
            msg=['Launch was asked to shutdown: ',
                LocalSubstitution('event.reason')]
        )]
    )
),

构建软件包

转到工作空间的根目录,并构建软件包:

colcon build

构建完成后,请记得设置工作空间环境。

启动示例

现在你可以使用``ros2 launch``命令来启动``example_event_handlers.launch.py``文件。

ros2 launch launch_tutorial example_event_handlers.launch.py turtlesim_ns:='turtlesim3' use_provided_red:='True' new_background_r:=200

这将执行以下操作:

  1. 启动一个带有蓝色背景的turtlesim节点

  2. 生成第二只乌龟

  3. 如果提供的``background_r``参数为``200``且``use_provided_red``参数为``True``,则将颜色更改为紫色

  4. 如果提供的``background_r``参数为``200``且``use_provided_red``参数为``True``,则在两秒后将颜色更改为粉色

  5. 当turtlesim窗口关闭时关闭启动文件

此外,当以下情况发生时,它将在控制台上记录消息:

  1. turtlesim节点启动

  2. 执行spawn动作

  3. 执行``change_background_r``动作

  4. 执行``change_background_r_conditioned``动作

  5. turtlesim节点退出

  6. 要求终止启动进程。

文档

启动文档 提供了关于可用事件处理程序的详细信息。

总结

在本教程中,您学习了如何在启动文件中使用事件处理程序。您了解了它们的语法和使用示例,以定义一组复杂的规则,以动态修改启动文件。