写在前面的话:
在ROS调试参数中,我们可以三种方式调试参数:
- 在C++中设置参数,编译执行,此种方式相对比较麻烦,每次都需要重新编译,然后查看效果,不建议;
- 将参数写入launch 文件中,
<param name="" value="" / >
此种方式,需要在C++文件中添加nh.param<param_type>(“param_name”, var, default_value)
,每次不需要编译C++文件,需要修改launch文件中参数,启动launch 即可,推荐; - 采用dynamic_reconfigure的形式完成调试,在程序运行过程中可以是实时更改参数大小,C++参数通过回调函数接收数据,实在是仿真中的一件利器,推荐。(注意cfg文件要更改执行权限).
下面给出实现过程:
代码的树行结构如下图所示:
需要额外编写cfg文件,该文件采用python编写,具体内容如下:
#!/usr/bin/env python
PACKAGE = "dynamic_tutorial"
from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()
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)
exit(gen.generate(PACKAGE, "dynamic_tutorial", "tutorial"))
其中比较重要的是gen.add函数,表示添加需要修改的参数(name, type, level, description, default, min, max)
。PACKAGE需要和创建的功能包名字相同,在exit中的第三个参数表示生成的头文件名称,本例子中为tutorial,则生成的头文件名称为 tutorialConfig.h
,生成的头文件在/devel/include
下面可以查看到。这个地方需要修改CMakelists
才可以生成,在本文后面提到。
编写相应的cpp节点文件
#include <ros/ros.h>
#include <dynamic_reconfigure/server.h>
#include <dynamic_tutorial/dynamicparamConfig.h>
void callback(dynamic_tutorial::dynamicparamConfig &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_tutorial::dynamicparamConfig> server;
dynamic_reconfigure::Server<dynamic_tutorial::dynamicparamConfig>::CallbackType f;
f = boost::bind(&callback,_1,_2);
server.setCallback(f);
ROS_INFO("spinning node");
ros::spin();
return 0;
}
这个地方需要主要我将cfg中生成的头文件已经修改为了dynamicparam
. 个人觉的C++这个地方可以当个模板来使用,对应语句基本无需修改。
CMakeLists文件修改
generate_dynamic_reconfigure_options(cfg/tutorial.cfg)
add_executable(${PROJECT_NAME}_node src/dynamic_tutorial.cpp)
add_dependencies(${PROJECT_NAME}_node ${PROJECT_NAME}_gencfg)
target_link_libraries(${PROJECT_NAME}_node ${catkin_LIBRARIES} )
内容为添加依赖,生成可执行文件。
启动
启动过程比较麻烦,建议写成launch
文件格式
首先启动roscore
, 然后启动 rosrun
节点, 最后启动rosrun rqt_reconfigure rqt_reconfigure
至此,就可以通过调节滑块完成参数的动态调节了,此种方法可以大大的提高代码的调试效率。推荐!