環境
この記事は以下の環境で動いています。
項目 | 値 |
---|---|
CPU | Core i5-8250U |
Ubuntu | 20.04 |
ROS | Noetic |
インストールについてはROS講座02 インストールを参照してください。
またこの記事のプログラムはgithubにアップロードされています。ROS講座11 gitリポジトリを参照してください。
#概要
launchファイルには他にも機能があります。前回で解説していない4つの機能を紹介します。
nodeのrename
以下にROS講座04で製作したsimple1.launchを示します。
<launch>
<node name="basic_simple_talker" pkg="basic_lecture" type="basic_simple_talker" />
<node name="basic_simple_listener" pkg="basic_lecture" type="basic_simple_listener" output="screen"/>
</launch>
これを実行してrosnode list
を実行すると以下のような2つのROSノードが起動されていることが分かります。
basic_simple_talker
basic_simple_listener
上記の例では実行されているノード名は元のROSノード名と同じになっています。
しかし、同じROSノードを複数立ち上げたい場合があります。
<launch>
<node name="talker" pkg="basic_lecture" type="basic_simple_talker" />
<node name="listener1" pkg="basic_lecture" type="basic_simple_listener" output="screen"/>
<node name="listener2" pkg="basic_lecture" type="basic_simple_listener" output="screen"/>
</launch>
今度はrqt_graph
を実行してみましょう。GUIの画面が立ち上がります。以下のように名前が違う2つのlistenerのROSノードが起動していることが分かります。ちなみに上記のsimple_rename.launchを改変して、同じnameを指定するとエラーが起きます。
remap
ROSトピックの名前を変更するツールです。
<launch>
<node name="basic_simple_talker" pkg="basic_lecture" type="basic_simple_talker" >
<remap from="chatter" to="content"/>
</node>
<node name="basic_simple_listener" pkg="basic_lecture" type="basic_simple_listener" output="screen">
<remap from="chatter" to="content"/>
</node>
</launch>
またまたrqt_graph
を見てみましょう以下のようにtalkerとlistenerの間でやり取りされているROSトピック名がchatter
からcontent
に変わっています。
argとif,unless
roslaunchを起動するときにオプション引数を使えます。<arg>
タブで変数を定義できます。default属性で初期値を設定できます。後述のターミナルからの実行時に値を指定しない初期値が適用されます。逆にdefaultこの属性が書いていなく、roslaunch起動時に値を指定しないとエラーになります。
この<arg>
で指定できる値の型は
- 論理型(bool)
- 数値型(double)
- 文字列型(string)
の3種類です。値を"true"、"false"と指定すると論理型になります(大文字、小文字を問わないので"TRUE"、"False"、"TruE"、"falSe"も可)。数字なら(1、3.1415、-12345)だと数字型に、他は文字列になります。
値を元にROSノードを起動するかしないかを切り替えることができます。このためには<gorup>
タグを使います。<group>
タグそれ自体はxmlを細かくまとめるだけで特に深い意味はありません。しかしif属性の値が論理型trueだと実行、falseだと実行されません。以下のようなlaunchファイルを作成します。
単純な条件分岐
<launch>
<arg name="mode" default="true"/>
<group if="$(arg mode)">
<node name="basic_simple_talker" pkg="basic_lecture" type="basic_simple_talker" />
<node name="basic_simple_listener" pkg="basic_lecture" type="basic_simple_listener" output="screen" />
</group>
</launch>
以下のように書くとmodeにはdefaultのtrueが入力されてROSノードは実行されます。
roslaunch basic_lecture launch_arg1.launch
以下のように値を上書きすると、modeにfalseが入ってROSノードは実行されません。
roslaunch basic_lecture launch_arg1.launch mode:=false
launchファイルの<group if="$(arg mode)">
を<group unless="$(arg mode)">
に書き換えると動作は逆になります。
evalを使った条件分岐
もっと複雑な条件分岐をさせたい場合はevalを使います。evalコマンドを使うとpythonのeval()を呼び出すことができます。これで複雑な条件分岐を行えます。例えば以下のようにlaunchを記述した場合は変数modeの値ががmode0かmode1だった時に実行されます。
<launch>
<arg name="mode" default="mode0"/>
<group if="$(eval mode=='mode0' or mode=='mode1')">
<node name="basic_simple_talker" pkg="basic_lecture" type="basic_simple_talker" />
<node name="basic_simple_listener" pkg="basic_lecture" type="basic_simple_listener" output="screen" />
</group>
</launch>
roslaunch basic_lecture launch_arg2.launch mode:=mode0
roslaunch basic_lecture launch_arg2.launch mode:=mode1
roslaunch basic_lecture launch_arg2.launch mode:=mode2
param
paramは起動時にROSノードに値を渡すことができる機能です。roslaunchで渡す値を記述します。ROSノードを若干書き換える必要があります。
#include <ros/ros.h>
#include <std_msgs/String.h>
#include <string>
int main(int argc, char** argv)
{
ros::init(argc, argv, "basic_param_talker");
ros::NodeHandle nh;
ros::NodeHandle pnh("~");
ros::Publisher chatter_pub = nh.advertise<std_msgs::String>("chatter", 10);
std::string msg_chatter = "hello world!";
pnh.getParam("content", msg_chatter);
ros::Rate loop_rate(10);
while (ros::ok())
{
std_msgs::String msg;
msg.data = msg_chatter;
ROS_INFO("%s", msg.data.c_str());
chatter_pub.publish(msg);
ros::spinOnce();
loop_rate.sleep();
}
return 0;
}
まず違うのは8行目、今までになかったros::NodeHandle pnh("~");
は値をroslaunchから受け取るのに必要な物です。10行目に値を受け取る変数を定義します。11行目のpn.getParam("content",msg_chatter);
はcontentという名前を受けて、その値をmsg_chatterに代入するという関数です。
ちなみにcontentという名前の値が存在しない場合は代入動作は行われず、値は変わりません。このためにmsg_chatterの定義時に初期値を入れることをお勧めします。
launchは以下のように書きます。
<launch>
<node name="basic_param_talker" pkg="basic_lecture" type="basic_param_talker" >
<param name="content" value="alternative hello"/>
</node>
<node name="basic_simple_listener" pkg="basic_lecture" type="basic_simple_listener" output="screen"/>
</launch>
以下のコマンドで実行します。
roslaunch basic_lecture launch_param.launch
すると以下のようにlistenerが受信する値が変わっているのが見えます。
[ INFO] [1554469390.298268118]: I heard: [alternative hello]
[ INFO] [1554469390.399493784]: I heard: [alternative hello]
[ INFO] [1554469390.499161718]: I heard: [alternative hello]
[ INFO] [1554469390.598687837]: I heard: [alternative hello]