编写新的行为插件

概述

本教程展示了如何创建自己的行为插件。行为插件位于行为服务器中。与规划器和控制器服务器不同,每个行为将拥有自己独特的动作服务器。规划器和控制器具有相同的API,因为它们执行相同的任务。然而,恢复可以用于执行各种各样的任务,因此每个行为可以拥有自己独特的动作消息定义和服务器。这使得行为服务器具有极大的灵活性,可以实现任何可能的行为动作,而无需进行其他的重用。

要求

  • ROS 2(二进制或源码编译)

  • Nav2(包括依赖项)

  • Gazebo

  • Turtlebot3

教程步骤

1- 创建一个新的行为插件

我们将创建一个简单的发送短信行为。它将使用Twilio通过短信向远程运营中心发送消息。本教程中的代码可以在 navigation_tutorials 仓库的 nav2_sms_behavior 中找到。该软件包可作为编写行为插件的参考。

我们的示例插件实现了 nav2_core::Behavior 的插件类。但是,我们在 nav2_behaviors 中有一个很好的动作包装器,因此我们在此应用程序中使用 nav2_behaviors::TimedBehavior 基类。这个包装器类派生自 nav2_core 类,因此可以用作插件,但处理了所需的大部分 ROS 2 动作服务器样板代码。

nav2_core 中的基类提供了4个纯虚方法来实现行为插件。行为服务器将使用插件来托管插件,但每个插件将提供自己独特的动作服务器接口。让我们了解更多关于编写行为插件所需的方法**如果您没有使用``nav2_behaviors``封装**。

虚拟方法

方法描述

需要重写?

configure()

当服务器进入 on_configure 状态时调用该方法。理想情况下,此方法应该执行 ROS 参数的声明和行为成员变量的初始化。此方法接受 4 个输入参数:父节点的共享指针、行为名称、tf 缓冲指针和碰撞检查器的共享指针。

activate()

当行为服务器进入on_activate状态时调用该方法。理想情况下,此方法应实现在行为进入活动状态之前必要的操作。

deactivate()

当行为服务器进入on_deactivate状态时调用该方法。理想情况下,此方法应实现在行为进入非活动状态之前必要的操作。

cleanup()

当行为服务器进入on_cleanup状态时调用该方法。理想情况下,此方法应清理为行为创建的资源。

对于提供ROS 2动作接口和样板代码的``nav2_behaviors``包装器,我们有4个虚拟方法需要实现。本教程使用这个包装器,因此我们将解决以下主要要素。

虚拟方法

方法描述

需要重写?

onRun()

当接收到新的行为动作请求时立即调用该方法。将行为目标传递给处理,并应启动行为初始化/处理。

onCycleUpdate()

以行为更新速率调用该方法,并应完成任何必要的更新。例如,对于旋转,可以计算当前周期的命令速度,将其发布并检查完成情况。

onConfigure()

当行为服务器进入on_configure状态时调用该方法。理想情况下,此方法应该实现在行为进入已配置状态之前必需的操作(获取参数等)。

No

onCleanup()

当行为服务器进入on_cleanup状态时调用该方法。理想情况下,此方法应清理为行为创建的资源。

No

对于本教程,我们将使用``onRun()``, onCycleUpdate()``和``onConfigure()``方法来创建短信行为。为了简洁起见,我们将跳过``onConfigure(),但仅声明参数。

在恢复中,onRun() 方法必须设置任何初始状态并启动行为。对于我们的求助行为,我们可以在此方法中轻松计算出所有需要的内容。

Status SendSms::onRun(const std::shared_ptr<const Action::Goal> command)
{
  std::string response;
  bool message_success = _twilio->send_message(
    _to_number,
    _from_number,
    command->message,
    response,
    "",
    false);

  if (!message_success) {
    RCLCPP_INFO(node_->get_logger(), "SMS send failed.");
    return Status::FAILED;
  }

  RCLCPP_INFO(node_->get_logger(), "SMS sent successfully!");
  return Status::SUCCEEDED;
}

我们接收到一个动作目标``command``,我们想要处理它。command``包含一个字段``message,其中包含我们想要通过短信发送给作战指挥中心的消息。这是我们希望发送的“求救”短信,以便将其发送给我们的战友。

我们使用 Twilio 服务完成此任务。请`创建一个账户 <https://www.twilio.com/>`_,并获取创建该服务所需的所有相关信息(例如 account_sidauth_token 和一个电话号码)。您可以将这些值作为参数设置到与 onConfigure() 参数声明相对应的配置文件中。

我们使用``_twilio``对象发送带有配置文件中的账户信息的消息。我们发送消息,并在屏幕上记录消息是否成功发送。根据这个值,我们返回``FAILED``或``SUCCEEDED``,以便返回给动作客户端。

onCycleUpdate() 对于我们这个短时运行的行为来说非常简单。如果行为需要长时间运行,例如旋转、导航到安全区域或离开危险区域并等待帮助,那么此函数将检查超时或计算控制值。对于我们的示例,我们简单地返回成功,因为我们已经在 onRun() 中完成了我们的任务。

Status SendSms::onCycleUpdate()
{
  return Status::SUCCEEDED;
}

