Robot Operating System——初探动态配置Parameters

当我们程序写完后,如果需要修改程序中的某个配置,可以通过三种方案进行:

  • 通过文件。修改文件内容,并让程序动态加载这个文件,进而动态修改配置。
  • 通过网路。可以通过网络接口,让程序暴露一些接口用于修改其内部配置。
  • 通过进程间通信。对于在一台机器上的进程,可以通过进程间通信,通知程序修改配置。

而在ROS 2中,它提供了一种叫做Parameters的技术,辅助我们快速修改配置。

需要注意的是,在ROS 2中,配置是和Node相关的,即Parameter从属于Node。

我们通过demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp和demo_nodes_cpp/src/parameters/set_and_get_parameters_async.cpp的例子来讲解如何在外部设置、获取一个Node上的Parameters。

同步模式

我们在一个叫set_and_get_parameters的Node中做相关实验(demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp)。这样我们就可以直接使用继承于Node的方法来操作。

需要注意的是,Node自身也是一个设置/获取Parameters值的服务端。后面我们会看到如何使用客户端来向这个服务端来设置和查询Parameters的值。

class SetAndGetParameters : public rclcpp::Node
{
public:
  DEMO_NODES_CPP_PUBLIC
  explicit SetAndGetParameters(const rclcpp::NodeOptions & options)
  : Node("set_and_get_parameters", options)
  {
    setvbuf(stdout, NULL, _IONBF, BUFSIZ);

Node内使用declare_parameter方法声明Parameters

Node的declare_parameter方法用于设置一些parameter的Key和Value。

    this->declare_parameter("foo", 0);
    this->declare_parameter("bar", "");
    this->declare_parameter("baz", 0.);
    this->declare_parameter("foobar", false);
    this->declare_parameter("foobarbaz", std::vector<bool>{});
    this->declare_parameter("toto", std::vector<uint8_t>{});

创建Parameter同步访问客户端

构建rclcpp::SyncParametersClient时,我们传入的this指针就是即将创建的客户端要访问的Node节点。

    auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(this);
    while (!parameters_client->wait_for_service(1s)) {
      if (!rclcpp::ok()) {
        RCLCPP_ERROR(this->get_logger(), "Interrupted while waiting for the service. Exiting.");
        rclcpp::shutdown();
      }
      RCLCPP_INFO(this->get_logger(), "service not available, waiting again...");
    }

SyncParametersClient有三个参数。如果只指定了Node节点,说明这个节点是在我们程序内部创建的。这样就不需要跨网络,而是可以直接启动一个线程来访问,形成异步请求。

  template<typename NodeT>
  explicit SyncParametersClient(
    std::shared_ptr<NodeT> node,
    const std::string & remote_node_name = "",
    const rclcpp::QoS & qos_profile = rclcpp::ParametersQoS())
  : SyncParametersClient(
      std::make_shared<rclcpp::executors::SingleThreadedExecutor>(),
      node,
      remote_node_name,
      qos_profile)
  {}

跨Node修改Parameters

SyncParametersClient的set_parameters接收一个rclcpp::Parameter组成的vector,返回表达操作结果的std::vector<rcl_interfaces::msg::SetParametersResult>。我们可以遍历这个返回结果,查看哪个设置失败了。

    // Set several different types of parameters.
    auto set_parameters_results = parameters_client->set_parameters(
      {
        rclcpp::Parameter("foo", 2),
        rclcpp::Parameter("bar", "hello"),
        rclcpp::Parameter("baz", 1.45),
        rclcpp::Parameter("foobar", true),
        rclcpp::Parameter("foobarbaz", std::vector<bool>({true, false})),
        rclcpp::Parameter("toto", std::vector<uint8_t>({0xff, 0x7f})),
      });
    // Check to see if they were set.
    for (auto & result : set_parameters_results) {
      if (!result.successful) {
        RCLCPP_ERROR(this->get_logger(), "Failed to set parameter: %s", result.reason.c_str());
      }
    }

跨Node查询Parameters

SyncParametersClient的get_parameters方法也接收一个由Key做成的vector。我们可以通过它来查询到该客户端连接的Node中,这些Key对应的Value。

    std::stringstream ss;
    // Get a few of the parameters just set.
    for (
      auto & parameter : parameters_client->get_parameters(
        {"foo", "baz", "foobarbaz", "toto"}))
    {
      ss << "\nParameter name: " << parameter.get_name();
      ss << "\nParameter value (" << parameter.get_type_name() << "): " <<
        parameter.value_to_string();
    }
    RCLCPP_INFO(this->get_logger(), "%s", ss.str().c_str());

完整代码

// Copyright 2015 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <chrono>
#include <memory>
#include <sstream>
#include <vector>

#include "rclcpp/rclcpp.hpp"
#include "rclcpp_components/register_node_macro.hpp"

#include "demo_nodes_cpp/visibility_control.h"

using namespace std::chrono_literals;

namespace demo_nodes_cpp
{

class SetAndGetParameters : public rclcpp::Node
{
public:
  DEMO_NODES_CPP_PUBLIC
  explicit SetAndGetParameters(const rclcpp::NodeOptions & options)
  : Node("set_and_get_parameters", options)
  {
    setvbuf(stdout, NULL, _IONBF, BUFSIZ);
    this->declare_parameter("foo", 0);
    this->declare_parameter("bar", "");
    this->declare_parameter("baz", 0.);
    this->declare_parameter("foobar", false);
    this->declare_parameter("foobarbaz", std::vector<bool>{});
    this->declare_parameter("toto", std::vector<uint8_t>{});

    auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(this);
    while (!parameters_client->wait_for_service(1s)) {
      if (!rclcpp::ok()) {
        RCLCPP_ERROR(this->get_logger(), "Interrupted while waiting for the service. Exiting.");
        rclcpp::shutdown();
      }
      RCLCPP_INFO(this->get_logger(), "service not available, waiting again...");
    }

    // Set several different types of parameters.
    auto set_parameters_results = parameters_client->set_parameters(
      {
        rclcpp::Parameter("foo", 2),
        rclcpp::Parameter("bar", "hello"),
        rclcpp::Parameter("baz", 1.45),
        rclcpp::Parameter("foobar", true),
        rclcpp::Parameter("foobarbaz", std::vector<bool>({true, false})),
        rclcpp::Parameter("toto", std::vector<uint8_t>({0xff, 0x7f})),
      });
    // Check to see if they were set.
    for (auto & result : set_parameters_results) {
      if (!result.successful) {
        RCLCPP_ERROR(this->get_logger(), "Failed to set parameter: %s", result.reason.c_str());
      }
    }

    std::stringstream ss;
    // Get a few of the parameters just set.
    for (
      auto & parameter : parameters_client->get_parameters(
        {"foo", "baz", "foobarbaz", "toto"}))
    {
      ss << "\nParameter name: " << parameter.get_name();
      ss << "\nParameter value (" << parameter.get_type_name() << "): " <<
        parameter.value_to_string();
    }
    RCLCPP_INFO(this->get_logger(), "%s", ss.str().c_str());

    rclcpp::shutdown();
  }
};

}  // namespace demo_nodes_cpp

RCLCPP_COMPONENTS_REGISTER_NODE(demo_nodes_cpp::SetAndGetParameters)

运行结果

./build/demo_nodes_cpp/set_and_get_parameters

在这里插入图片描述
可以看到查询到的值都是修改后的值。

异步模式

我们参考demo_nodes_cpp/src/parameters/set_and_get_parameters_async.cpp的例子,看看异步设置和查询Parameters是如何做到的。

创建Node,设置Parameters

这次我们不在Node中执行逻辑,而是在Main函数中。这样我们就需要创建一个Node,然后给这个Node声明一批Parameters。

int main(int argc, char ** argv)
{
  // Force flush of the stdout buffer.
  setvbuf(stdout, NULL, _IONBF, BUFSIZ);

  rclcpp::init(argc, argv);

  auto node = rclcpp::Node::make_shared("set_and_get_parameters_async");

  // Declare parameters that may be set on this node
  node->declare_parameter("foo", 0);
  node->declare_parameter("bar", "");
  node->declare_parameter("baz", 0.);
  node->declare_parameter("foobar", false);
  node->declare_parameter("foobarbaz", std::vector<bool>{});
  node->declare_parameter("toto", std::vector<uint8_t>{});

创建Parameter异步访问客户端

这次我们创建的对象是rclcpp::AsyncParametersClient,它要操作的Node就是上面我们创建的"set_and_get_parameters_async"。

  auto parameters_client = std::make_shared<rclcpp::AsyncParametersClient>(node);
  while (!parameters_client->wait_for_service(1s)) {
    if (!rclcpp::ok()) {
      RCLCPP_ERROR(node->get_logger(), "Interrupted while waiting for the service. Exiting.");
      return 0;
    }
    RCLCPP_INFO(node->get_logger(), "service not available, waiting again...");
  }

异步设置,同步等待

由于这次是异步设置Parameters,所以我们需要等待set_parameters返回的结果。直到rclcpp::spin_until_future_complete完成了针对上述Node的等待,再遍历这个结构体,查询是不是每个设置都是成功的。

  // Set several different types of parameters.
  auto results = parameters_client->set_parameters(
  {
    rclcpp::Parameter("foo", 2),
    rclcpp::Parameter("bar", "hello"),
    rclcpp::Parameter("baz", 1.45),
    rclcpp::Parameter("foobar", true),
    rclcpp::Parameter("foobarbaz", std::vector<bool>({true, false})),
    rclcpp::Parameter("toto", std::vector<uint8_t>({0xff, 0x7f})),
  });
  // Wait for the results.
  if (rclcpp::spin_until_future_complete(node, results) !=
    rclcpp::FutureReturnCode::SUCCESS)
  {
    RCLCPP_ERROR(node->get_logger(), "set_parameters service call failed. Exiting tutorial.");
    return -1;
  }
  // Check to see if they were set.
  for (auto & result : results.get()) {
    if (!result.successful) {
      RCLCPP_ERROR(node->get_logger(), "Failed to set parameter: %s", result.reason.c_str());
    }
  }

异步查询,同步等待

AsyncParametersClient的get_parameters也是异步请求,返回的是std::vector<rclcpp::Parameter>。我们还是需要使用rclcpp::spin_until_future_complete来等到Node完成此次查询请求。等到查询完成才可以遍历访问查询到的数据。

  auto parameters = parameters_client->get_parameters({"foo", "baz", "foobarbaz", "toto"});
  if (rclcpp::spin_until_future_complete(node, parameters) !=
    rclcpp::FutureReturnCode::SUCCESS)
  {
    RCLCPP_ERROR(node->get_logger(), "get_parameters service call failed. Exiting tutorial.");
    return -1;
  }
  std::stringstream ss;
  for (auto & parameter : parameters.get()) {
    ss << "\nParameter name: " << parameter.get_name();
    ss << "\nParameter value (" << parameter.get_type_name() << "): " <<
      parameter.value_to_string();
  }
  RCLCPP_INFO(node->get_logger(), "%s", ss.str().c_str());

完整代码

// Copyright 2015 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <chrono>
#include <memory>
#include <sstream>
#include <vector>

#include "rclcpp/rclcpp.hpp"

using namespace std::chrono_literals;

int main(int argc, char ** argv)
{
  // Force flush of the stdout buffer.
  setvbuf(stdout, NULL, _IONBF, BUFSIZ);

  rclcpp::init(argc, argv);

  auto node = rclcpp::Node::make_shared("set_and_get_parameters_async");

  // Declare parameters that may be set on this node
  node->declare_parameter("foo", 0);
  node->declare_parameter("bar", "");
  node->declare_parameter("baz", 0.);
  node->declare_parameter("foobar", false);
  node->declare_parameter("foobarbaz", std::vector<bool>{});
  node->declare_parameter("toto", std::vector<uint8_t>{});

  auto parameters_client = std::make_shared<rclcpp::AsyncParametersClient>(node);
  while (!parameters_client->wait_for_service(1s)) {
    if (!rclcpp::ok()) {
      RCLCPP_ERROR(node->get_logger(), "Interrupted while waiting for the service. Exiting.");
      return 0;
    }
    RCLCPP_INFO(node->get_logger(), "service not available, waiting again...");
  }

  // Set several different types of parameters.
  auto results = parameters_client->set_parameters(
  {
    rclcpp::Parameter("foo", 2),
    rclcpp::Parameter("bar", "hello"),
    rclcpp::Parameter("baz", 1.45),
    rclcpp::Parameter("foobar", true),
    rclcpp::Parameter("foobarbaz", std::vector<bool>({true, false})),
    rclcpp::Parameter("toto", std::vector<uint8_t>({0xff, 0x7f})),
  });
  // Wait for the results.
  if (rclcpp::spin_until_future_complete(node, results) !=
    rclcpp::FutureReturnCode::SUCCESS)
  {
    RCLCPP_ERROR(node->get_logger(), "set_parameters service call failed. Exiting tutorial.");
    return -1;
  }
  // Check to see if they were set.
  for (auto & result : results.get()) {
    if (!result.successful) {
      RCLCPP_ERROR(node->get_logger(), "Failed to set parameter: %s", result.reason.c_str());
    }
  }

  // Get a few of the parameters just set.
  auto parameters = parameters_client->get_parameters({"foo", "baz", "foobarbaz", "toto"});
  if (rclcpp::spin_until_future_complete(node, parameters) !=
    rclcpp::FutureReturnCode::SUCCESS)
  {
    RCLCPP_ERROR(node->get_logger(), "get_parameters service call failed. Exiting tutorial.");
    return -1;
  }
  std::stringstream ss;
  for (auto & parameter : parameters.get()) {
    ss << "\nParameter name: " << parameter.get_name();
    ss << "\nParameter value (" << parameter.get_type_name() << "): " <<
      parameter.value_to_string();
  }
  RCLCPP_INFO(node->get_logger(), "%s", ss.str().c_str());

  rclcpp::shutdown();

  return 0;
}

总结

本文的两个例子,分别使用SyncParametersClient和AsyncParametersClient从Node外部设置和查询Node的Parameters。实际我们在Node内部可以通过Node类中的set_parameter方法操作本Node的Parameters。
在这里插入图片描述

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

breaksoftware

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值