ROS dynamic_reconfigure 动态参数配置

动态参数配置模板

编写.cfg文件

mkdir Ros-DynamicConfiguire
cd Ros-DynamicConfiguire && mkdir src
cd src 
catkin_create_pkg dynamic_tutorials  roscpp rospy rosmsg std_msgs dynamic_reconfigure 
cd dynamic_tutorials   && mkdir cfg
cd cfg && touch cfg/Tutorials.cfg

配置文件Tutorials.cfg内容如下

#!/usr/bin/env python
PACKAGE = "dynamic_tutorials"

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_tutorials", "Tutorials"))

name - a string which specifies the name under which this parameter should be stored
type - defines the type of value stored, and can be any of int_t, double_t, str_t, or bool_t
level - A bitmask which will later be passed to the dynamic reconfigure callback. When the callback is called all of the level values for parameters that have been changed are ORed together and the resulting value is passed to the callback.
description - string which describes the parameter
default - specifies the default value
min - specifies the min value (optional and does not apply to strings and bools)
max - specifies the max value (optional and does not apply to strings and bools)
注: gen.enum用于生成枚举参数

使用.cfg文件

chmod a+x cfg/Tutorials.cfg

在CMakeLists.txt下添加以下命令

generate_dynamic_reconfigure_options(
	cfg/Tutorials.cfg
)
## Declare a C++ executable
add_executable(${PROJECT_NAME}_node src/dynamic_tutorials_node.cpp)

## Specify libraries to link a library or executable target against
 target_link_libraries(${PROJECT_NAME}_node
   ${catkin_LIBRARIES}
 )

dynamic_tutorials_node.cpp

#include <ros/ros.h>

#include <dynamic_reconfigure/server.h>
#include <dynamic_tutorials/TutorialsConfig.h>

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;
}

注: 参数来配置文件的头文件路径为:package_name/file_name+"Config.h"
注: 在callback函数中进行参数赋值操作。

运行

roscore #terminal 1
rosrun dynamic_tutorials dynamic_tutorials_node #termianl 2
rosrun rqt_reconfigure rqt_reconfigure #terminal 3

运行结果

参考

  1. Python dynamic_reconfigure
    但是文件updatePID_node.py 第一行添加如下代码
   #! /usr/bin/env python
  1. C++ ros之动态配置参数
posted @ 2022-01-25 19:16  采男孩的小蘑菇  阅读(432)  评论(0编辑  收藏  举报