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. |
はじめてのcfgファイルを書く
Description: このチュートリアルでは、dynamic_reconfigureでは欠かせないcfgファイルについて学びます。Tutorial Level: INTERMEDIATE
Next Tutorial: Setting up Dynamic Reconfigure for a Node(c++) Setting up Dynamic Reconfigure for a Node(python)
Contents
はじめに
rospy, roscpp, dynamic_reconfigureに依存するdynamic_tutorialsと呼ばれるパッケージを作ることからはじめましょう。 :
catkin_create_pkg dynamic_tutorials rospy roscpp dynamic_reconfigure
次に、パッケージのなかでcfgディレクトリを作成し、この中にすべてのcfgファイルを入れることになります。:
mkdir cfg
最後に、cfgファイルを作らなくてはならないので、エディタでTutorials.cfgを新規作成してください。
cfgファイル
以下をcgfファイルに追加してください。:
1 #!/usr/bin/env python
2 PACKAGE = "dynamic_tutorials"
3
4 from dynamic_reconfigure.parameter_generator_catkin import *
5
6 gen = ParameterGenerator()
7
8 gen.add("int_param", int_t, 0, "An Integer parameter", 50, 0, 100)
9 gen.add("double_param", double_t, 0, "A double parameter", .5, 0, 1)
10 gen.add("str_param", str_t, 0, "A string parameter", "Hello World")
11 gen.add("bool_param", bool_t, 0, "A Boolean parameter", True)
12
13 size_enum = gen.enum([ gen.const("Small", int_t, 0, "A small constant"),
14 gen.const("Medium", int_t, 1, "A medium constant"),
15 gen.const("Large", int_t, 2, "A large constant"),
16 gen.const("ExtraLarge", int_t, 3, "An extra large constant") ],
17 "An enum to set size")
18
19 gen.add("size", int_t, 0, "A size parameter which is edited via an enum", 1, 0, 3, edit_method=size_enum)
20
21 exit(gen.generate(PACKAGE, "dynamic_tutorials", "Tutorials"))
さて、一行一行コードを読み解いていきましょう。
この最初の行は、とてもシンプルとなっています。rosを初期化して、パラメータジェネレータをインポートしています。
8 gen.add("int_param", int_t, 0, "An Integer parameter", 50, 0, 100)
すでに、ジェネレータを取得したので、パラメータを定義することができます。add関数は、パラメータのリストにあたらしくパラメータを加えます。いくらかの引数をもちます。:
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
name - パラメータが蓄えられる場所の名前を特定する文字列
type - 蓄える値のタイプをセットします。int_t, double_t, str_t, bool_tのうちどれかです。
level - 後にdynamic reconfigureコールバックに渡されるビットマスク。コールバックが呼ばれたときに、全ての変更のあったパラメータの準位値の論理輪を取り、その返り値をコールバックに返します。
description - パラメータを記述する文字列
default - デフォルトの値を表記する
min - 最小値をセットします (オプションであり、文字列とboolには適用されません)
max - 最大値をセットします (オプションであり、文字列とboolには適用されません)
これらの行では、単に異なるタイプのパラメータをさらに定義しています。
13 size_enum = gen.enum([ gen.const("Small", int_t, 0, "A small constant"),
14 gen.const("Medium", int_t, 1, "A medium constant"),
15 gen.const("Large", int_t, 2, "A large constant"),
16 gen.const("ExtraLarge", int_t, 3, "An extra large constant") ],
17 "An enum to set size")
18
19 gen.add("size", int_t, 0, "A size parameter which is edited via an enum", 1, 0, 3, edit_method=size_enum)
ここで、enumによって値が決まっているintegerを定義します。これをするのに、gen.enumを呼び出し、それに、enumの表記によって続く定数のリストを渡します。enumはもうできたので、これをジェネレータに渡すことができます。これで今は、0や1ではなく、"Small"や"Medium"で値が設定できるようになりました。
21 exit(gen.generate(PACKAGE, "dynamic_tutorials", "Tutorials"))
最後の行は、単にジェネレータに必要なファイルを作るように言って、プログラムを終了しています。第2のパラメータは、これが実行されそうなnodeの名前(ドキュメントを作成するときのみ)で、だ3のパラメータは、作られたファイルが受ける名前の接頭辞です。(たとえば、c++には"<name>Config.h"、pythonには"<name>Config.py")
注意: 第3引数は、拡張子を除いてcfgファイル名と同じである必要があります。さもなければ、ライブラリが毎回のビルドで生成されることになり、それらを使うnodeも再コンパイルを要求されます。
cfgファイルを使う
このcfgファイルを使えるようにするには、実行可能にする必要があるので、以下のコマンドを使って、実行可能にしましょう。
chmod a+x cfg/Tutorials.cfg
次に、CMakeLists.txtに以下の行を追加する必要があります。 Fuerte とそれ以前:
#add dynamic reconfigure api find_package(catkin REQUIRED dynamic_reconfigure) generate_dynamic_reconfigure_options(relative_path_to_file1 relative_path_to_file2 ...) # make sure configure headers are build before node using them add_dependencies(example_node dynamic_tutorials_gencfg)
これは、パッケージがビルドされたときに、cfgを実行します。最後にやるべきことは、パッケージをビルドすることです。
Contents
はじめに
rospy roscpp dynamic_reconfigureに依存するdynamic_tutorialsと呼ばれるパッケージを作ることからはじめましょう。 :
roscreate-pkg dynamic_tutorials rospy roscpp dynamic_reconfigure
次に、パッケージのなかでcfgディレクトリを作成し、この中にすべてのcfgファイルを入れることになります。
mkdir cfg
最後に、cfgファイルを作らなくてはならないので、エディタでTutorials.cfgを新規作成してください。
cfg ファイル
以下をcgfファイルに追加してください。:
1 #!/usr/bin/env python
2 PACKAGE = "dynamic_tutorials"
3 # The following line should not be here for Groovy and above
4 import roslib;roslib.load_manifest(PACKAGE)
5
6 # For Groovy and above, the following line should be
7 # from dynamic_reconfigure.parameter_generator_catkin import *
8 from dynamic_reconfigure.parameter_generator import *
9
10 gen = ParameterGenerator()
11
12 gen.add("int_param", int_t, 0, "An Integer parameter", 50, 0, 100)
13 gen.add("double_param", double_t, 0, "A double parameter", .5, 0, 1)
14 gen.add("str_param", str_t, 0, "A string parameter", "Hello World")
15 gen.add("bool_param", bool_t, 0, "A Boolean parameter", True)
16
17 size_enum = gen.enum([ gen.const("Small", int_t, 0, "A small constant"),
18 gen.const("Medium", int_t, 1, "A medium constant"),
19 gen.const("Large", int_t, 2, "A large constant"),
20 gen.const("ExtraLarge", int_t, 3, "An extra large constant") ],
21 "An enum to set size")
22
23 gen.add("size", int_t, 0, "A size parameter which is edited via an enum", 1, 0, 3, edit_method=size_enum)
24
25 exit(gen.generate(PACKAGE, "dynamic_tutorials", "Tutorials"))
さて、一行一行コードを読み解いていきましょう。
1 #!/usr/bin/env python
2 PACKAGE = "dynamic_tutorials"
3 # The following line should not be here for Groovy and above
4 import roslib;roslib.load_manifest(PACKAGE)
5
6 # For Groovy and above, the following line should be
7 # from dynamic_reconfigure.parameter_generator_catkin import *
8 from dynamic_reconfigure.parameter_generator import *
この最初の行は、とてもシンプルとなっています。rosを初期化して、パラメータジェネレータをインポートしています。
10 gen = ParameterGenerator()
すでに、ジェネレータを取得したので、パラメータを定義することができます。add関数は、パラメータのリストにあたらしくパラメータを加えます。いくらかの引数をもちます。:
name - パラメータが蓄えられる場所の名前を特定する文字列
type - 蓄える値のタイプをセットします。int_t, double_t, str_t, bool_tのうちどれかです。
level - 後にdynamic reconfigureコールバックに渡されるビットマスク。コールバックが呼ばれたときに、全ての変更のあったパラメータの準位値の論理輪を取り、その返り値をコールバックに返します。
description - パラメータを記述する文字列
default - デフォルトの値を表記する
min - 最小値をセットします (オプションであり、文字列とboolには適用されません)
max - 最大値をセットします (オプションであり、文字列とboolには適用されません)
これらの行では、単に異なるタイプのパラメータをさらに定義しています。
16 size_enum = gen.enum([ gen.const("Small", int_t, 0, "A small constant"),
17 gen.const("Medium", int_t, 1, "A medium constant"),
18 gen.const("Large", int_t, 2, "A large constant"),
19 gen.const("ExtraLarge", int_t, 3, "An extra large constant") ],
20 "An enum to set size")
21
22 gen.add("size", int_t, 0, "A size parameter which is edited via an enum", 1, 0, 3, edit_method=size_enum)
ここで、enumによって値が決まっているintegerを定義します。これをするのに、gen.enumを呼び出し、それに、enumの表記によって続く定数のリストを渡します。enumはもうできたので、これをジェネレータに渡すことができます。これで今は、0や1ではなく、"Small"や"Medium"で値が設定できるようになりました。
25 exit(gen.generate(PACKAGE, "dynamic_tutorials", "Tutorials"))
最後の行は、単にジェネレータに必要なファイルを作るように言って、プログラムを終了しています。第2のパラメータは、これが実行されそうなnodeの名前(ドキュメントを作成するときのみ)で、だ3のパラメータは、作られたファイルが受ける名前の接頭辞です。(たとえば、c++には"<name>Config.h"、pythonには"<name>Config.py")
NOTE: 第3引数は、拡張子を除いてcfgファイル名と同じである必要があります。さもなければ、ライブラリが毎回のビルドで生成されることになり、それらを使うnodeも再コンパイルを要求されます。
cfgファイルを使う
このcfgファイルを使えるようにするには、実行可能にする必要があるので、以下のコマンドを使って、実行可能にしましょう。
chmod a+x cfg/Tutorials.cfg
次に、CMakeLists.txtに以下の行を追加する必要があります。 Fuerte とそれ以前:
#add dynamic reconfigure api rosbuild_find_ros_package(dynamic_reconfigure) include(${dynamic_reconfigure_PACKAGE_PATH}/cmake/cfgbuild.cmake) gencfg()
Groovy と それ以後:
#add dynamic reconfigure api find_package(catkin REQUIRED dynamic_reconfigure) generate_dynamic_reconfigure_options(relative_path_to_file1 relative_path_to_file2 ...)
これは、パッケージがビルドされたときに、cfgを実行します。最後にやるべきことは、パッケージをビルドすることです。