ROS_Dynamic Reconfig 動態參數調節

創建功能包(package)

cd ~/catkin_ws/src
catkin_create_pkg dynamic_refg roscpp dynamic_reconfigure
cd ..
catkin_make

向功能包添加動態重配置文件(.cfg)

roscd dynamic_refg
mkdir cfg && cd cfg
gedit My_cfg.cfg

向My_cfg.cfg文件輸入如下的內容:

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

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_refg", "My_cfg")) 
其中  gen = ParameterGenerator()  創建一個參數生成器對象
     gen.add 加入不同的參數。其中gen.add(...)格式如下:

 gen.add(name, type, level, description, default, min, max)
     name: 參數的名稱
     type: 參數類型
     level:一個傳遞給回調的位掩碼
     description: 一個描述參數
     default: 節點啓動的初始值
     min: 參數最小值
     max: 參數最大值

 exit  生成必要的文件並退出
       first parameter is namespace's name
       second parameter is node's name
       third parameter is the current file's name

在編譯之前,必須運行
      chmod a+x src/dynamic_refg/cfg/My_cfg.cfg
    添加權限。

修改CMakeLists.txt文件

將CMakeLists.txt文件的內容修改爲如下所示:

cmake_minimum_required(VERSION 2.8.3)
project(dynamic_refg)

find_package(catkin REQUIRED COMPONENTS
  dynamic_reconfigure
  roscpp
  rospy
  std_msgs
)


## Generate dynamic reconfigure parameters in the 'cfg' folder
 generate_dynamic_reconfigure_options(
   cfg/My_cfg.cfg
 )


catkin_package(
#  INCLUDE_DIRS include
   LIBRARIES dynamic_refg
   CATKIN_DEPENDS dynamic_reconfigure roscpp rospy std_msgs
#  DEPENDS system_lib
)


include_directories(
# include
  ${catkin_INCLUDE_DIRS}
)

構建功能包,生成相關頭文件

cd ~/catkin_ws
catkin_make

向功能包添加動態重配置節點

node.cpp
這裏寫代碼片

#include <ros/ros.h>

#include <dynamic_reconfigure/server.h>
#include "dynamic_refg/My_cfgConfig.h"

void callback(dynamic_refg::My_cfgConfig &config)
{
  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, "node_dynamic_reconfigure");

  dynamic_reconfigure::Server<dynamic_refg::My_cfgConfig> server;
  dynamic_reconfigure::Server<dynamic_refg::My_cfgConfig>::CallbackType f;

  f = boost::bind(&callback, _1); //綁定回調函數
  server.setCallback(f); //爲服務器設置回調函數, 節點程序運行時會調用一次回調函數來輸出當前的參數配置情況

  ROS_INFO("Spinning node");
  ros::spin(); //服務器循環監聽重配置請求,當服務器收到重配置請求的時候,就會自動調用回調函數
  return 0;
}

修改CMakeLists.txt文件

將CMakeLists.txt文件的內容修改爲如下:

cmake_minimum_required(VERSION 2.8.3)
project(dynamic_refg)

find_package(catkin REQUIRED COMPONENTS
  dynamic_reconfigure
  roscpp
  rospy
  std_msgs
)

 generate_dynamic_reconfigure_options(
   cfg/My_cfg.cfg
 )

catkin_package(
#  INCLUDE_DIRS include
   LIBRARIES dynamic_refg
   CATKIN_DEPENDS dynamic_reconfigure roscpp rospy std_msgs
#  DEPENDS system_lib
)


include_directories(
# include
  ${catkin_INCLUDE_DIRS}
)


add_executable(node src/node.cpp)
add_dependencies(node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(node
   ${catkin_LIBRARIES}
 )

構建功能包

cd ~/catkin_ws
catkin_make

構建功能包,運行動態重配置服務器節點程序

打開終端,輸入:

rosrun dynamic_refg node 

打開另一個終端,輸入:

rosrun rqt_reconfigure rqt_reconfigure

完成動態節點的編寫。

發表評論
所有評論
還沒有人評論,想成為第一個評論的人麼? 請在上方評論欄輸入並且點擊發布.
相關文章