環境
この記事は以下の環境で動いています。
項目 | 値 |
---|---|
CPU | Core i5-8250U |
Ubuntu | 20.04 |
ROS | Noetic |
インストールについてはROS講座02 インストールを参照してください。
またこの記事のプログラムはgithubにアップロードされています。ROS講座11 gitリポジトリを参照してください。
概要
rosparamはROSでパラーメーターを取り扱う仕組みです。rosparamは全てrosmasterプロセスで一元的に管理されます。
paramの基本型としてはstr、int、double、boolがあります。またこれらを組み合わせたリストや辞書を扱うこともできます。
本当は実行時に動的に値を変えることができるのですが、そのようなことをしたい場合はrostopicやdynamic_reconfigureで代用するのが一般的で、rosparamは主に起動時パラメーターとして使用されます。今回はlaunchでrosparamを定義して、rosノードで読み込む方法を説明します。
ソースコード
roslaunch
roslaunchでrosparamを設定するサンプルです。roslaunchでrosparamを設定するためのタグとして<param>
タグと<rosparam>
タグがあります(おそらく歴史的な経緯から2種類あるのでしょう)。それぞれでの記法を解説します。
<launch>
<node name="node1" pkg="adv_lecture" type="adv_param1_display" output="screen">
<param name="int_param" value="1"/>
</node>
<param name="node2/int_param" value="2"/>
<node name="node2" pkg="adv_lecture" type="adv_param1_display" output="screen"/>
<rosparam command="load" file="$(find adv_lecture)/config/param1_config.yaml"/>
<node name="node3" pkg="adv_lecture" type="adv_param1_display" output="screen"/>
<rosparam>
node4:
int_param: 4
</rosparam>
<node name="node4" pkg="adv_lecture" type="adv_param1_display" output="screen"/>
</launch>
paramタグの使い方
rosparamを設定するのでよく使うのが<param>
タグです。記述する場所によってrosparamのネームスペースが異なります。
-
<node>
タグの中で記述するとその/node_name/param_name
という名前でrosparamが設定されます。 - また
<launch>
タグの直下に置くと/param_name
というそのままの名前でrosparamが設定されます。 -
type
属性でrosparamの型を決められますが、整数はint、小数があるとdouble、true/falseはbool、その他はstringに推論されます。
rosparamタグの使い方
多数のパラメーターを設定する場面で使われるのが<rosparam>
タグです。
-
<rosparam command="load" file="filename.yaml"/>
とするとyamlで記述されたfilenameの中身をそのままrosparamとして設定します。ns
属性をつけると設定するパラメーターすべてにネームスペースをつけることができます。 -
<rosparam>~~~~~</rosparam>
と書くとファイル読み込みではなく、launch上にyamlのフォーマットで読み込むrosparamを記述することができます。
特にリストのrosparamは<rosparam>
タグでないと記述できないのでこのような場合は必須です。<rosparam>list_param: [1, 2, 3, 4]</rosparam>
と記述します。
C++(rosノード)
rosparamを読んでprintするだけのノードです。
#include <ros/ros.h>
int main(int argc, char** argv)
{
ros::init(argc, argv, "param_sample");
ros::NodeHandle nh;
ros::NodeHandle pnh("~");
int param_data=0;
pnh.getParam("int_param", param_data);
ROS_INFO("[%s] param:%i", ros::this_node::getName().c_str(), param_data);
ros::spin();
return 0;
}
- rosparamの読出しをする場合は2つ
ros::NodeHandle
をインスタンス化するのが一般的です。ros::NodeHandle pnh("~")
と書くことで、ROSノードの名前空間にアクセスできます。 -
pnh.getParam("int_param", param_data);
でrosparamを読みだせます。このように書くと/(ノード名)/int_param
という名前のrosparamを読み込みます。該当のrosparamがない場合は変数への書き込みは行われません。 - rosparamを読み込む変数の型は
bool
、int
、double
、std::string
が使えます。 -
getParam
は呼び出すごとにパラメーターサーバー(=roscore)にパラメーターを問い合わせます。このために毎回1msほどの待ちが発生してしまいます。代わりにgetParamCached
を使うことでローカルにあるキャッシュの値を読むので待ちが発生しません。キャッシュも裏で自動的に更新されるので、厳密に最新が欲しい場合以外はgetParamCached
を使うほうが良いでしょう。
ビルド
cd ~/catkin_ws
catkin_make
実行
各ターミナルごとに実行前にsource ~/catkin_ws/devel/setup.bash
を実行する必要があります。
roslaunch adv_lecture rosparam1.launch
以下のように表示されるはずです。各ノードで別々のrosparamが読み込まれていることが分かります。
[ INFO] [1588415110.016945722]: [/node1] param:1
[ INFO] [1588415110.036019346]: [/node2] param:2
[ INFO] [1588415110.043859978]: [/node3] param:3
[ INFO] [1588415110.045789058]: [/node4] param:4
rosparamコマンド
rosparam
コマンドを使うことで現在のrosparamを読んだり、書き込んだりできます。
rosparam list
rosparam list
を実行すると設定されているrosparamの一覧を見れます。上記のroslaunch adv_lecture rosparam1.launch
を実行しているときにこのコマンドを実行すると以下のように見えます。
/node1/int_param
/node2/int_param
/node3/int_param
/node4/int_param
/rosdistro
/roslaunch/uris/host_ubuntu__42045
/rosversion
/run_id
launchで指定したrosparamが存在することが確認できました。
rosparam get
特定のrosparamの値を見ることができます。rosparam get /node1/int_param
と使います。またrosparam get /node1
とすると/node1
名前空間以下のすべてのrosparamの値を見ることができます。
rosparam set
rosparam set /node1/int_param 12
の様にしてパラメーターをセットできます。