【ROS学习】通过dynamic_reconfigure动态调参
摘要
!!! note
在ROS中我们经常需要对参数进行调整,我们可以通过ROS的dynamic_reconfigure功能包实现机器人PID控制器的可视化动态调整。
!!!
创建功能包
1.进入工作空间
·cd xxx_ws/src
2.创建一个新的功能包(名为dynamic_reconfigure_test)
catkin_create_pkg dynamic_reconfigure_test

编写配置文件
- 新建一个cfg文件夹
mkdir cfg - 新建一个新的cfg文件(例如 pid.cfg)
touch pid.cfg
3.编写cfg 文件
PACKAGE = "dynamic_reconfigure_test"
#导入dynamic_reconfigure功能包提供的参数生成器(parameter generator)
from dynamic_reconfigure.parameter_generator_catkin import *
#创建一个参数生成器
gen = ParameterGenerator()
#定义动态配置的参数
gen.add("KP", double_t, 0, "KP_param", 0.0, 0, 500)
gen.add("KI", double_t, 0, "KI_param", 0.0, 0, 500)
gen.add("KD", double_t, 0, "KD_param", 0.0, 0, 500)
#退出
exit(gen.generate(PACKAGE, "dynamic_PID", "pid"))

4.给配置文件设置权限
通过ll查看当前文件的权限,通过 chmod a+x pid.cfg添加可执行的功能
配置CMakeList文件
1.修改cmakelists
因为我们一开始创建新的功能包就包含了dynamic_reconfigure 这个功能包,所以已经有了!
如果是后面在自己的原有基础上加功能的话,记得写上!



2.修改packages

先进行编译
先进行编译的目的是生成需要的头文件,添加编译白名单:
catkin_make -DCATKIN_WHITELIST_PACKAGES="dynamic_reconfigure_test"
我们可以看到/devel/include中生成了对应的.h文件

创建服务器节点
- src中创建一个cpp文件
- 添加cpp函数
#include <dynamic_reconfigure/server.h>
#include <dynamic_reconfigure_test/pidConfig.h>
float KP = 0.0;
float KI = 0.0;
float KD = 0.0;
//回调函数
void Callback(dynamic_reconfigure_test::pidConfig &config)
{
KP = config.KP;
KI = config.KI;
KD = config.KD;
ROS_INFO("KP KI KD = [%f %f %f]",KP,KI,KD);
}
int main(int argc,char **argv)
{
//初始化,创建节点
ros::init(argc,argv,"dynamic_test");
//创建一个参数动态配置的服务器实例
dynamic_reconfigure::Server<dynamic_reconfigure_test::pidConfig> server;
//定义回调函数
dynamic_reconfigure::Server<dynamic_reconfigure_test::pidConfig>::CallbackType f;
//将回调函数和服务端绑定,当客户端请求修改参数时,服务器跳转到回调函数进行处理
f = boost::bind(&Callback,_1);
server.setCallback(f);
ros::spin();
return 0;
}
3.配置CMakelist文件

执行
分别运行
roscore
rosrun dynamic_reconfigure_test dynamic_test
rosrun rqt_reconfigure rqt_reconfigure


浙公网安备 33010602011771号