文章目录
文章目录
前言
一、编写.cfg文件
二、为节点配置dynamic_reconfigure
总结
前言
dynamic_reconfigure配置是ROS中为了方便用户对程序中的参数进行实时调整而推出的工具,配置好自己的dynamic_reconfigure文件后,可以很方便的使用ROS提供的rqt_reconfigure工具对程序的参数进行合理调整,以获得最优的性能。
例如:move_base中就针对costmap、planner等设置了很多动态调整的参数,可以方便用户在使用过程中调整得到合适的参数。
又例如:如果我们开发了一个PID控制器程序,如果这时能通过rqt_reconfigure工具,对PID参数进行合理的调整,然后直接将获得的参数写进程序,就能使工作更加高效。
一、编写.cfg文件
1.在功能包文件夹下,创建一个config文件夹(其他名字也行,比如cfg)
在其中创建一个后缀为.cfg的文件
2.在其中写入内容
#!/usr/bin/env python
from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()
type_enum = gen.enum([gen.const("centroid", str_t, "centroid", "Use Centroid"),
gen.const("initial", str_t, "initial", "Use Initial"),
gen.const("middle", str_t, "middle", "Use Middle")],
"An enum to set frontier type")
gen.add("timeout", double_t, 0, "Explore Timeout(s)", 30.0, 10.0, 100.0)
gen.add("min_frontier_size", double_t, 0, "Min Frontier Size(m)", 0.75, 0.5, 2)
gen.add("visualize", bool_t, 0, "Is Visualize?", True)
gen.add("frontier_type", str_t, 0, "Select Frontier Type", "centroid", edit_method=type_enum)
gen.add("potential_scale", double_t, 0, "Distance Weight", 3.0)
gen.add("gain_scale", double_t, 0, "Gain Weight", 1.0)
gen.add("information_scale", double_t, 0, "Information Weight", 1.2)
gen.add("information_r", double_t, 0, "Information Radius", 3.0)
exit(gen.generate("explore_server", "explore_server", "Explore"))
进行逐行解析:
#!/usr/bin/env python
from dynamic_reconfigure.parameter_generator_catkin import *
说明这是一个python文件,使用/usr/bin/env下的python解析,并引入dynamic_reconfigure头文件
gen = ParameterGenerator()
创建一个参数生成器,然后可以使用add函数添加动态配置的参数,add函数的参数如下:
-
name - 一个字符串,指定应存储此参数的名称
-
paramtype - 定义存储值的类型,可以是 int_t、double_t、str_t 或 bool_t 中的任何一个
-
level - 稍后将传递给动态重新配置回调的位掩码。当回调被调用时,所有已更改参数的级别值将被或运算在一起,并将结果值传递给回调。
-
description - 描述参数的字符串
-
default - 指定默认值
-
min - 指定最小值(可选,不适用于字符串和布尔值)
-
max - 指定最大值(可选,不适用于字符串和布尔值)
例如:
gen.add("timeout", double_t, 0, "Explore Timeout(s)", 30.0, 10.0, 100.0)
我想动态设置程序超时时间(timeout),该变量为double类型,位掩码为0,描述是"Explore Timeout(s)",默认值为30.0,最小值为:10.0,最大值为:100.0,这个配置在rqt_reconfigure中的显示如下:
布尔类型的值没有最大最小值,它在程序中的显示如下:
type_enum = gen.enum([gen.const("centroid", str_t, "centroid", "Use Centroid"),
gen.const("initial", str_t, "initial", "Use Initial"),
gen.const("middle", str_t, "middle", "Use Middle")],
"An enum to set frontier type")
这里我们可以使用gen.num创建一个枚举类型的变量,让用户可以通过下拉列表选择值,gen.num中有两个参数,一个是gen.const组成的列表,gen.const参数结构和gen.add一样,第二个参数就是枚举类型的描述。
gen.add("frontier_type", str_t, 0, "Select Frontier Type", "centroid", edit_method=type_enum)
然后可以通过edit_method=type_enum参数将枚举类型添加进去,最后的显示效果如下:
最后,使用gen.generate生成config文件,并使用exit退出
exit(gen.generate("explore_server", "explore_server", "Explore"))
gen.generate第一个参数是config的“命名空间”(功能包名),第二个参数是可以在其中运行的节点的名称(仅用于生成文档),第三个参数是生成的文件将获得的名称前缀。
具体来说,第一个参数是我们使用生成的Config文件的命名空间(功能包名)
第二个参数是运行时的节点名
第三个参数是生成配置头文件的前缀,我们需要包含我们生成的配置头文件
Explore就是头文件的前缀,可以在devel/include/功能包名 看到这个生成的头文件(这和msgs生成类似)
3.CmakeLists.txt和package.xml文件修改
首先需要在find_package和catkin_package函数中添加dynamic_reconfigure包的依赖
然后在generate_dynamic_reconfigure_options函数中添加.cfg文件,这与生成.msg类似,config/是你定义的文件夹名
最后需要在add_dependencies中添加依赖项${PROJECT_NAME}_gencfg
在package.xml文件中添加dynamic_reconfigure的依赖
二、为节点配置dynamic_reconfigure
配置好.cfg文件后,就可以在我们自己编写的节点中使用生成的配置文件了。
首先引入头文件:
第一个是dynamic_reconfigure服务器的头文件,用于创建服务器,第二个是我们自己写的.cfg文件生成的头文件,用于使用我们定义的参数。
dynamic_reconfigure::Server<ExploreConfig> configServer;
dynamic_reconfigure::Server<ExploreConfig>::CallbackType cb;
然后,我们可以创建两个变量,第一个是动态配置参数服务器,第二个是回调函数,也就是我们使用rqt_reconfigure调参时进入的函数,需要我们自己编写。
void Explore_Server::configCb(ExploreConfig& config, uint32_t level)
{
ROS_INFO("Dynamic Config Start");
timeout = config.timeout;
min_frontier_size_ = config.min_frontier_size;
visualize_ = config.visualize;
frontier_type_ = config.frontier_type;
potential_scale_ = config.potential_scale;
gain_scale_ = config.gain_scale;
information_scale_ = config.information_scale;
information_r_ = config.information_r;
}
然后可以在程序中编写自己的回调函数,我这里进行了赋值操作,当然也可以进行其他操作,这里configCb之前的Explore_Server::是我程序中的命名空间,非必需,大家根据自己程序编写。
cb = boost::bind(&Explore_Server::configCb, this, _1, _2);
configServer.setCallback(cb);
然后使用bind函数将回调函数绑定后赋值给cb变量,然后使用setCallback函数为服务器设置回调函数。
当然,这些修改的参数要在其他类中的方法使用,还应该提供一个参数更新的接口:
search_.configUpdate(min_frontier_size_, potential_scale_, gain_scale_, information_scale_, information_r_);
最后,可以使用dynparam dump将调好的参数写到文件中:
rosrun dynamic_reconfigure dynparam dump /your_node dump.yaml
也可以使用dynparam load将参数文件再次加载:
rosrun dynamic_reconfigure dynparam load /node dump.yaml
总结
到此为止就实现了一个动态参数配置的节点和我们自定义个.cfg文件,在运行程序时,我们就可以使用rqt_configure工具,实时的动态调节程序的参数,帮助我们高效便捷的获得最优程序参数。