监控参数变化 (C++)

目标: 学习使用 ParameterEventHandler 类来监控和响应参数更改。

教程级别: 中级

时间: 20 分钟

背景

通常,节点需要响应其自身参数或其他节点参数的更改。 ParameterEventHandler 类可以轻松监听参数更改,以便您的代码可以对其做出响应。 本教程将向您展示如何使用 C++ 版本的 ParameterEventHandler 类来监视节点自身参数的更改以及另一个节点参数的更改。

先决条件

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

任务

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

1 创建包

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

按照 these instructions 创建一个名为 ros2_ws 的新工作区。

回想一下,应该在 src 目录中创建包,而不是在工作区的根目录中创建包。 因此,导航到“ros2_ws/src”,然后在那里创建一个新包:


ros2 pkg create –build-type ament_cmake –license Apache-2.0 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-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”更新时调用的回调。

Note

保存“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)运行参数黑板演示应用程序,如下所示:

ros2 run demo_nodes_cpp parameter_blackboard

最后,从第三个终端(已初始化 ROS),让我们在 paramter_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 是一种监视参数更改的便捷方法,以便您可以响应更新的值。

相关内容

要了解如何将 ROS 1 参数文件适配到 ROS 2,请参阅 将 YAML 参数文件从 ROS 1 迁移到 ROS2 教程。