动态参数配置

机器人在很多情况下需要不停的调整参数使得机器人的性能达到最优的状态(比如机器人的PID参数整定),而通过launch文件中加载yaml文件的方式调试参数需要不停的重启程序,导致调试效率极低,这里就需要用到动态参数配置功能。

创建cfg文件

首先,要实现动态参数配置,需要将待配置参数以特定格式写入.cfg文件。这里我们新建一个功能包。

$ cd ros_ws/src
$ catkin_create_pkg dynamic_tutorial rospy roscpp dynamic_reconfigure
$ cd dynamic_tutorial
$ mkdir cfg

在cfg文件夹中添加tutorial.cfg
tutorial.cfg

#!/usr/bin/env python

PACKAGE = "dynamic_tutorial"

from dynamic_reconfigure.parameter_generator_catkin import *

gen = ParameterGenerator()

#add(name,type, level,description, default, min,max)
gen.add("vel_x", double_t, 0, "linear velocity of the robot",0,-0.5,0.5)
gen.add("vel_z", double_t, 0, "rotation velocity of the robot", 0 ,-2.0,2.0)
gen.add("stop", bool_t, 0 , "if stop the robot", False)

# name:参数名,使用字符串描述;
# type:定义参数的类型,可以是int_t, double_t, str_t, 或者bool_t;
# level:需要传入参数动态配置回调函数中的掩码,在回调函数中会修改所有参数的掩码,表示参数已经进行修改;
# description:描述参数作用的字符串;
# default:设置参数的默认值;
# min:可选,设置参数的最小值,对于字符串和布尔类型值不生效;
# max:可选,设置参数的最大值,对于字符串和布尔类型值不生效;
# 这种方法可以生成一个参数值,也可以使用如下方法生成一个枚举类型的值:

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"))

添加动态程序模块

编写好.cfg后需要在程序模块中添加动态参数配置服务,在src文件夹中添加一个demo:dynamic_tutorial.cpp

#include <ros/ros.h>
#include <dynamic_reconfigure/server.h>
#include <dynamic_tutorial/tutorialConfig.h>


/** 
 * @brief 回调函数-收到reconfigure时调用
 * @param config    tutorialConfig引用对象    
 * @param level     优先级
 *
 * @return 无
 */
void callback(dynamic_tutorial::tutorialConfig &config,uint32_t level)
{
    ROS_INFO("Reconfigure request:%f,%f,%s,%d",
            config.vel_x,config.vel_z,
            config.stop?"True":"False",
            config.size);
}

int main(int argc,char** argv)
{
    ros::init(argc,argv,"dynamic_tutorial_node");
    ros::NodeHandle nh;
    //定义一个动态参数配置服务
    dynamic_reconfigure::Server<dynamic_tutorial::tutorialConfig> server;
    //定义一个动态参数配置服务的回调type
    dynamic_reconfigure::Server<dynamic_tutorial::tutorialConfig>::CallbackType f;
    //绑定callback函数
    f = boost::bind(&callback,_1,_2);
    //设置callback函数
    server.setCallback(f);

    ROS_INFO("Spinning node");
    ros::spin();
    return 0;
}

配置编译文件

.cfg文件与.cpp文件编写完成后需要修改CMakeLists.txt。

generate_dynamic_reconfigure_options(
  cfg/tutorial.cfg
)
add_executable(${PROJECT_NAME}_node src/dynamic_tutorial.cpp)
add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(${PROJECT_NAME}_node ${catkin_LIBRARIES})

catkin_make后即可运行,打开两个终端分别运行roscore、dynamic_tutorial_node
再打开一个终端,然后运行如下指令启动动态调参窗口。

rosrun rqt_reconfigure rqt_reconfigure

如图所示,通过修改动态窗口中数值或选项即可修改参数。

学习笔记