dynamic_reconfigure可以用来实时修改参数,很适合用于机器人参数可视化在线调试。减少了在调试机器人的时候修改完参数再编译这样低效的操作过程,同时效果和qt GUI差不多。
下面详细介绍一下整个过程。
首先我们需要创建自己的一个ros包
catkin_create_pkg --rosdistro ROSDISTRO dynamic_tutorials rospy roscpp dynamic_reconfigure
mkdir cfg
我理解这个文件的作用相当于一个前端界面设计。
#!/usr/bin/env python
PACKAGE = "dynamic_tutorials"
from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()#初始化ros,导入参数生成
#下面是添加一些参数列表
#add函数每个参数对应的意义为:名字 数据类型 等级 描述 默认数值大小 参数的最小值 参数的最大值
#例如:添加一个名字为“int_param”的参数,类型为int_t,优先级为最高,描述为"An Integer parameter",
#默认值为50,范围为0到100
gen.add("int_param", int_t, 0, "An Integer parameter", 50, 0, 100)
gen.add("double_param", double_t, 0, "A double parameter", .5, 0, 1)
gen.add("str_param", str_t, 0, "A string parameter", "Hello World")
gen.add("bool_param", bool_t, 0, "A Boolean parameter", True)
size_enum = gen.enum([ gen.const("Small", int_t, 0, "A small constant"),
gen.const("Medium", int_t, 1, "A medium constant"),
gen.const("Large", int_t, 2, "A large constant"),
gen.const("ExtraLarge", int_t, 3, "An extra large constant")],
"An enum to set size")
gen.add("size", int_t, 0, "A size parameter which is edited via an enum", 1, 0, 3, edit_method=size_enum)
#退出生成器,并且告诉生成器需要生成"dynamic_tutorials", "Tutorials"文件,注意第二个参数最好和包名一致,第三个参数
#最好和.cfg的文件名一致
exit(gen.generate(PACKAGE, "dynamic_tutorials", "Tutorials"))
修改权限
chmod a+x cfg/Tutorials.cfg
修改CMakeLists.txt文件
#add dynamic reconfigure api
generate_dynamic_reconfigure_options(
cfg/Tutorials.cfg
)
# 注意example_node 需要你后面的node一致,所以是需要修改的 第二个注意的就是这句后放置的顺序
add_dependencies(example_node ${PROJECT_NAME}_gencfg)
在src下面建一个server.cpp文件
#include
#include
#include
void callback(dynamic_tutorials::TutorialsConfig &config, uint32_t level) {
ROS_INFO("Reconfigure Request: %d %f %s %s %d",
config.int_param, config.double_param,
config.str_param.c_str(),
config.bool_param?"True":"False",
config.size);
}
int main(int argc, char **argv) {
ros::init(argc, argv, "dynamic_tutorials");
dynamic_reconfigure::Server<dynamic_tutorials::TutorialsConfig> server;
dynamic_reconfigure::Server<dynamic_tutorials::TutorialsConfig>::CallbackType f;
f = boost::bind(&callback, _1, _2);
server.setCallback(f);
ROS_INFO("Spinning node");
ros::spin();
return 0;
}
修改CMakeLists.txt
注意:add_dependencies需要放到后面,否则编译会报错.
add_executable(server_node
src/server.cpp
)
add_dependencies(server_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(server_node
${catkin_LIBRARIES}
)
add_dependencies(server_node ${PROJECT_NAME}_gencfg)
然后在catkin路径下编译。
生成一个server_node可执行程序。
首先打开一个reconfigure_gui
rosrun rqt_gui rqt_gui -s reconfigure
接下来运行
rosrun dynamic_tutorials server_node
然后点击一下界面的refresh按钮。
当我们移动滑块修改数值时,控制台会出现如下消息:
$ rosrun dynamic_tutorials server_node
[ INFO] [1543653672.086715303]: Reconfigure Request: 50 0.500000 Hello World True 1
[ INFO] [1543653672.088855283]: Spinning node
[ INFO] [1543653682.834439677]: Reconfigure Request: 31 0.500000 Hello World True 1
[ INFO] [1543653688.787728891]: Reconfigure Request: 42 0.500000 Hello World True 1
[ INFO] [1543653697.835389329]: Reconfigure Request: 35 0.500000 Hello World True 1
[ INFO] [1543658117.635085148]: Reconfigure Request: 35 0.320000 Hello World True 1
[ INFO] [1543658119.285826415]: Reconfigure Request: 35 0.320000 Hello World True 2
[ INFO] [1543658270.037109274]: Reconfigure Request: 35 0.530000 Hello World True 2
[ INFO] [1543658270.901272044]: Reconfigure Request: 35 0.590000 Hello World True 2
[ INFO] [1543658271.533270257]: Reconfigure Request: 35 0.720000 Hello World True 2
[ INFO] [1543658272.176771669]: Reconfigure Request: 35 0.750000 Hello World True 2
[ INFO] [1543658279.383009569]: Reconfigure Request: 35 0.750000 ni hao True 2
[ INFO] [1543658283.983014755]: Reconfigure Request: 35 0.740000 ni hao True 2
[ INFO] [1543658285.265657221]: Reconfigure Request: 35 0.730000 ni hao True 2