概念
一种可以在运行时更新参数而无需重启节点的参数配置策略。
客户端实现
- 新建功能包,添加依赖 roscpp rospy std_msgs dynamic_reconfigure
- 新建cfg文件
#! /usr/bin/env python3
"""4生成动态参数 int,double,bool,string,列表5实现流程:6 1.导包7 2.创建生成器8 3.向生成器添加若干参数9 4.生成中间文件并退出
10
"""
# 1.导包
from dynamic_reconfigure.parameter_generator_catkin import *
PACKAGE = "dr_pkg"
# 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","dr"))
- 配置CMakeLists
generate_dynamic_reconfigure_options(cfg/dr.cfg
)
服务端实现
C++
- 包含头文件
- 初始化 ros 节点
- 创建服务器对象
- 创建回调对象(使用回调函数,打印修改后的参数)
- 服务器对象调用回调对象
- spin()
#include "ros/ros.h"
#include "dynamic_reconfigure/server.h"
#include "dr_pkg/drConfig.h"/* 动态参数服务端: 参数被修改时直接打印实现流程:1.包含头文件2.初始化 ros 节点3.创建服务器对象4.创建回调对象(使用回调函数,打印修改后的参数)5.服务器对象调用回调对象6.spin()
*/void cb(dr_pkg::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<dr_pkg::drConfig> server;// 4.创建回调对象(使用回调函数,打印修改后的参数)dynamic_reconfigure::Server<dr_pkg::drConfig>::CallbackType cbType;cbType = boost::bind(&cb,_1,_2);// 5.服务器对象调用回调对象server.setCallback(cbType);// 6.spin()ros::spin();return 0;
}
python
- 导包
- 初始化 ros 节点
- 创建服务对象
- 回调函数处理
- spin()
#! /usr/bin/env python3
import rospy
from dynamic_reconfigure.server import Server
from dr_pkg.cfg import drConfig"""动态参数服务端: 参数被修改时直接打印实现流程:1.导包2.初始化 ros 节点3.创建服务对象4.回调函数处理5.spin
"""
# 回调函数
def cb(config,level):rospy.loginfo("python 动态参数服务解析:%d,%.2f,%d,%s,%d",config.int_param,config.double_param,config.bool_param,config.string_param,config.list_param)return configif __name__ == "__main__":# 2.初始化 ros 节点rospy.init_node("dr_p")# 3.创建服务对象server = Server(drConfig,cb)# 4.回调函数处理# 5.spinrospy.spin()