上一篇博文介绍了ROS中参数的基本用法,这篇博文继续介绍参数的动态调整。
创建和使用cfg文件
在上篇博文提到的dynamic_turtle包中新建cfg文件夹,并创建dynamic_turtle.cfg。打开dynamic_turtle.cfg,写入以下内容:
#!/usr/bin/env python
PACKAGE = "dynamic_turtle"
from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()
gen.add("speed", double_t, 0, "the speed of turtle", 4.0, 0.5, 20)
exit(gen.generate(PACKAGE, "dynamic_turtle", "dynamic_turtle"))
dynamic_turtle.cfg其实是一个基于python的模块,首先创建一个ParameterGenerator对象,然后调用其add()函数将参数添加到参数列表中。add()的参数含义分别是:参数名,参数类型,级别,描述,缺省值,最小值,最大值。
这里我添加了一个参数speed,最小值设置为0.5,最大值设置为20。
最后一行是告知generator创建必要的文件并退出程序。第二个参数是cfg文件依附的节点名,第三个参数是生成头文件名称的前缀。(例如我生成的头文件即为:dynamic_turtleConfig.h”, 如果是python则为 “dynamic_turtleConfig.py”)
编辑完成之后,我们需要添加运行权限才能使用.cfg文件。
$chmod a+x cfg/dynamic_turtle.cfg
再修改CMakeList.txt,产生相应的头文件为后续所用:(注意:add_dependencies需要在add_executable之后,taeget_link之前)
generate_dynamic_reconfigure_options(
cfg/dynamic_turtle.cfg
)
add_dependencies(dynamic_turtle_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_gencfg)
利用回调机制动态修改参数
将动态调整机制加入circle.cpp中:
#include <ros/ros.h>
#include <geometry_msgs/Twist.h>
#include <dynamic_reconfigure/server.h>
#include <dynamic_turtle/dynamic_turtleConfig.h>
geometry_msgs::Twist T;
void ConfigCb(dynamic_turtle::dynamic_turtleConfig &config, uint32_t level)
{
T.linear.x = config.speed;
T.angular.z = T.linear.x / 2.0;
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "circle");
ros::NodeHandle nh;
/*dynamic config*/
dynamic_reconfigure::Server<dynamic_turtle::dynamic_turtleConfig> server;
dynamic_reconfigure::Server<dynamic_turtle::dynamic_turtleConfig>::CallbackType f;
f = boost::bind(&ConfigCb, _1, _2);
server.setCallback(f);
if(!nh.getParam("/speed", T.linear.x))
{
ROS_ERROR("Get Speed ERROR");
return 0;
}
T.angular.z = T.linear.x / 2.0;
ros::Publisher twist_pb = nh.advertise<geometry_msgs::Twist>("turtle1/cmd_vel", 100);
ros::Rate rate(1);
while(ros::ok())
{
twist_pb.publish(T);
ros::spinOnce();
rate.sleep();
}
}
接下来针对动态调整的部分代码做一些讲解,让大家进一步地了解动态修改参数的方法。
#include <dynamic_reconfigure/server.h>
#include <dynamic_turtle/dynamic_turtleConfig.h>
这一段包含了动态修改参数所必要的两个头文件,注意第二个头文件就是我们利用dynamic_turtle.cfg文件产生的。
void ConfigCb(dynamic_turtle::dynamic_turtleConfig &config, uint32_t level)
{
T.linear.x = config.speed;
T.angular.z = T.linear.x / 2.0;
}
这是一个回调函数,config为上述.cfg文件声明的参数列表,利用config.speed便可以调用更改参数时的speed值,并改变T的值,从而改变乌龟转圈的速度。
dynamic_reconfigure::Server<dynamic_turtle::dynamic_turtleConfig> server;
dynamic_reconfigure::Server<dynamic_turtle::dynamic_turtleConfig>::CallbackType f;
f = boost::bind(&ConfigCb, _1, _2);
server.setCallback(f);
这段代码声明了一个动态调整参数的服务,并设置其回调函数为ConifgCb。当服务一旦被访问,回调函数自动执行。
最后执行一下 $catkin_make
,重新编译产生新的可执行文件和头文件。
文件树如下:
利用rqt_reconfigure可视化调整参数
分别执行以下命令:
$roslaunch dynamic_turtle circle.launch
$rosrun turtlesim turtlesim_node
rosrun rqt_reconfigure rqt_reconfigure
在rqt_reconfigure窗口的左边栏选择circle_node,滑动右侧的滑条,或者直接在窗口设置一个值都可以动态的改变speed。在turtlesim中也可以看到乌龟加快或者减慢转圈的速度。(为什么乌龟的轨迹不是完全重合呢,按理说半径恒为2啊,这个问题留给读者自己思考,可以下方留言交流哦~)
总结
使用动态调整参数的机制可总结为以下步骤:
-
在package.xml文件中加入dynamic_reconfigure编译依赖和运行依赖。
-
创建.cfg文件,添加参数名到参数列表。
-
修改CMakeLists.txt。添加generate_dynamic_reconfigure_options以及add_dependencies。
-
在程序中加入两个头文件,并声明动态调整服务,绑定其回调函数。在回调函数中实现对参数对程序的影响
后记
动态调整参数实质上是访问动态参数服务,利用回调函数对原程序进行修改,并且不需要进行重新编译。这样做最大的好处便是可以在机器人运行过程中,在调整参数之后,实时的查看机器人运行状态,极大的方便了参数的调试。