Skip to content

第七章 参数通信

7.1 参数通信

在 ROS2 中参数被视为节点的设置,而参数通信机制是基于服务通信实现的。

① 打开一个小海龟模拟器窗口

Bash
ros2 run turtlesim turtlesim_node

image-20250301131313690

② 查看带有parameter的服务,这些是与参数相关的服务,提供参数的查询与设置

Bash
ros2 service list -t | grep parameter

image-20250303130210353

③ 查看参数列表,其中背景相关三个参数是显示声明的,其余是默认参数

Bash
ros2 param list

image-20250303130356817

④ 查看参数的具体描述

Bash
ros2 param describe /turtlesim background_r

image-20250303130657190

⑤ 获取当前节点的参数值

Bash
ros2 param get /turtlesim background_r

image-20250303130826125

⑥ 修改参数值

Text Only
ros2 param set /turtlesim background_r 255

image-20250303130945694

⑦ 将参数导出为yaml文件,以便修改多个参数

Bash
ros2 param dump /turtlesim > turtlesim_param.yaml

image-20250303131205907

直接修改yaml文件,然后下次运行时带上该文件

Bash
ros2 run turtlesim turtlesim_node --ros-args --params-file turtlesim_param.yaml

image-20250303131443595

7.2 Python参数服务

7.2.1 参数声明与设置

修改detect_service_py/detect_service_py/detect_service.py,使用参数声明:

Python
class FaceDetectService(Node):
    def __init__(self, name):
        super().__init__(name)
        # ... #
        """添加参数声明"""
        # 检测参数(未使用参数通信)
        # self.upsample_times = 1
        # self.model = "hog"
        # 声明参数
        self.declare_parameter("face_locations_upsample_times", 1)
        self.declare_parameter("face_locations_model", "hog")
        # 设置参数
        self.upsample_times = self.get_parameter("face_locations_upsample_times").value
        self.model = self.get_parameter("face_locations_model").value

重新编译运行节点以后,就可以查看参数已经识别:

Bash
ros2 param list

image-20250303150159980

可以在启动节点时使用参数,加上--ros-args -p

Bash
ros2 run detect_service_py face_detect_service --ros-args -p face_locations_upsample_times:=2

7.2.2 订阅参数更新

在命令行、其他节点修改过参数后,需要同时修改属性赋值。此时需要添加一个参数回调函数:

Python
from rcl_interfaces.msg import SetParametersResult

class FaceDetectService(Node):
    def __init__(self, name):
        super().__init__(name)
        # ... #
        # 添加参数回调函数
        self.add_on_set_parameters_callback(self.parameters_callback)

    def parameters_callback(self, parameters):
        for parameter in parameters:
            self.get_logger().info(f"参数{parameter.name}被设置为{parameter.value}")
            if parameter.name == "face_locations_upsample_times":
                self.upsample_times = self.get_parameter("face_locations_upsample_times").value
            elif parameter.name == "face_locations_model":
                self.model = self.get_parameter("face_locations_model").value
        return SetParametersResult(successful=True)

编译运行

Bash
colcon build --packages-select detect_service_py
source install/setup.bash
Bash
ros2 run detect_service_py face_detect_service --ros-args -p face_locations_upsample_times:=2

另一个终端,修改参数

Bash
ros2 param set /face_detect face_locations_upsample_times 1

修改结果

image-20250303153506891

7.2.3 修改其他节点的参数

修改其他节点的参数,需要用到服务通信发送请求,原因看下图,当我们运行服务端时,有很多关于参数的服务,其中我们就需要使用/face_detect/set_parameters服务设置参数。

image-20250303155951334

查看消息接口内容

Bash
ros2 interface show rcl_interfaces/srv/SetParameters

image-20250303160501788

修改detect_service_py/detect_service_py/detect_client.py

Python
# 导入设置参数的服务消息接口
from rcl_interfaces.srv import SetParameters
# 导入设置参数的话题消息接口
from rcl_interfaces.msg import Parameter, ParameterValue, SetParametersResult

class FaceDetectService(Node):
    def __init__(self, name):
        super().__init__(name)
        # ... #

    def call_set_parameter(self, parameters):
        # 1.创建客户端,并等待服务上线
        client = self.create_client(SetParameters, "/face_detect/set_parameters")
        while client.wait_for_service(timeout_sec=1) is False:
             self.get_logger().info("等待服务上线...")
        # 2.构造Request(由于消息接口复杂,故消息赋值单开一个函数完成)
        request = SetParameters.Request()
        request.parameters = parameters
        # 3.发送请求并等待服务端处理完成(异步获取结果)
        future = client.call_async(request)
        rclpy.spin_until_future_complete(self, future=future)
        response = future.result()
        return response

    def update_detect_parameter(self, times=1):
        # 1.创建一个参数对象
        param = Parameter()
        param.name = "face_locations_upsample_times"
        # 2.创建参数值对象
        param_value = ParameterValue()
        # 整数数据
        param_value.type = ParameterType.PARAMETER_INTEGER
        param_value.integer_value = times
        # 3.赋值参数对象
        param.value = param_value
        # 4.发送更新参数请求
        response = self.call_set_parameter([param])
        for result in response.results:
            if result.successful:
                self.get_logger().info(f"参数{param.name}被设置为{times}")     
            else:
                self.get_logger().error(f"参数设置错误{result.reason}")

