【ROS2概念】系列(十二)——ROS2中的参数param

目录

  • 一、ROS2参数概念
  • 二、命令行设置参数
    • 2.1 启动小海龟仿真器
    • 2.2 查看系统中的参数列表
    • 2.3 获取参数值
    • 2.4 设置参数值
    • 2.5 保存参数
    • 2.6 加载参数文件
  • 三、启动节点并加载参数
    • 3.1 以命令行方式加载参数文件
    • 3.2 以launch文件的形式
  • 四、动态参数配置(GUI)
    • 4.1 rqt动态参数配置界面
    • 4.2 节点内获取动态参数的代码
  • 五、编写可配置参数的节点
    • 5.1 C++代码
    • 5.2 python代码
  • 六、监控ROS2参数的动态变化
    • 6.1 示例代码
    • 6.2 代码解析

一、ROS2参数概念

ROS2的参数是由Service构建出来,因为ROS2 中没有ROS master,也就没有参数服务器。

ROS2不再有全局参数,每个参数都特定于一个节点,每个节点声明和管理自己的参数,这些参数在节点被杀死时被销毁。

当启动一个节点时,该节点会创建一些 ROS2 Service,通过这些Service从终端或其他节点与这个节点的参数进行交互,这个节点则通过参数回调服务来修改自身的参数

二、命令行设置参数

以小海龟仿真器为例,看看里边有哪些参数。

2.1 启动小海龟仿真器

ros2 run turtlesim turtlesim_node
ros2 run turtlesim turtle_teleop_key

2.2 查看系统中的参数列表

来看看当前运行的系统中,有哪些参数:

ros2 param list

终端中可以看到,以每个节点名为命名空间,每个节点都有一些参数:

turtlesim节点中有三个rgb参数,可以用来设置海龟仿真器的背景颜色。

2.3 获取参数值

在以上列表中,如果我们想查看某个参数的值,就可以这样来操作:

ros2 param get

比如看下背景颜色中的g值:

ros2 param get /turtlesim background_g

可以看到如下反馈,是一个整型数:

2.4 设置参数值

除了查看参数值之外,还可以通过命令行设置某一个参数的值:

ros2 param set

比如修改仿真器背景色中的r值为150:

ros2 param set /turtlesim background_r 150

终端中会看到设置成功的日志:

仿真器的背景也很快变色了:

这种方式只能修改一次参数值,下次重新启动就失效了,如果要下次继续生效,就得保存参数了。

2.5 保存参数

我们可以使用dump命令来保存节点所有的参数到文件中:

ros2 param dump

比如保存turtlesim节点的参数:

ros2 param dump /turtlesim

终端中可以看到保存成功的提示:

很快就可以在你运行终端的路径下看到保存好的文件啦,打开之后的内容如下:

2.6 加载参数文件

保存好的参数文件可以在下次启动时加载使用:

ros2 run --ros-args --params-file

关掉已经在运行的海龟仿真器,重新启动来加载在启动海龟仿真器时,前边的命令不变,但是后边需要加上ros-args和--params-file配置:

ros2 run turtlesim turtlesim_node --ros-args --params-file ./turtlesim.yaml

海龟仿真器又启动啦,这回背景是不是变成了之前修改的颜色。 这就是ROS2中的参数,我们可以通过命令行get或set参数值,还可以利用文件保存和加载参数。

三、启动节点并加载参数

3.1 以命令行方式加载参数文件

让节点加载参数文件

ros2 run --ros-args --params-file

例如:

ros2 run turtlesim turtlesim_node --ros-args --params-file ./turtlesim.yaml

3.2 以launch文件的形式

tb3_param_dir = LaunchConfiguration(
    'tb3_param_dir',
    default=os.path.join(
        get_package_share_directory('turtlebot3_bringup'),
        'param',
        TURTLEBOT3_MODEL + '.yaml'))
        
Node(
    package='turtlebot3_node',
    executable='turtlebot3_ros',
    parameters=[tb3_param_dir],
    arguments=['-i', usb_port],
    output='screen')

四、动态参数配置(GUI)

4.1 rqt动态参数配置界面

动态参数配置主要通过rqt来实现。

rqt->Plugins->Configuration->Dynamic Reconfigure

修改了参数后会立即生效。具体的实现流程是,参数变化后产生参数事件,触发回调函数。在回调函数中将新的参数赋值给变量。

