监视参数变化(C++)

**目标:**学习使用ParameterEventHandler类监视并响应参数变化。

教程级别: 中级

**时间:**20分钟

**最低平台要求:**Galactic

背景

通常节点需要对自己的参数或其他节点的参数变化做出响应。ParameterEventHandler类使得监听参数变化并响应变得容易。本教程将展示如何使用C++版本的ParameterEventHandler类来监视节点自身参数的变化以及其他节点的参数变化。

先决条件

在开始本教程之前,您应该先完成以下教程:

另外,您必须使用 ROS 2 的 Galactic 版本。

任务

在本教程中,您将创建一个新的包以包含一些示例代码,编写一些 C++ 代码来使用 ParameterEventHandler 类,并测试生成的代码。

1 创建一个包

首先,打开一个新的终端并 source your ROS 2 installation 以便 ros2 命令能够正常工作。

按照:ref:这些指示 创建名为``ros2_ws``的新工作空间。

请记住,包应该创建在 src 目录中,而不是工作空间的根目录。因此,进入 ros2_ws/src,然后在那里创建一个新的包:

ros2 pkg create --build-type ament_cmake cpp_parameter_event_handler --dependencies rclcpp

您的终端将返回一个消息,验证您的包 cpp_parameter_event_handler 及其所有必要的文件和文件夹的创建。

“--dependencies”参数将自动添加必要的依赖项行到“package.xml”和“CMakeLists.txt”中。

1.1 更新 package.xml

因为您在创建软件包时使用了``--dependencies``选项,所以您不需要手动将依赖项添加到``package.xml``或``CMakeLists.txt``中。不过,您仍需确保将描述、维护者电子邮件和姓名以及许可信息添加到``package.xml``中。

<description>C++ parameter events client tutorial</description>
<maintainer email="you@email.com">Your Name</maintainer>
<license>Apache License 2.0</license>

2 编写 C++ 节点

在``ros2_ws/src/cpp_parameter_event_handler/src``目录中创建一个名为``parameter_event_handler.cpp``的新文件,并将以下代码粘贴其中:

#include <memory>

#include "rclcpp/rclcpp.hpp"

class SampleNodeWithParameters : public rclcpp::Node
{
public:
  SampleNodeWithParameters()
  : Node("node_with_parameters")
  {
    this->declare_parameter("an_int_param", 0);

    // Create a parameter subscriber that can be used to monitor parameter changes
    // (for this node's parameters as well as other nodes' parameters)
    param_subscriber_ = std::make_shared<rclcpp::ParameterEventHandler>(this);

    // Set a callback for this node's integer parameter, "an_int_param"
    auto cb = [this](const rclcpp::Parameter & p) {
        RCLCPP_INFO(
          this->get_logger(), "cb: Received an update to parameter \"%s\" of type %s: \"%ld\"",
          p.get_name().c_str(),
          p.get_type_name().c_str(),
          p.as_int());
      };
    cb_handle_ = param_subscriber_->add_parameter_callback("an_int_param", cb);
  }

private:
  std::shared_ptr<rclcpp::ParameterEventHandler> param_subscriber_;
  std::shared_ptr<rclcpp::ParameterCallbackHandle> cb_handle_;
};

int main(int argc, char ** argv)
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<SampleNodeWithParameters>());
  rclcpp::shutdown();

  return 0;
}

2.1 检查代码

第一条语句``#include <memory>``是为了让代码可以利用std::make_shared模板。接下来的``#include "rclcpp/rclcpp.hpp"``是为了让代码可以引用rclcpp接口提供的各种功能,包括ParameterEventHandler类。

在类声明之后,代码定义了一个名为``SampleNodeWithParameters``的类。该类的构造函数声明了一个整型参数``an_int_param``,默认值为0。接下来,代码创建了一个将用于监视参数变化的``ParameterEventHandler``。最后,代码创建了一个lambda函数,并将其设置为在``an_int_param``更新时调用的回调函数。

注解

非常重要的一点是要保存``add_parameter_callback``返回的句柄;否则,回调函数将无法正确注册。

SampleNodeWithParameters()
: Node("node_with_parameters")
{
  this->declare_parameter("an_int_param", 0);

  // Create a parameter subscriber that can be used to monitor parameter changes
  // (for this node's parameters as well as other nodes' parameters)
  param_subscriber_ = std::make_shared<rclcpp::ParameterEventHandler>(this);

  // Set a callback for this node's integer parameter, "an_int_param"
  auto cb = [this](const rclcpp::Parameter & p) {
      RCLCPP_INFO(
        this->get_logger(), "cb: Received an update to parameter \"%s\" of type %s: \"%ld\"",
        p.get_name().c_str(),
        p.get_type_name().c_str(),
        p.as_int());
    };
  cb_handle_ = param_subscriber_->add_parameter_callback("an_int_param", cb);
}

