(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

nodeのためのDynamic Reconfigureを準備する

Description: nodeのためのDynamic Reconfigureを準備する

Tutorial Level:

動的再設定可能なnodeの例は、 dynamic_reconfigure/test以下で見れると思います。

nodeのためのDynamic Reconfigureを準備する

この例では、ROSのメッセージの中で変数を再設定するように動的再設定可能なnodeを準備させるにはどのようにするかをお見せします。 driver_base/SensorLevels.h. 以下でyour_packageと呼ばれるパッケージと呼ぶことになるdynamic reconfigure サーバnodeを加えていることを前提としています。

  1. 以下の行をmanifest.xmlに加えることで、 dynamic_reconfigureに依存するようにしてください,

      <depend package="dynamic_reconfigure" />

以下の例ではさらにこちらも必要です。

  •   <depend package="driver_base" />
  • 設定フイルを作成し、 your_package/cfg/MyStuff.cfgを作ってください:

       1 #! /usr/bin/env python
       2 # Forearm camera configuration
       3 
       4 PACKAGE='your_package'
       5 import roslib; roslib.load_manifest(PACKAGE)
       6 
       7 from math import pi
       8 
       9 from driver_base.msg import SensorLevels
      10 from dynamic_reconfigure.parameter_generator import *
      11 
      12 gen = ParameterGenerator()
      13 angles = gen.add_group("Angles")
      14 #       Name                    Type      Reconfiguration level             Description                                                                                      Default    Min   Max
      15 angles.add("min_ang",              double_t, SensorLevels.RECONFIGURE_STOP,    "The angle of the first range measurement. The unit depends on ~ang_radians.",                   -pi/2,     -pi, pi)
      16 angles.add("max_ang",              double_t, SensorLevels.RECONFIGURE_STOP,    "The angle of the first range measurement. The unit depends on ~ang_radians.",                   pi/2,      -pi, pi)
      17 gen.add("intensity",            bool_t,   SensorLevels.RECONFIGURE_STOP,    "Whether or not the hokuyo returns intensity values.",                                           False)
      18 gen.add("cluster",              int_t,    SensorLevels.RECONFIGURE_STOP,    "The number of adjacent range measurements to cluster into a single reading",                    1,         0,   99)
      19 gen.add("skip",                 int_t,    SensorLevels.RECONFIGURE_STOP,    "The number of scans to skip between each measured scan",                                        0,         0,    9)
      20 gen.add("port",                 str_t,    SensorLevels.RECONFIGURE_CLOSE,   "The serial port where the hokuyo device can be found",                                          "/dev/ttyACM0")
      21 gen.add("calibrate_time",       bool_t,   SensorLevels.RECONFIGURE_CLOSE,   "Whether the node should calibrate the hokuyo's time offset",                                    Tre)
      22 gen.add("frame_id",             str_t,    SensorLevels.RECONFIGURE_RUNNING, "The frame in which laser scans will be returned",                                               "laser")
      23 gen.add("time_offset",          double_t, SensorLevels.RECONFIGURE_RUNNING, "An offet to add to the timestamp before publication of a scan",                                 0,     -0.25, 0.25)
      24 gen.add("allow_unsafe_settings",bool_t,   SensorLevels.RECONFIGURE_CLOSE,   "Turn this on if you wish to use the UTM-30LX with an unsafe angular range. Turning this option on may cause occasional crashes or bad data. This option is a tempory workaround that will hopefully be removed in an upcoming driver version.", False)
      25 
      26 exit(gen.generate(PACKAGE, "dynamic_reconfigure_node", "MyStuff"))
    

    1

  • .cfg ファイルを実行可能にしてください。

    chmod a+x your_package/cfg/MyStuff.cfg
  • コールバックを処理するROSのnodeを作成します。例えば、以下をyour_package/src/dynamic_reconfigure_node.cppとして保存してください:

       1 #include <dynamic_reconfigure/server.h>
       2 #include <your_package/MyStuffConfig.h>
       3 
       4 void callback(your_package::MyStuffConfig &config, uint32_t level)
       5 {
       6   ROS_INFO("Reconfigure request : %f %f %i %i %i %s %i %s %f %i",
       7            config.groups.angles.min_ang, config.groups.angles.max_ang,
       8            (int)config.intensity, config.cluster, config.skip, 
       9            config.port.c_str(),(int)config.calibrate_time, 
      10            config.frame_id.c_str(), config.time_offset,   
      11            (int)config.allow_unsafe_settings);
      12   
      13   // do nothing for now
      14 }
      15 
      16 int main(int argc, char **argv)
      17 {
      18   ros::init(argc, argv, "dynamic_reconfigure_node");
      19   dynamic_reconfigure::Server<your_package::MyStuffConfig> srv;
      20   dynamic_reconfigure::Server<your_package::MyStuffConfig>::CallbackType f;
      21   f = boost::bind(&callback, _1, _2);
      22   srv.setCallback(f);
      23   ROS_INFO("Starting to spin...");
      24   ros::spin();
      25   return 0;
      26 }
    
  • 以下の行を加えることでCMakeLists.txtを更新し、上のをコンパイルしてください。

    # add dynamic reconfigure api
    rosbuild_find_ros_package(dynamic_reconfigure)
    include(${dynamic_reconfigure_PACKAGE_PATH}/cmake/cfgbuild.cmake)
    gencfg()
    rosbuild_add_executable(dynamic_reconfigure_node src/dynamic_reconfigure_node.cpp)
  • パッケージにrosmakeを行い、nodeをlaunchしてください。
    rosrun your_package dynamic_reconfigure_node

  1. taken directly from forearm camera configuration. (1)

Wiki: ja/dynamic_reconfigure/Tutorials/SettingUpDynamicReconfigureForANode (last edited 2013-03-18 06:15:56 by Yuto Inagaki)