def main(args=None):
    rclpy.init(args=args)
    node = FaceDetectClient("face_detect_client")
    node.update_detect_parameter(times=1)
    node.send_request()
    node.update_detect_parameter(times=2)
    node.send_request()
    rclpy.shutdown()                

编译运行

Bash
colcon build --packages-select detect_service_py
source install/setup.bash

打开服务端

Bash
ros2 run detect_service_py face_detect_service

打开客户端

Bash
ros2 run detect_service_py face_detect_client

运行结果

image-20250303163307819

7.3 C++参数服务

7.3.1 参数声明与设置

修改patrol_service_cpp/src/patrol_service.cpp,使用参数声明:

C++
class TurtleController : public rclcpp::Node
{
public:
    TurtleController() : Node("turtle_controller")
    {
        // 声明和设置参数
        this->declare_parameter("k", 1.0);
        this->declare_parameter("max_speed", 3);
        this->get_parameter("k", k_);
        this->get_parameter("max_speed", max_speed_);
        // ...
    }
};

重新编译运行节点以后,就可以查看参数已经识别:

image-20250303165611541

7.3.2 订阅参数更新

方法与Python保持一致,API名称有所不同。

C++
class TurtleController : public rclcpp::Node
{
public:
    TurtleController() : Node("turtle_controller")
    {
        // ...
        // 添加参数回调函数
        this->add_on_set_parameters_callback(
            [&] (const std::vector<rclcpp::Parameter> &params) -> SetParametersResult {
                for (const auto &param : params) {
                    // 打印日志
                    RCLCPP_INFO(this->get_logger(), "更新参数 %s 值为:%f",param.get_name().c_str(), param.as_double());
                    // 判断参数名称
                    if (param.get_name() == "k") {
                        k_ = param.as_double();
                    } else if (param.get_name() == "max_speed") {
                        max_speed_ = param.as_double();
                    }
                }
                // 返回结果
                auto result = SetParametersResult();
                result.successful = true;
                return result;
            }
        );
    }
};

编译运行

Bash
colcon build --packages-select patrol_service_cpp
source install/setup.bash

image-20250303174014806

7.3.3 修改其他节点的参数

修改patrol_service_cpp/src/patrol_client.cpp

C++
#include "rcl_interfaces/msg/parameter.hpp"
#include "rcl_interfaces/msg/parameter_value.hpp"
#include "rcl_interfaces/msg/parameter_type.hpp"
#include "rcl_interfaces/srv/set_parameters.hpp"

using SetParameters = rcl_interfaces::srv::SetParameters;
using Parameter = rcl_interfaces::msg::Parameter;
using ParameterValue = rcl_interfaces::msg::ParameterValue;

class TurtleController : public rclcpp::Node
{
public:
    /* 设置参数 */
    std::shared_ptr<SetParameters::Response> set_patrol_parameter(
        rcl_interfaces::msg::Parameter &parameters)
    {
        // 1.创建参数客户端,并等待服务上线
        auto param_client = this->create_client<SetParameters>("/turtle_controller/set_parameters");
        while(!param_client->wait_for_service(1s)) {
            if (!rclcpp::ok()) {
                RCLCPP_ERROR(this->get_logger(), "等待服务被打断。。。");
                return;
            } else {
                RCLCPP_INFO(this->get_logger(), "等待参数服务上线。。。");
            }
        }
        // 2.构造Request(由于消息接口复杂,故消息赋值单开一个函数完成)
        auto request = std::make_shared<SetParameters::Request>();
        request->parameters.push_back(parameters);
        // 3.发送请求并等待服务端处理完成(异步获取结果)
        auto future = param_client->async_send_request(request);
        rclcpp::spin_until_future_complete(this->get_node_base_interface(), future);
        auto response = future.get();
        return response;
    }

    void update_patrol_parameter(double k)
    {
        // 1.创建一个参数对象
        auto param = Parameter();
        param.name = "k";
        // 2.创建一个参数值对象
        auto param_value = ParameterValue();
        param_value.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE;
        param_value.double_value = k;
        // 3.赋值参数对象
        param.value = param_value;
        // 4.发送更新参数请求
        auto response = this->set_patrol_parameter(param);
        if (response == nullptr) {
            RCLCPP_WARN(this->get_logger(), "参数修改失败");
            return;
        } else {
            // 循环取出结果,判断successful
            for (auto result : response->results) {
                if (result.successful) {
                    RCLCPP_INFO(this->get_logger(), "参数k 已修改为:%f", k);
                } else {
                    RCLCPP_WARN(this->get_logger(), "参数k 失败原因:%s", result.reason.c_str());
                }
            }
        }
    }
};

编译运行

Bash
colcon build --packages-select patrol_service_cpp
source install/setup.bash

先打开小海龟,接着打开服务端,最后打开客户端,参数修改成功:

image-20250303193531008