在``SampleNodeWithParameters``之后是一个典型的``main``函数,它初始化ROS,使示例节点能够发送和接收消息,然后在用户在控制台输入^C后关闭。

int main(int argc, char ** argv)
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<SampleNodeWithParameters>());
  rclcpp::shutdown();

  return 0;
}

2.2 添加可执行文件

要构建此代码,首先打开``CMakeLists.txt``文件,并在依赖项``find_package(rclcpp REQUIRED)``下添加以下代码行

add_executable(parameter_event_handler src/parameter_event_handler.cpp)
ament_target_dependencies(parameter_event_handler rclcpp)

install(TARGETS
  parameter_event_handler
  DESTINATION lib/${PROJECT_NAME}
)

3. 构建和运行

在构建之前,最好在工作空间的根目录(ros2_ws)中运行``rosdep``来检查是否缺少依赖项:

rosdep install -i --from-path src --rosdistro $ROS_DISTRO -y

返回到您的工作空间的根目录 ros2_ws,并构建您的新包:

colcon build --packages-select cpp_parameter_event_handler

打开一个新的终端,导航到 ros2_ws,并加载设置文件:

. install/setup.bash

现在运行节点:

ros2 run cpp_parameter_event_handler parameter_event_handler

该节点现已激活并具有一个参数,每当更新该参数时,它将打印一条消息。要进行测试,打开另一个终端并像以前一样设置ROS环境(. install/setup.bash),然后执行以下命令:

ros2 param set node_with_parameters an_int_param 43

运行节点的终端将显示类似以下内容的消息:

[INFO] [1606950498.422461764] [node_with_parameters]: cb: Received an update to parameter "an_int_param" of type integer: "43"

我们之前在节点中设置的回调函数已被调用,并显示了新的更新值。现在,您可以使用终端中的``^C``终止运行的``parameter_event_handler``示例。

3.1 监视另一个节点的参数变化

您还可以使用``ParameterEventHandler``来监视另一个节点的参数变化。让我们更新``SampleNodeWithParameters``类,以便还监视另一个节点的参数更改。我们将使用``parameter_blackboard``演示应用程序来托管一个双精度参数,并监视其更新。

首先在构造函数中添加以下代码,放在现有代码之后:

// Now, add a callback to monitor any changes to the remote node's parameter. In this
// case, we supply the remote node name.
auto cb2 = [this](const rclcpp::Parameter & p) {
    RCLCPP_INFO(
      this->get_logger(), "cb2: Received an update to parameter \"%s\" of type: %s: \"%.02lf\"",
      p.get_name().c_str(),
      p.get_type_name().c_str(),
      p.as_double());
  };
auto remote_node_name = std::string("parameter_blackboard");
auto remote_param_name = std::string("a_double_param");
cb_handle2_ = param_subscriber_->add_parameter_callback(remote_param_name, cb2, remote_node_name);

然后添加另一个成员变量,cb_handle2,用于额外的回调句柄:

private:
  std::shared_ptr<rclcpp::ParameterEventHandler> param_subscriber_;
  std::shared_ptr<rclcpp::ParameterCallbackHandle> cb_handle_;
  std::shared_ptr<rclcpp::ParameterCallbackHandle> cb_handle2_;  // Add this
};

在终端中,返回到工作空间根目录``ros2_ws``,并像以前一样构建更新的软件包:

colcon build --packages-select cpp_parameter_event_handler

然后加载设置文件:

. install/setup.bash

现在,为了测试远程参数的监视功能,首先运行新构建的 parameter_event_handler 代码:

ros2 run cpp_parameter_event_handler parameter_event_handler

接下来,在另一个已初始化 ROS 的终端中,运行 parameter_blackboard 演示应用程序,如下所示:

ros2 run demo_nodes_cpp parameter_blackboard

最后,在第三个终端(已初始化ROS),让我们在parameter_blackboard节点上设置一个参数:

ros2 param set parameter_blackboard a_double_param 3.45

执行此命令后,你应该在parameter_event_handler窗口中看到输出,表示在参数更新时调用了回调函数:

[INFO] [1606952588.237531933] [node_with_parameters]: cb2: Received an update to parameter "a_double_param" of type: double: "3.45"

总结

你创建了一个带有参数的节点,并使用ParameterEventHandler类设置了一个回调函数来监控该参数的变化。你还使用相同的类监控了远程节点的变化。ParameterEventHandler是一种方便的方法,用于监控参数的变化,以便你可以对更新的值做出响应。