1.使用dynamic_reconfigure实现节点参数动态更新
0x00 为何需要在线动态更新参数
在整个ROS开发过程中,经常需要配置各种参数保证系统的正常运行,默认提供的参数一般都是写好固定在相应的配置文件中,在各节点启动时从配置文件中一次性的读取然后保持该参数一直运行,如果想要重新修改参数需要将当前节点停止,修改好配置文件中相应参数,然后重新启动节点这样才能完成参数的更新。整个过程比较费时费力,而且难免也会影响系统的正常运行,所以我们就需要在不停止节点运行情况下来实时更新所需的参数。在ROS下dynamic_reconfigure软件包就可以来完成在线动态更新节点参数的功能。
0x01 安装必须软件包
首先是安装ROS下相应版本的dynamic_reconfigure软件包,使用如下命令来安装(ROS各版本都可以使用该命令):
sudo apt-get install -y ros-$ROS_DISTRO-dynamic-reconfigure
在本次教程中我们使用turtlesim来做相应的演示,所以需要确保turtlesim相关软件包已经安装好了:
sudo apt-get install -y ros-$ROS_DISTRO-turtlesim
使用如下命令确保turtlesim可以正常运行,如下图所示:
0x02 使用yaml配置文件来更新节点参数
我们首先演示如何使用yaml文件来加载配置参数,这种方式虽然也可以修改节点参数,但是如果要想更新参数必须要先将节点停止重新启动重新读取参数才能使配置参数生效,接下来是整个操作过程:
(1)创建软件包,使用如下命令:
catkin_create_pkg turtlesim_dynamic rospy roscpp dynamic_reconfigure
(2)在src目录下编写源码文件turtlesim_dynamic.cpp,控制turtlesim来转圈:
/******************************************************** * Copyright: 2016-2018(c) ROS小课堂 www.corvin.cn * Filename: turtlesim_dynamic.cpp * Author: corvin * Descrition: 使用turtlesim来测试dynamic_reconfigure * 动态更新节点参数. * History: * 20180503: init this file. *******************************************************/ #include <ros/ros.h> #include <geometry_msgs/Twist.h> using namespace std; int main(int argc, char **argv) { ros::init(argc, argv, "turtlesim_dynamic_node"); ros::NodeHandle handle; string cmd_topic = "/turtle1/cmd_vel"; int loop_rate = 1; double linear_x = 1.0; double angular_z = 1.0; bool move_flag = true; ros::param::get("~cmd_topic", cmd_topic); ros::param::get("~loop_rate", loop_rate); ros::param::get("~linear_x", linear_x); ros::param::get("~angular_z", angular_z); ros::param::get("~move_flag", move_flag); ros::Publisher cmdVelPub = handle.advertise<geometry_msgs::Twist>(cmd_topic, 1); geometry_msgs::Twist speed; ros::Rate rate(loop_rate); while(ros::ok()) { if(move_flag) { speed.linear.x = linear_x; speed.angular.z = angular_z; cmdVelPub.publish(speed); } ros::spinOnce(); rate.sleep(); } }
(3)在cfg目录下增加dynamic.yaml配置文件,需要注意每个参数都是一个键值对,冒号后面有一个空格,文件内容如下:
# Copyright: 2016-2018(c) ROS小课堂 www.corvin.cn # FileName: dynamic.yaml # Author: corvin # Description: 用于节点启动时加载的参数配置文件. # History: # 20180503: init this file. cmd_topic: turtle1/cmd_vel loop_rate: 1 linear_x: 1.0 angular_z: 1.0 move_flag: ture
(4)在launch目录下创建turtlesim_dynamic.launch文件,文件内容如下:
<!-- Copyright: 2016-2018(c) ROS小课堂 www.corvin.cn FileName: turtlesim_dynamic.launch Author: corvin Description: 加载turtlesim_dynamic_node启动的launch文件,启动时同时加载dynamic配置文件. History: 20180503: init this file. --> <launch> <node pkg="turtlesim_dynamic" type="turtlesim_dynamic_node" name="turtlesim_dynamic_node" output="screen"> <rosparam file="$(find turtlesim_dynamic)/cfg/dynamic.yaml" command="load" /> </node> </launch>
(5)最后修改编译配置文件CMakeLists.txt,主要就是修改源码文件名和将target_link_libraries注释取消掉即可,具体需要修改的地方如下图所示:
(6)编译软件包使用turtlesim_node来进行测试:
直接在catkin_ws目录下执行catkin_make命令来编译所有软件包,然后source devel/setup.bash后就可以来使用roslaunch来启动该节点了,完整命令如下:
roslaunch turtlesim_dynamic turtlesim_dynamic.launch
接下来启动turtlesim_node节点,命令如下:
rosrun turtlesim turtlesim_node
启动后完整的测试效果如下所示,可以发现我们设置的默认频率是1Hz,移动的线速度x是1m/s,角速度z是1rad/s执行都是正常的:
当需要修改参数时,我们需要先将该节点停止,然后修改dynamic.yaml配置文件,然后重新启动才能看到修改参数后的效果,如下图所示:
0x03 使用dynamic_reconfigure来动态更新节点参数
(1)首先编写需要的cfg文件,在cfg目录下创建dynamic.cfg文件,该文件是使用python来编写的,配置文件内容如下:
#!/usr/bin/env python # _*_ coding:utf-8 _*_ """ Copyright: 2016-2018(c) ROS小课堂 www.corvin.cn FileName: dynamic.cfg Author: corvin Description: dynamic_reconfigure需要使用的cfg配置文件,该文件使用python来实现. History: 20180503: init this file. """ PACKAGE = "turtlesim_dynamic" from dynamic_reconfigure.parameter_generator_catkin import * gen = ParameterGenerator() gen.add("cmd_topic", str_t, 0, "turtlesim cmd topic name", "/turtle1/cmd_vel") gen.add("cmd_pub_rate", int_t, 0, "turtlesim cmd pub rate", 1, 0, 5) gen.add("linear_x", double_t, 0, "turtlesim linear.x", 1.0, 0.5, 3.0) gen.add("angular_z", double_t, 0, "turtlesim angular.z", 1.0, 0.5, 3.0) gen.add("move_flag", bool_t, 0, "turtlesim whether move or not", True ) log_enum = gen.enum([ gen.const("info", int_t, 0, "log print flag:INFO"), gen.const("warn", int_t, 1, "log print flag:WARN"), gen.const("error", int_t, 2, "log print flag:ERROR")], "Set Log Level") gen.add("log_level", int_t, 0, "Set Log Level", 0, 0, 2, edit_method=log_enum) exit(gen.generate(PACKAGE, "turtlesim_dynamic_node", "dynamic"))
下面来对上述源码进行简要解析,需要注意的代码如下:
-
gen = ParameterGenerator() :创建一个动态参数生成器,后面就可以往该变量中添加可以动态配置的参数。
-
gen.add("cmd_pub_rate", int_t, 0, "turtlesim cmd pub rate", 1, 0, 5):第一个参数代表是该可配置动态参数名,是一个字符串形式;第二个参数表示参数的数据类型;第三个参数表示需要传入参数动态配置回调函数中的掩码,在回调函数中会修改所有参数的掩码,表示参数已经进行修改,一般都是设置为0;第四个参数表示对该参数的说明描述;第五个参数表示参数设置的默认值;第六个参数表示参数可以设置的最小值;最后一个参数表示可设置的参数的最大值;
-
exit(gen.generate(PACKAGE, "turtlesim_dynamic_node", "dynamic")):用于生成所有C++和Python相关的头文件并且退出程序,这里第二个参数表示动态参数运行的节点名,第三个参数是生成文件所使用的前缀,需要和配置文件名相同,不要带后面的.cfg后缀,这样根据该配置文件就会生成dynamicConfig.h的头文件,后面在cpp的源码中可以直接引用。
-
需要注意给该文件增加上执行权限,使用chmod +x dynamic.cfg来给该文件加上执行权限。
(2)修改turtlesim_dynamic.cpp源码文件,具体代码如下:
/******************************************************** * Copyright: 2016-2018(c) ROS小课堂 www.corvin.cn * Filename: turtlesim_dynamic.cpp * Author: corvin * Descrition: 使用turtlesim来测试dynamic_reconfigure * 动态更新节点参数. * History: * 20180503: init this file. *******************************************************/ #include <ros/ros.h> #include <geometry_msgs/Twist.h> #include <dynamic_reconfigure/server.h> #include <turtlesim_dynamic/dynamicConfig.h> using namespace std; string cmd_topic = "/turtle1/cmd_vel"; int loop_rate = 1; double linear_x = 1.0; double angular_z = 1.0; bool move_flag = true; int log_level= 0; void dynamic_callback(turtlesim_dynamic::dynamicConfig &config) { ROS_INFO("Reconfigure Request: %s %d %f %f %s %d", config.cmd_topic.c_str(), config.cmd_pub_rate, config.linear_x, config.angular_z, config.move_flag?"True":"False", config.log_level); cmd_topic = config.cmd_topic; loop_rate = config.cmd_pub_rate; linear_x = config.linear_x; angular_z = config.angular_z; move_flag = config.move_flag; log_level = config.log_level; } int main(int argc, char **argv) { ros::init(argc, argv, "turtlesim_dynamic_node"); ros::NodeHandle handle; dynamic_reconfigure::Server<turtlesim_dynamic::dynamicConfig> server; dynamic_reconfigure::Server<turtlesim_dynamic::dynamicConfig>::CallbackType callback; callback = boost::bind(&dynamic_callback, _1); server.setCallback(callback); ros::Publisher cmdVelPub; geometry_msgs::Twist speed; while(ros::ok()) { cmdVelPub = handle.advertise<geometry_msgs::Twist>(cmd_topic, 1); ros::Rate rate(loop_rate); if(move_flag) { speed.linear.x = linear_x; speed.angular.z = angular_z; cmdVelPub.publish(speed); switch(log_level) { case 0: ROS_INFO("log level: INFO, cmd_pub_rate: %d", loop_rate); break; case 1: ROS_WARN("log level: WARN, cmd_pub_rate: %d", loop_rate); break; case 2: ROS_ERROR("log level: ERROR, cmd_pub_rate: %d", loop_rate); break; default: break; } } ros::spinOnce(); rate.sleep(); } }
下面对上述源码进行简要解析,需要注意的代码如下:
-
dynamic_reconfigure::Server<turtlesim_dynamic::dynamicConfig> server:创建了一个动态参数配置的服务端实例,参数配置的类型就是配置文件中描述的类型,该服务端实例会监听客户端的参数配置请求。
-
dynamic_reconfigure::Server<turtlesim_dynamic::dynamicConfig>::CallbackType callback;
callback = boost::bind(&dynamic_callback, _1);
server.setCallback(callback); 定义一个回调函数,并将回调函数和服务端绑定,当客户端请求修改参数时,服务端即可跳转到回调函数中进行处理。
(3)修改CMakeLists.txt编译配置文件:
(4)修改launch文件,同时启动turtlesim_node仿真小乌龟和rqt_reconfigure控制面板:
<!-- Copyright: 2016-2018(c) ROS小课堂 www.corvin.cn FileName: turtlesim_dynamic.launch Author: corvin Description: 加载turtlesim_dynamic_node启动的launch文件,启动时同时加载dynamic配置文件. History: 20180503: init this file. --> <launch> <node pkg="turtlesim" type="turtlesim_node" name="turtlesim_node" output="screen" /> <node pkg="turtlesim_dynamic" type="turtlesim_dynamic_node" name="turtlesim_dynamic_node" output="screen" /> <node pkg="rqt_reconfigure" type="rqt_reconfigure" name="rqt_reconfigure" output="screen" /> </launch>
(5)重新编译该软件包,然后启动launch文件开始测试,测试效果如下图所示:
0x04 使用dynparam命令行工具
我们除了可以使用GUI工具rqt_reconfigure来调整各参数外,还可使用命令行工具来操作各参数,该命令工具使用规则如下:
rosrun dynamic_reconfigure dynparam COMMAND
目前支持的命令列表如下:
rosrun dynamic_reconfigure dynparam list :列出当前可以动态配置参数的节点
rosrun dynamic_reconfigure dynparam get 节点名 :获取节点的配置参数信息
rosrun dynamic_reconfigure dynparam set 节点名 参数名 参数值 :设置节点的配置参数信息
rosrun dynamic_reconfigure dynparam dump 节点名 ×××.yaml: 将节点的配置参数信息保存进xxx.yaml文件中
rosrun dynamic_reconfigure dynparam load 节点名 ×××.yaml: 将保存节点配置参数信息的xxx.yaml文件加载到节点中
接下来通过演示来分别详细介绍每个命令的用法:
(1)列出当前系统中哪些节点可以动态配置参数,命令如下:
rosrun dynamic_reconfigure dynparam list
(2)获取节点的详细配置参数信息,命令如下:
rosrun dynamic_reconfigure dynparam get /turtlesim_dynamic_node
(3)设置节点的某一个参数,假如设置linear_x为2.0,命令如下:
rosrun dynamic_reconfigure dynparam set /turtlesim_dynamic_node linear_x 2.0
(4)将节点的配置信息保存到yaml文件中,假设文件名为my_dynamic.yaml,完整命令如下:
rosrun dynamic_reconfigure dynparam dump /turtlesim_dynamic_node my_dynamic.yaml
(5)修改yaml配置文件里参数,重新将参数加载到节点中,修改参数如下所示:
使用如下命令来将修改的参数重新加载,命令如下:
rosrun dynamic_reconfigure dynparam load /turtlesim_dynamic_node my_dynamic.yaml
0x04 参考资料
[1].dynamic_reconfigure软件包在ROS WiKi官网地址[OL]. http://wiki.ros.org/dynamic_reconfigure/Tutorials
[2].turtlesim软件包在ROS WiKi官网地址[OL]. http://wiki.ros.org/turtlesim
[3].古月关于dynamic_reconfigure的介绍[OL]. http://www.guyuehome.com/1173
0x05 问题反馈
大家在按照教程操作过程中有任何问题,可以关注ROS小课堂的官方微信公众号,在公众号中给我发消息反馈问题即可,我基本上每天都会处理公众号中的留言!当然,如果你要是顺便给ROS小课堂打个赏,我也会感激不尽的,打赏30块还会邀请进ROS小课堂的微信群与更多志同道合的小伙伴一起学习和交流!