4.2 节点内获取动态参数的代码

以下为GUI动态参数配置对应执行的代码:

// Subscription for parameter change
rclcpp::AsyncParametersClient::SharedPtr parameters_client_;
rclcpp::Subscription::SharedPtr parameter_event_sub_;

    
// Setup callback for changes to parameters.
parameters_client_ = std::make_shared(
  node->get_node_base_interface(),
  node->get_node_topics_interface(),
  node->get_node_graph_interface(),
  node->get_node_services_interface());

//register callback function
parameter_event_sub_ = parameters_client_->on_parameter_event(std::bind(&TurtlesimController::on_parameter_event_callback, this, std::placeholders::_1));

//callback function
void TurtlesimController::on_parameter_event_callback(const rcl_interfaces::msg::ParameterEvent::SharedPtr event)
{
  std::lock_guard l(config_mutex_);
  
  for (auto & changed_parameter : event->changed_parameters) {
    const auto & type = changed_parameter.value.type;
    const auto & name = changed_parameter.name;
    const auto & value = changed_parameter.value;

    if (type == rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE) {
      // Trajectory
      if (name == "walk_distance") {
        walk_distance_ = value.double_value;
        RCLCPP_INFO(this->get_logger(), "update walk_distance: %.3f ", walk_distance_);
      }
    }
    else if(type == rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER)
    {
      if (name == "execute_frequency") {
        execute_frequency_ = value.integer_value;//不会改变定时器执行频率,仅作为演示用
        RCLCPP_INFO(this->get_logger(), "update execute_frequency: %d ", execute_frequency_);
      }
    }
    else if (type == rcl_interfaces::msg::ParameterType::PARAMETER_BOOL)
    {
      if (name == "print_execute_duration") {
        print_execute_duration_ = value.bool_value;
        RCLCPP_INFO(this->get_logger(), "update print_execute_duration: %d ",print_execute_duration_);
      }
    }
    else if (type == rcl_interfaces::msg::ParameterType::PARAMETER_STRING)
    {
      if (name == "show_str") {
        show_str_ = value.string_value;
        RCLCPP_INFO(this->get_logger(), "update show_str: %s ",show_str_.c_str());
      }
    }
  }
}

ROS2的参数时基于Client/Server架构,首先声明与rqt动态参数界面交互的Client,即parameters_client_指针,然后声明参数修改事件的指针parameter_event_sub_

rclcpp::AsyncParametersClient::SharedPtr parameters_client_;
rclcpp::Subscription::SharedPtr parameter_event_sub_;

接着为共享指针parameters_client_赋值,拿到节点资源base_interface、topics_interface、graph_interface、services_interface交互权限。

parameters_client_ = std::make_shared(
  node->get_node_base_interface(),
  node->get_node_topics_interface(),
  node->get_node_graph_interface(),
  node->get_node_services_interface());

然后通过parameters_client_指针,利用ROS2的on_parameter_event参数变化事件函数,为触发参数修改事件绑定对应的回调处理函数TurtlesimController::on_parameter_event_callback

parameter_event_sub_ = parameters_client_->on_parameter_event(std::bind(&TurtlesimController::on_parameter_event_callback, this, std::placeholders::_1));

最后定义回调处理函数TurtlesimController::on_parameter_event_callback

void TurtlesimController::on_parameter_event_callback(const rcl_interfaces::msg::ParameterEvent::SharedPtr event)
{
  ****
}

在回调处理函数中,获取到的有个技巧,通过event->changed_parameters即可获取变化的参数,而无须循环所有参数列表。

  for (auto & changed_parameter : event->changed_parameters) {
    const auto & type = changed_parameter.value.type;
    const auto & name = changed_parameter.name;
    const auto & value = changed_parameter.value;
    ***
}

五、编写可配置参数的节点

动态参数配置与此节所述参数配置不同,前者有图形化界面,后者是通过命令发布。

5.1 C++代码

#include 
#include 
#include 
#include 

using namespace std::chrono_literals;

class ParametersClass: public rclcpp::Node
{
  public:
    ParametersClass()
      : Node("parameter_node")
    {
      this->declare_parameter("my_parameter", "world");
      timer_ = this->create_wall_timer(1000ms, std::bind(&ParametersClass::respond, this));
    }
    void respond()
    {
      this->get_parameter("my_parameter", parameter_string_);
      RCLCPP_INFO(this->get_logger(), "Hello %s", parameter_string_.c_str());
    }
  private:
    std::string parameter_string_;
    rclcpp::TimerBase::SharedPtr timer_;
};

