Note: This tutorials assumes that you have completed Setting up Dynamic Reconfigure for a Node(python) or (c++).
(!) 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.

Dynamic Reconfigure Pythonクライアントを使う。

Description: このチュートリアルでは、dynamic_reconfigureクライアントの使い方と基本的なステップをカバーします。

Tutorial Level:

コード

再設定できるnodeがあるので、今度は、再設定をするnodeを書かなくてはなりません。client.pyと呼ばれるファイルをnodesディレクトリに作成し、以下のコードを追加してください。:

   1 #!/usr/bin/env python
   2 
   3 PACKAGE = 'dynamic_tutorials'
   4 import roslib;roslib.load_manifest(PACKAGE)
   5 import rospy
   6 
   7 import dynamic_reconfigure.client
   8 
   9 def callback(config):
  10     rospy.loginfo("Config set to {int_param}, {double_param}, {str_param}, {bool_param}, {size}".format(**config))
  11 
  12 if __name__ == "__main__":
  13     rospy.init_node("dynamic_client")
  14 
  15     client = dynamic_reconfigure.client.Client("dynamic_tutorials", timeout=30, config_callback=callback)
  16 
  17     r = rospy.Rate(0.1)
  18     x = 0
  19     b = False 
  20     while not rospy.is_shutdown():
  21         x = x+1
  22         if x>10:
  23             x=0
  24         b = not b
  25         client.update_configuration({"int_param":x, "double_param":(1/x+1), "str_param":str(rospy.get_rostime()), "bool_param":b, "size":1})
  26         r.sleep()

コード解説

dynamic reconfigure クライアントを書くのはとても簡単です。:

   1 #!/usr/bin/env python
   2 
   3 PACKAGE = 'dynamic_tutorials'
   4 import roslib;roslib.load_manifest(PACKAGE)
   5 import rospy
   6 
   7 import dynamic_reconfigure.client

ROSを初期化し、dynamic_reconfigure.clientをインポートします。

   1 def callback(config):
   2     rospy.loginfo("Config set to {int_param}, {double_param}, {str_param}, {bool_param}, {size}".format(**config))

そしたら、サーバによって返される設定を出力するコールバックを定義します。このコールバックとサーバには、主な違いが2つあります。一つは更新された設定オブジェクトを返す必要がないこと、と"level"引数がないことです。このコールバックはオプションです。

   1 if __name__ == "__main__":
   2     rospy.init_node("dynamic_client")
   3 
   4     client = dynamic_reconfigure.client.Client("dynamic_tutorials", timeout=30, config_callback=callback)
   5 
   6     r = rospy.Rate(0.1)
   7     x = 0
   8     b = False 
   9     while not rospy.is_shutdown():
  10         x = x+1
  11         if x>10:
  12             x=0
  13         b = not b
  14         client.update_configuration({"int_param":x, "double_param":(1/x+1), "str_param":str(rospy.get_rostime()), "bool_param":b, "size":1})
  15         r.sleep()

最後に、ROSとクライアントの初期化をしています。メインループは10秒に一度実行され、クライアントのupdate_configurationを毎回呼ぶだけです。すべての設定を使わなければいけないわけではなく、 パラメータの内の一つだけを辞書式配列に渡すことができることも注意してください。

実行しましょう

また、実行可能にしましょう。: chmod +x nodes/client.py coreとサーバノードをlaunchし、新しいクライアントnodeも同様にしくてださい。すべてうまくいったなら、クライアントとサーバは、10秒ごとに合致する設定を表示し始めるはずです。

Wiki: ja/dynamic_reconfigure/Tutorials/UsingTheDynamicReconfigurePythonClient (last edited 2013-03-14 14:47:22 by Yuto Inagaki)