ROS动态参数 - dynamic reconfigure 动态配置参数
一、普通参数和动态参数的对比
什么是动态参数?
一种可以在运行时更新参数而无需重启节点的参数!
接下来我们与普通的参数进行对比:
1. 修改时机和灵活性
对于静态参数:
仅能在节点启动时通过launch文件或命令行设置,一旦节点运行,参数值无法动态修改,必须重启节点才能生效!例如,传感器的物理参数(如摄像头焦距)通常作为静态参数配置;
对于静态参数:
允许在节点运行过程中实时调整,无需重启;
例如机器人标定:比如当前我们需要标定机器人的线速度或者角速度(线速度和角速度都是和轮胎的半径、轮间距相关的),此时可能每一辆机器人的轮子之间的参数都会有一点误差,不是那么绝对相等的,所以有时候为了获取更准确的里程计数据(与车辆的速度有关),所以我们会经常的调试轮胎的半径和轮间距,此时就可以通过动态参数进行调整!
导航期间调整动态参数:例如当我们设置全局代价地图的参数的配置的时候:
膨胀半径的值可能不符合我们设置的要求,如果我们将这个值设置到参数服务器当中,那么此时更改值需要重新启动节点,比较麻烦!
如果我们想要更改动态参数,可以通过rqt进行更改:
rqt
此时可以通过动态配置,选择glbal_costmap来对代价值进行设置,例如下面所示,可以看到全局地图的代价值发生改变:
2. 实现机制与通信方式
对于静态参数:
基于 ROS 参数服务器(Parameter Server),参数存储在全局空间,通过rosparam命令或ros::param接口访问。修改参数需调用rosparam set命令,但节点不会自动感知变化,需主动查询
对于动态参数:
通过dynamic_reconfigure库实现,采用 C/S 架构:
- 服务端:节点需集成动态参数服务器,定义参数类型、范围和回调函数;
- 客户端:通过服务调用(如/node_name/set_parameters)或可视化工具发送参数修改请求,服务端通过回调函数更新参数并触发逻辑调整;
3. 生命周期与作用域
对于静态参数:
全局参数,生命周期与roscore绑定,节点关闭后参数仍存在,需手动删除或随roscore终止而销毁;
对于动态参数
本地参数,生命周期与节点绑定,节点关闭后参数自动销毁。这种设计增强了节点的封装性和独立性;
接下来我们实现一个简单的动态参数的案例,方便大家更好的理解;
二、动态参数案例实现
1. 编写客户端
编写.cfg文件
cfg文件其实也就是一个python文件,用于生成参数修改的客户端(GUI),示例代码如下所示:
#! /usr/bin/env python
# 1.导包
from dynamic_reconfigure.parameter_generator_catkin import *
PACKAGE = "dynamic_recofig"
# 2.创建生成器
gen = ParameterGenerator()# 3.向生成器添加若干参数
#add(name, paramtype, level, description, default=None, min=None, max=None, edit_method="")
gen.add("int_param",int_t,0,"整型参数",50,0,100)
gen.add("double_param",double_t,0,"浮点参数",1.57,0,3.14)
gen.add("string_param",str_t,0,"字符串参数","hello world ")
gen.add("bool_param",bool_t,0,"bool参数",True)many_enum = gen.enum([gen.const("small",int_t,0,"a small size"),gen.const("mediun",int_t,1,"a medium size"),gen.const("big",int_t,2,"a big size")],"a car size set")gen.add("list_param",int_t,0,"列表参数",0,0,2, edit_method=many_enum)# 4.生成中间文件并退出
exit(gen.generate(PACKAGE,"dr_node","mycar"))
上面的代码逻辑大部分包括四步:导包、创建参数生成器、向参数生成器添加参数、配置节点并退出;
这里我们讲解一下向生成器中添加参数这个add函数:
add(name, paramtype, level, description, default=None, min=None, max=None, edit_method="")
- name:这里为我们自定义的参数名;
- paramtype: 也就是参数类型,这里封装的都是_t的,例如int_t;
- level: 掩码,一般用于在回调函数中,标记参数是否被修改过,一般直接传入0即可;
- description: 对这个参数进行描述;
- default:给这个参数设置的默认值;
- min和max:分别为参数的极值;
- edit_method:用于设置特殊的参数;
这里我们需要注意一下上面list类型的设置:
many_enum = gen.enum([gen.const("small",int_t,0,"a small size"),gen.const("mediun",int_t,1,"a medium size"),gen.const("big",int_t,2,"a big size")],"a car size set")gen.add("list_param",int_t,0,"列表参数",0,0,2, edit_method=many_enum)
首先,这里列表的类型取决于列表中的数据的类型,这里我们设置的列表的类型是int_t;
然后定义了一个方法,用来设置列表,其中,列举了三种枚举类型,最后在对这个方法进行描述;
配置节点函数:
generate(pkgname, nodename, name)
- pkgname: 对应我们的功能包名;
- nodename:对应节点名;
- name: name必须和配置文件的第一部分相符!
比如配置文件为Tutorials.cfg,那么name就为Tutorials!
接下来我们再对其加上可执行权限;
chmod +x *.cfg
然后修改下CMakeLists.txt的内容:
generate_dynamic_reconfigure_options(cfg/mycar.cfg
)
此时我们就可以编译所写的代码!
此时会生成调用所需要的头文件!
2. 编写服务端
接下来我们以C++为例,编写服务端的代码:
#include "ros/ros.h"
#include "dynamic_reconfigure/server.h"
#include "dynamic_recofig/drConfig.h"void cb(dynamic_recofig::drConfig& config, uint32_t level){ROS_INFO("动态参数解析数据:%d,%.2f,%d,%s,%d",config.int_param,config.double_param,config.bool_param,config.string_param.c_str(),config.list_param);
}int main(int argc, char *argv[])
{setlocale(LC_ALL,"");// 2.初始化 ros 节点ros::init(argc,argv,"dr");// 3.创建服务器对象dynamic_reconfigure::Server<dynamic_recofig::drConfig> server;// 4.创建回调对象(使用回调函数,打印修改后的参数)dynamic_reconfigure::Server<dynamic_recofig::drConfig>::CallbackType cbType;cbType = boost::bind(&cb,_1,_2);// 5.服务器对象调用回调对象server.setCallback(cbType);// 6.spin()ros::spin();return 0;
}
这里我们看一下代码的整体逻辑:主要是通过创建服务器对象(服务器对象的参数类型是我们通过client设置的),然后调用回调函数来解析设置的参数;
需要注意的是:
dynamic_reconfigure::Server<dynamic_recofig::drConfig>::CallbackType cbType;
上面我们创建了CakkbackType类型的回调函数,这个回调函数必须满足下面的类型:
void callback(ConfigType& config, uint32_t level);
- ConfigType:动态参数配置的类型(例如drConfig);
- level:参数变化的掩码,标识哪些参数被修改;
问题:但是这里我们创建的回调函数已经满足上面的参数要求了,那么是否还需要使用bind?
理论上这里我们直接传入函数指针即可:
server.setCallback(&cb); // 看似可行,但实际不成立!
但是实际上是不可以的!因为ROS的Server::setCallback接口设计并非接受原始函数指针,而是需要一个函数对象(boost::function)!
typedef boost::function<void(ConfigType &, uint32_t level)> CallbackType;void setCallback(const CallbackType &callback){boost::recursive_mutex::scoped_lock lock(mutex_);callback_ = callback;callCallback(config_, ~0); // At startup we need to load the configuration with all level bits set. (Everything has changed.)updateConfigInternal(config_);}
可以看到这里的CallbackType的类型是boost::function类型!
// 创建回调对象,绑定用户函数和参数占位符
dynamic_reconfigure::Server<dynamic_recofig::drConfig>::CallbackType cbType;
cbType = boost::bind(&cb, _1, _2); // 将cb与参数占位符绑定// 设置回调
server.setCallback(cbType);
- boost::bind(&cb, _1, _2) 生成一个函数对象,接受两个参数(config和level),并传递给cb;
- _1 对应 config,_2 对应 level;
这里我们可以再复习一下占位符和bind的作用:
占位符(Placeholders)用于在绑定函数时保留参数的位置,允许在调用生成的函数对象时动态传递这些参数:
#include <functional>
#include <iostream>
using namespace std::placeholders; // 引入占位符 _1, _2...void func(int a, double b, const std::string& c) {std::cout << a << ", " << b << ", " << c << std::endl;
}int main() {// 绑定 func,固定第一个参数为 42,保留后两个参数的位置auto bound_func = std::bind(func, 42, _1, _2);// 调用时只需传递后两个参数bound_func(3.14, "Hello"); // 输出:42, 3.14, Hello
}
配置CMakeLists.txt文件:
add_executable(dr01_server src/dr01_server.cpp)
add_dependencies(dr01_server ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(dr01_server${catkin_LIBRARIES}
)
接下来我们编译程序,再进行运行:
可以看到,当我们在客户端对数值进行更改时,服务器可以解析到并进行更新;
至此,我们就完成了一个简单的动态参数设置的案例