【ROS2】参数 Parameter Hello World 代码示例讲解(C++版)
ROS2 取消了中心化的参数服务器,每个节点都可以是参数服务器。参数的生命周期与节点的生命周期绑定(尽管节点可以实现某种持久化机制,以便在重启后重新加载参数值)。ROS2的参数服务器实现了分布式,但通常机器人系统的配置仍然是集中管理的,接下来通过三个节点(参数管理节点、参数使用方的业务节点、参数修改方的业务节点)来介绍ROS2参数管理器的集中与分布式管理。参数的寻址方式包括节点名称、节点命名空间、

ROS 系列学习教程(总目录)
ROS2 系列学习教程(总目录)
ROS2 取消了中心化的参数服务器,每个节点都可以是参数服务器。参数用于在启动时(或运行时)配置节点,而无需更改代码。参数的生命周期与节点的生命周期绑定(尽管节点可以实现某种持久化机制,以便在重启后重新加载参数值)。
参数的寻址方式包括节点名称、节点命名空间、参数名称和参数命名空间。提供参数命名空间是可选的。
每个参数由键、值和描述符组成。键是字符串,值可以是以下类型之一:bool int64 float64 string byte[] bool[] int64[]或float64[] string[]。默认情况下,所有描述符都为空,但可以包含参数描述、值范围、类型信息和其他约束。
主要特点:
- 动态配置:运行时修改参数,无需重启节点
- 类型安全:支持多种数据类型
- 持久化:参数可以保存到文件中
- 分布式:每个节点都有自己的参数服务器
- 回调机制:参数变化时触发回调函数
ROS2的参数服务器实现了分布式,但通常机器人系统的配置仍然是集中管理的,接下来通过三个节点(参数管理节点、参数使用方的业务节点、参数修改方的业务节点)来介绍ROS2参数管理器的集中与分布式管理。
一、创建功能包
cd ros2_learning/src
ros2 pkg create --build-type ament_cmake hello_world_parameter_cpp
其中,
使用 --build-type 指定编译系统为 ament_cmake
hello_world_parameter_cpp:自定义功能包名称
生成的目录结构如下:
hello_world_parameter_cpp
├── CMakeLists.txt
├── include
│ └── hello_world_parameter_cpp
├── LICENSE
├── package.xml
└── src
二、编辑源文件
我们编写第一个节点(param_manager_node)。
在 hello_world_parameter_cpp/src 目录下新增 param_manager_node.cpp 文件,文件内容如下:
#include <string>
#include <vector>
#include <rclcpp/rclcpp.hpp>
class ParamManager : public rclcpp::Node
{
public:
ParamManager() : Node("param_manager_node")
{
// 1. 声明参数
this->declare_parameter("robot_speed", 1.0);
this->declare_parameter("robot_name", std::string("robot_alpha"));
this->declare_parameter("enable_debug", false);
// 声明数组参数
std::vector<double> default_waypoints = {1.0, 2.0, 3.0};
this->declare_parameter("waypoints", default_waypoints);
// 2. 添加参数回调
callback_handle_ = this->add_on_set_parameters_callback(
std::bind(&ParamManager::parametersCallback, this, std::placeholders::_1));
// 3. 创建定时器,定期打印参数值
timer_ = this->create_wall_timer(
std::chrono::seconds(2),
std::bind(&ParamManager::printParameters, this));
// 4. 初始打印参数
printParameters();
}
private:
void printParameters()
{
// 获取并打印所有参数
double robot_speed = this->get_parameter("robot_speed").as_double();
std::string robot_name = this->get_parameter("robot_name").as_string();
bool enable_debug = this->get_parameter("enable_debug").as_bool();
auto waypoints = this->get_parameter("waypoints").as_double_array();
RCLCPP_INFO(this->get_logger(), "=== Current Parameters ===");
RCLCPP_INFO(this->get_logger(), "Robot Speed: %.2f", robot_speed);
RCLCPP_INFO(this->get_logger(), "Robot Name: %s", robot_name.c_str());
RCLCPP_INFO(this->get_logger(), "Enable Debug: %s", enable_debug ? "true" : "false");
RCLCPP_INFO(this->get_logger(), "Waypoints: [%.1f, %.1f, %.1f]",
waypoints[0], waypoints[1], waypoints[2]);
RCLCPP_INFO(this->get_logger(), "==========================");
}
rcl_interfaces::msg::SetParametersResult parametersCallback(
const std::vector<rclcpp::Parameter> ¶meters)
{
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;
for (const auto ¶m : parameters)
{
RCLCPP_INFO(this->get_logger(),
"Parameter '%s' changed to: %s",
param.get_name().c_str(),
param.value_to_string().c_str());
// 参数验证
if (param.get_name() == "robot_speed")
{
double speed = param.as_double();
if (speed < 0.0 || speed > 10.0)
{
result.successful = false;
result.reason = "Robot speed must be between 0 and 10";
RCLCPP_WARN(this->get_logger(),
"Invalid speed value: %.2f", speed);
return result;
}
}
if (param.get_name() == "robot_name")
{
std::string name = param.as_string();
if (name.empty())
{
result.successful = false;
result.reason = "Robot name cannot be empty";
return result;
}
}
}
return result;
}
rclcpp::TimerBase::SharedPtr timer_;
OnSetParametersCallbackHandle::SharedPtr callback_handle_;
};
int main(int argc, char **argv)
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<ParamManager>());
rclcpp::shutdown();
return 0;
}
接下来是参数使用方的业务节点(business_node),
在 hello_world_service_cpp/src 目录下新增 business_node.cpp 文件,文件内容如下:
#include <chrono>
#include <rclcpp/rclcpp.hpp>
using namespace std::chrono_literals;
class BusinessNode : public rclcpp::Node
{
public:
BusinessNode() : Node("business_node")
{
// 启动一个同步客户端,连接服务端节点:param_server_node
sync_client_ = std::make_shared<rclcpp::SyncParametersClient>(this, "param_manager_node");
// 等待服务上线
while (!sync_client_->wait_for_service(std::chrono::seconds(1)))
{
RCLCPP_INFO(this->get_logger(), "Waiting for parameter service...");
}
// 获取远程参数
auto robot_name_param = sync_client_->get_parameter<std::string>("robot_name");
RCLCPP_INFO(this->get_logger(), "Got remote robot_name: %s", robot_name_param.c_str());
// 设置远程参数
sync_client_->set_parameters({rclcpp::Parameter("robot_name", "new_robot_from_client")});
RCLCPP_INFO(this->get_logger(), "Set remote parameter robot_name to 'new_robot_from_client'");
// 验证设置是否成功
auto updated_name = sync_client_->get_parameter<std::string>("robot_name");
RCLCPP_INFO(this->get_logger(), "Verified updated robot_name: %s", updated_name.c_str());
// 订阅参数事件,监听参数变化
auto event_cb = [this](const rcl_interfaces::msg::ParameterEvent & event)
{
// 过滤只关注 param_manager_node 的参数事件
// if (event.node != "param_manager_node")
// {
// return;
// }
// 遍历所有发生变化的参数
for (const auto &p : event.changed_parameters)
{
rclcpp::Parameter param;
try
{
param = rclcpp::Parameter::from_parameter_msg(p);
RCLCPP_INFO(this->get_logger(), "[%s] '%s' convert to: %s",
event.node.c_str(), p.name.c_str(), param.value_to_string().c_str());
}
catch (const std::exception &e)
{
RCLCPP_ERROR(this->get_logger(), "Error converting parameter '%s': %s", p.name.c_str(), e.what());
}
}
};
param_subscriber_ = std::make_shared<rclcpp::ParameterEventHandler>(this);
event_cb_handle_ = param_subscriber_->add_parameter_event_callback(event_cb);
}
private:
std::shared_ptr<rclcpp::SyncParametersClient> sync_client_;
std::shared_ptr<rclcpp::ParameterEventHandler> param_subscriber_;
std::shared_ptr<rclcpp::ParameterEventCallbackHandle> event_cb_handle_;
};
int main(int argc, char **argv)
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<BusinessNode>());
rclcpp::shutdown();
return 0;
}
然后是参数修改方的业务节点(dynamic_param_modifier),
在 hello_world_service_cpp/src 目录下新增 dynamic_param_modifier.cpp 文件,文件内容如下:
#include <rclcpp/rclcpp.hpp>
#include <thread>
class DynamicParamModifier : public rclcpp::Node
{
public:
DynamicParamModifier() : Node("dynamic_param_modifier"), counter_(0)
{
// 创建参数客户端
param_client_ = std::make_shared<rclcpp::AsyncParametersClient>(this, "param_manager_node");
// 等待参数服务器可用
while (!param_client_->wait_for_service(std::chrono::seconds(1)))
{
RCLCPP_INFO(this->get_logger(), "Parameter service not available, waiting...");
}
// 创建定时器,定期修改参数
timer_ = this->create_wall_timer(
std::chrono::seconds(3),
std::bind(&DynamicParamModifier::modifyParameters, this));
}
private:
void modifyParameters()
{
counter_++;
// 动态修改参数
double new_speed = 1.0 + (counter_ % 5) * 0.5;
std::string new_name = "robot_" + std::to_string(counter_);
RCLCPP_INFO(this->get_logger(),
"Modifying parameters: speed=%.2f, name=%s",
new_speed, new_name.c_str());
// 异步设置参数
auto results_future = param_client_->set_parameters({rclcpp::Parameter("robot_speed", new_speed),
rclcpp::Parameter("robot_name", new_name)});
// 在后台线程等待结果,避免在回调中阻塞或重复将节点添加到执行器
auto node_shared = this->shared_from_this();
std::thread([node_shared, results_future]() mutable
{
if (results_future.wait_for(std::chrono::seconds(5)) == std::future_status::ready)
{
auto results = results_future.get();
for (const auto &result : results)
{
if (!result.successful)
{
RCLCPP_ERROR(node_shared->get_logger(), "Failed to set parameter: %s", result.reason.c_str());
}
}
}
else
{
RCLCPP_ERROR(node_shared->get_logger(), "Setting parameters timed out");
}
}).detach();
}
rclcpp::AsyncParametersClient::SharedPtr param_client_;
rclcpp::TimerBase::SharedPtr timer_;
int counter_;
};
int main(int argc, char **argv)
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<DynamicParamModifier>());
rclcpp::shutdown();
return 0;
}
三、编辑编译配置文件CMakeList.txt
默认生成的 CMakeList.txt 文件内容如下:
由于新增了三个节点,所以要配置该文件的编译规则。
找到ros2_learning/src/hello_world_parameter_cpp/CMakeLists.txt,修改如下:
修改说明如下:
find_package(rclcpp REQUIRED)
# 指定源文件,生成可执行文件
add_executable(parameter_manager src/parameter_manager.cpp)
# 指定可执行文件的依赖项
ament_target_dependencies(parameter_manager rclcpp)
add_executable(business_node src/business_node.cpp)
ament_target_dependencies(business_node rclcpp)
add_executable(single_param_node src/single_param_node.cpp)
ament_target_dependencies(single_param_node rclcpp)
add_executable(dynamic_param_modifier src/dynamic_param_modifier.cpp)
ament_target_dependencies(dynamic_param_modifier rclcpp)
# 定义安装规则,指定可执行文件的安装目录
install(TARGETS
parameter_manager
business_node
single_param_node
dynamic_param_modifier
DESTINATION lib/${PROJECT_NAME}
)
四、编译工程
进入到工作空间 ros2_learning 目录,执行如下指令编译该工程:
colcon build
五、运行节点
ROS2 提供了 run 命令,可以根据包名和节点名,在任何目录执行。
但需要先设置环境变量,即让系统可以找到节点,进入到工作空间目录,执行如下指令:
source install/setup.bash
执行如下命令分别启动三个节点:
ros2 run hello_world_parameter_cpp parameter_manager
ros2 run hello_world_parameter_cpp business_node
ros2 run hello_world_parameter_cpp dynamic_param_modifier
启动节点后,打印如下:

openEuler 是由开放原子开源基金会孵化的全场景开源操作系统项目,面向数字基础设施四大核心场景(服务器、云计算、边缘计算、嵌入式),全面支持 ARM、x86、RISC-V、loongArch、PowerPC、SW-64 等多样性计算架构
更多推荐


所有评论(0)