剩余的方法未被使用,不需要强制重写它们。

2- 导出行为插件

现在我们已经创建了自定义行为,我们需要导出我们的行为插件,以便行为服务器能够看到它。插件在运行时加载,如果它们不可见,那么我们的行为服务器将无法加载它。在ROS 2中,导出和加载插件由``pluginlib``处理。

在我们的教程中,nav2_sms_bahavior::SendSms 类以 nav2_core::Behavior 动态加载,它是我们的基类。

  1. 要导出该行为,我们需要提供两行代码。

#include "pluginlib/class_list_macros.hpp"
PLUGINLIB_EXPORT_CLASS(nav2_sms_bahavior::SendSms, nav2_core::Behavior)

请注意,它需要 pluginlib 来导出插件的类。Pluginlib 提供了宏 PLUGINLIB_EXPORT_CLASS,它完成了所有的导出工作。

按照惯例,将这些代码放在文件末尾是一个好的做法,但从技术上讲,也可以放在文件顶部。

  1. 下一步是在软件包的根目录中创建插件描述文件。例如,在我们的教程软件包中,我们可以创建一个名为``behavior_plugin.xml``的文件。该文件包含以下信息

  • library path:插件的库名称和位置。

  • class name:类的名称。

  • class type:类的类型。

  • base class:基类的名称。

  • description:插件的描述。

<library path="nav2_sms_behavior_plugin">
  <class name="nav2_sms_behavior/SendSms" type="nav2_sms_behavior::SendSms" base_class_type="nav2_core::Behavior">
    <description>This is an example plugin which produces an SMS text message recovery.</description>
  </class>
</library>
  1. 下一步是使用``CMakeLists.txt``通过使用cmake函数``pluginlib_export_plugin_description_file()``导出插件。此函数将插件描述文件安装到``share``目录,并设置ament索引以便发现它。

pluginlib_export_plugin_description_file(nav2_core behavior_plugin.xml)
  1. 插件描述文件还应添加到``package.xml``中。

<export>
  <build_type>ament_cmake</build_type>
  <nav2_core plugin="${prefix}/behavior_plugin.xml" />
</export>
  1. 编译后应该注册该插件。接下来,我们将使用这个插件。

3- 通过参数文件传递插件名称

要启用该插件,我们需要修改``nav2_params.yaml``文件,如下所示,以替换以下参数

behavior_server:  # Humble and later
recoveries_server:  # Galactic and earlier
  ros__parameters:
    costmap_topic: local_costmap/costmap_raw
    footprint_topic: local_costmap/published_footprint
    cycle_frequency: 10.0
    behavior_plugins: ["spin", "backup", "wait"]  # Humble and later
    recovery_plugins: ["spin", "backup", "wait"]  # Galactic and earlier
    spin:
      plugin: "nav2_behaviors/Spin"
    backup:
      plugin: "nav2_behaviors/BackUp"
    wait:
      plugin: "nav2_behaviors/Wait"
    global_frame: odom
    robot_base_frame: base_link
    transform_timeout: 0.1
    use_sim_time: true
    simulate_ahead_time: 2.0
    max_rotational_vel: 1.0
    min_rotational_vel: 0.4
    rotational_acc_lim: 3.2

with

behavior_server:  # Humble and newer
recoveries_server:  # Galactic and earlier
  ros__parameters:
    local_costmap_topic: local_costmap/costmap_raw
    local_footprint_topic: local_costmap/published_footprint
    global_costmap_topic: global_costmap/costmap_raw
    global_footprint_topic: global_costmap/published_footprint
    cycle_frequency: 10.0
    behavior_plugins: ["spin", "backup", "wait","send_sms"]  # Humble and newer
    recovery_plugins: ["spin", "backup", "wait","send_sms"]  # Galactic and earlier
    spin:
      plugin: "nav2_behaviors/Spin"
    backup:
      plugin: "nav2_behaviors/BackUp"
    wait:
      plugin: "nav2_behaviors/Wait"
    send_sms:
      plugin: "nav2_sms_behavior/SendSms"
    account_sid: ... # your sid
    auth_token: ... # your token
    from_number: ... # your number
    to_number: ... # the operations center number
    global_frame: odom
    robot_base_frame: base_link
    transform_timeout: 0.1
    use_sim_time: true
    simulate_ahead_time: 2.0
    max_rotational_vel: 1.0
    min_rotational_vel: 0.4
    rotational_acc_lim: 3.2

在上面的片段中,您可以观察到我们在``send_sms``的ROS 2动作服务器名称下添加了SMS行为。我们还告诉行为服务器``send_sms``的类型是``SendSms``,并为您的Twilio帐户提供了参数。

4- 运行行为插件

使用启用了Nav2的Turtlebot3模拟。如何进行此操作的详细说明请参见:ref:getting_started。下面是该操作的快捷命令:

$ ros2 launch nav2_bringup tb3_simulation_launch.py params_file:=/path/to/your_params_file.yaml

在新终端中运行:

$ ros2 action send_goal "send_sms" nav2_sms_behavior/action/SendSms "{message : Hello!! Navigation2 World }"