int main(int argc, char** argv)
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared());
  rclcpp::shutdown();
  return 0;
}

这段代码是ParametersClass类的构造函数,其中第一行就创建了一个ROS参数,参数名为my_parameter,参数值为“world”,数据类型是string。接下来的第二行创建了一个1s周期的定时器,触发respond函数。

ParametersClass()
: Node("parameter_node")
{
   this->declare_parameter("my_parameter", "world");
   timer_ = this->create_wall_timer(1000ms, std::bind(&ParametersClass::respond, this));
}

在respond函数中,第一行会查询“my_parameter”参数,并且保存在parameter_string_这个私有变量中,紧接着第二行就把查询到的参数值打印出来了。

void respond()
{
    this->get_parameter("my_parameter", parameter_string_);
    RCLCPP_INFO(this->get_logger(), "Hello %s", parameter_string_.c_str());
}

5.2 python代码

ROS2参数示例-创建、读取、修改参数,param_declare.py文件。

#!/usr/bin/env python3
# -*- coding: utf-8 -*-

import rclpy                                     # ROS2 Python接口库
from rclpy.node   import Node                    # ROS2 节点类

class ParameterNode(Node):
    def __init__(self, name):
        super().__init__(name)                                    # ROS2节点父类初始化
        self.timer = self.create_timer(2, self.timer_callback)    # 创建一个定时器(单位为秒的周期,定时执行的回调函数)
        self.declare_parameter('robot_name', 'mbot')              # 创建一个参数,并设置参数的默认值

    def timer_callback(self):                                      # 创建定时器周期执行的回调函数
        robot_name_param = self.get_parameter('robot_name').get_parameter_value().string_value   # 从ROS2系统中读取参数的值

        self.get_logger().info('Hello %s!' % robot_name_param)     # 输出日志信息,打印读取到的参数值

        new_name_param = rclpy.parameter.Parameter('robot_name', rclpy.Parameter.Type.STRING, 'mbot')    # 重新将参数值设置为指定值
        all_new_parameters = [new_name_param]
        self.set_parameters(all_new_parameters)                    # 将重新创建的参数列表发送给ROS2系统

def main(args=None):                                 # ROS2节点主入口main函数
    rclpy.init(args=args)                            # ROS2 Python接口初始化
    node = ParameterNode("param_declare")            # 创建ROS2节点对象并进行初始化
    rclpy.spin(node)                                 # 循环等待ROS2退出
    node.destroy_node()                              # 销毁节点对象
    rclpy.shutdown()                                 # 关闭ROS2 Python接口

ROS2节点创建了一个定时器,同时通过self.declare_parameter函数声明一个参数robot_name,并设置默认值为mbot,通过self.get_parameter函数获取最新的参数值,接着利用rclpy.parameter.Parameter函数设置单个参数为指定值,最后利用self.set_parameters函数通过参数列表一次设置多个参数(实际只有一个)。

完成代码的编写后需要设置功能包的编译选项,让系统知道Python程序的入口,打开功能包的setup.py文件,加入如下入口点的配置:

entry_points={
    'console_scripts': [
     'param_declare = learning_parameter.param_declare:main',
    ],
},

六、监控ROS2参数的动态变化

前述都是通过定时器定时查询参数值来发现参数是否发生变化,ROS2提供了参数的事件触发机制ParameterEventHandler, 当参数被改变后,可以通过回调函数的方式,动态发现参数修改结果。

注意:此功能目前只支持Galactic及以上的ROS2版本。

6.1 示例代码

#include 
#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(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 param_subscriber_;
  std::shared_ptr cb_handle_;
};

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

  return 0;
}

6.2 代码解析

ParameterEventHandler类,就是在rclcpp/rclcpp.hpp中定义的。

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(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类的构造函数中,声明了一个整型数参数an_int_param,参数值默认是0,然后创建了ParameterEventHandler实例,用于监控参数的变化。最后创建了一个lambda函数,并设置为参数变化时的回调函数。

参考:

[ROS2基础]参数和动作

古月居理解参数:https://www.guyuehome.com/10864
动态参数监控,https://www.guyuehome.com/35373

你可能感兴趣的:(【ROS2概念】系列(十二)——ROS2中的参数param)