(!) 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.

大きなプロジェクトにおける roslaunch の tips

Description: このチュートリアルは大きなプロジェクトにおける roslaunch ファイルの書き方に関する tips を紹介します.主に異なる状況でできるかぎり再利用できるように launch ファイルを組むことに主眼をおきます.ケーススタディに 2dnav_pr2 のパッケージを使います.

Tutorial Level: INTERMEDIATE

Next Tutorial: Roslaunch Nodes in Valgrind or GDB

導入

ロボットの上で動いている大きなアプリケーションは内部で繋がっている nodes をいくつか内包しているのが典型的です.各 node はたくさんの parameters を持っています.2d ナビゲーションが良い例です.2dnav_pr2 アプリケーションは move_base, localization, ground plane filtering, base controller, map server といった node で構成されています.これらの node に影響を与える ROS のパラメータは全部合わせると数百個になります.最終的に,効率良くするのためには ground plane filtering はチルトレーザーが載っているマシンで実行されるべきだ,といった束縛条件があります.

roslaunch ファイルはこういったことをまとめてくれます.実行中のロボットがあるとして, 2dnav_pr2 パッケージの 2dnav_pr2.launch を launch すると,そのロボットをナビゲーションするために必要なものをすべて立ち上げてくれます.このチュートリアルでは この launch ファイルとその特徴を見ていきます.

roslaunch ファイルはできるだけ再利用可能性が高いことが望まれます.今回の場合では,構造が同じロボット同士で launch ファイルを全く変更せずに使いまわすことができます.ほんの少し変更することでロボットからシミュレータへの移行ですら可能となります.このようにするために launch ファイルがどのように構成されているか見ていきましょう.

トップレベルの機構

これがトップレベルの launch ファイルです( "rospack find 2dnav_pr2/move_base/2dnav_pr2.launch" で行けます).

<launch>
  <group name="wg">
    <include file="$(find pr2_alpha)/$(env ROBOT).machine" />
    <include file="$(find 2dnav_pr2)/config/new_amcl_node.xml" />
    <include file="$(find 2dnav_pr2)/config/base_odom_teleop.xml" />
    <include file="$(find 2dnav_pr2)/config/lasers_and_filters.xml" />
    <include file="$(find 2dnav_pr2)/config/map_server.xml" />
    <include file="$(find 2dnav_pr2)/config/ground_plane.xml" />

    <!-- The navigation stack and associated parameters -->
    <include file="$(find 2dnav_pr2)/move_base/move_base.xml" />
  </group>
</launch>

このファイルは他のファイルをまとめてインクルードしています.インクルードされたそれぞれのファイルは node と parameter を含み(インクルードをネストすることも可能です), localization や sensor processing や path planning といったシステムの一部に関連しています.

Design tip: トップレベルの launch ファイルは短くあるべきで,また,当該アプリのサブコンポーネントに応じた別のファイルのインクルード文と一般的には変更の加えられた ROS parameter で構成されるべきでもあります.

あとで分かることになりますが,こうすることでシステムの一部を取り替えることが簡単になります.

PR2 で実行するには, core を起動し, pr2_alpha パッケージの pre.launch のようなロボット特有の launch ファイル(以下, robot launch ファイル)を立ち上げてから, 2dnav_pr2.launch を launch することが必要です.launch ファイルを別々に立ち上げなくとも, robot launch ファイルをインクルードすることも可能です.次のようなトレードオフがあります:

  • 長所:「新しいターミナルを開いて roslaunch をする」というステップが一つ減る
  • 短所:robot launch ファイルを launch すると,およそ一分間のキャリブレーションが始まります.もし 2dnav_pr2 launch ファイルが robot launch ファイルをインクルードしているならば, Ctrl-C で roslaunch を kill し,立ち上げなおす度にキャリブレーションが始まります.
  • 短所:2d navigation の node には,起動する前にキャリブレーションが終わっている必要がある node もあります.roslaunch は node が立ち上がる順番やタイミングをコントロールする方法を意図的に提供していません.理想的な解決策は,キャリブレーションが済むまで待つことで node をうまく動かすことですが,それを待つのならば, launch ファイルを2つに分け,まず robot launch ファイルを立ち上げ,キャリブレーションが終わるまで待ち, 2dnav を立ち上げることもできます.

このように launch ファイルを複数に分けるべきか否かについて普遍的な回答はありません.ここでは2つに分けて進めていきます.

Design tip: トップレベルの launch ファイルをアプリケーションが何個必要とするか決めるときはこのトレードオフを気にして下さい.

マシンのタグと環境変数

負荷分散や帯域幅管理のために,どの node がどのマシンで走らせているかを管理したいというのがあります.例えば, amcl node を base laser と同じマシンで走らせたいというのがあります.それと同時に,再利用性の観点から, roslaunch ファイルにマシン名を直打ちすることはしたくありません.roslaunch はこの問題を machine tag を使って対処しています.

最初にインクルードするのものは

<include file="$(find pr2_alpha)/$(env ROBOT).machine" />

このファイルについて最初に注意すべきことは環境変数 ROBOT の値を利用するために,env substitution argument を使うという事です. 例えば roslaunch の前に

export ROBOT=pre

とすると pre.machine がインクルードされます.

Design tip: launch ファイルが環境変数に依存するよう env substitution argument を使う.

次にマシンファイルを見てみましょう.例として pr2_alpha パッケージにある pre.machine を見て下さい.

<launch>
  <machine name="c1" address="pre1" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" default="true" />
  <machine name="c2" address="pre2" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
</launch>

このファイルは論理的なマシン名 ("c1" や "c2") と実際のホスト名 ("pre1" や "pre2") を対応付けしています.また,適切な ssh 権限があるときは,あなたがどういうユーザでログインするかも管理できます.

一旦対応付けが定義されると, node を launch するときに使用出来るようになります.例えば, 2dnav_pr2 パッケージでインクルードされている config/new_amcl_node.xml には次のような行があります.

<node pkg="amcl" type="amcl" name="amcl" machine="c1">

これにより amcl node は論理マシン名が c1 であるマシン上で走ることができます(他の launch ファイルを見てみると,ほとんどのレーザーセンサの処理はこのマシン上に置かれているのが分かります).

新しいロボットで実行するとき,例えば prf で実行するときは,環境変数 ROBOT を変えればよいだけです.そうすれば対応するマシンファイル (pr2_alpha パッケージの prf.machine) が読み込まれます.環境変数 ROBOT を sim にすれば,シミュレータにも使うことができます. pr2_alpha パッケージの sim.machine ファイルを見ると,論理的なマシン名がすべて localhost になっていることが分かります.

Design tip: 負荷分散やどの node を同じマシンで走らせるかの管理にはマシンのタグを使い,再利用性を高めるためにマシンファイル名には環境変数に依存させましょう.

パラメータ,名前空間, yaml ファイル

インクルードファイル move_base.xml を見てみましょう.以下がそのファイルの一部です:

<node pkg="move_base" type="move_base" name="move_base" machine="c2">
  <remap from="odom" to="pr2_base_odometry/odom" />
  <param name="controller_frequency" value="10.0" />
  <param name="footprint_padding" value="0.015" />
  <param name="controller_patience" value="15.0" />
  <param name="clearing_radius" value="0.59" />
  <rosparam file="$(find 2dnav_pr2)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
  <rosparam file="$(find 2dnav_pr2)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
  <rosparam file="$(find 2dnav_pr2)/move_base/local_costmap_params.yaml" command="load" />
  <rosparam file="$(find 2dnav_pr2)/move_base/global_costmap_params.yaml" command="load" />
  <rosparam file="$(find 2dnav_pr2)/move_base/navfn_params.yaml" command="load" />
  <rosparam file="$(find 2dnav_pr2)/move_base/base_local_planner_params.yaml" command="load" />
</node>

上記のコードでは move_base の node を立ち上げています.最初の要素は remapping です. move_baseは "odom" という topic からオドメトリを受け取るようにデザインされています. pr2 の場合,オドメトリは pr2_base_odometry という topic にパブリッシュされるので, "odom" を再配置します.

Design tip: 与えられた情報の型が,異なる状況で異なる topic に対して publish されるときは topic の remapping をしましょう.

次にきているのが <param> のタグ郡です.これらのタグは全て node 要素の中であることに注意しておいてください.それ故,それらは private parameters となります.例えば一番最初のタグでは move_base/controller_frequency を 10.0 にセットしています.

<param> 要素の後には <rosparam> の要素がいくつかあります.これらは yaml (複雑なデータ構造も可能な人間が読みやすくなっているフォーマット) 内のパラメータデータを読み込みます.以下に、上で一番初めに <rosparam> に読み込まれている costmap_common_params.yaml ファイルの一部を載せます:

raytrace_range: 3.0
footprint: [[-0.325, -0.325], [-0.325, 0.325], [0.325, 0.325], [0.46, 0.0], [0.325, -0.325]]
inflation_radius: 0.55

# BEGIN VOXEL STUFF
observation_sources: base_scan_marking base_scan tilt_scan ground_object_cloud

base_scan_marking: {sensor_frame: base_laser, topic: /base_scan_marking, data_type: PointCloud, expected_update_rate: 0.2,
  observation_persistence: 0.0, marking: true, clearing: false, min_obstacle_height: 0.08, max_obstacle_height: 2.0}

yaml がベクトルのような表記を表すことができるのが分かります (footprint など).また,ネストされた namespace の中にパラメータをいくつか入れることもできます.例えば, base_scan_marking/sensor_framebase_laser にセットされています.これらの名前空間は yaml ファイル自身の名前空間,すなわち rosparam 要素の ns attribute によって global_costmap として宣言された名前空間に関係していることに注意して下さい.今回, node 要素の中に rosparam が含まれているので,パラメータの完全な識別名は /move_base/global_costmap/base_scan_marking/sensor_frame になります.

move_base.xml の次の行は以下の通りです:

<rosparam file="$(find 2dnav_pr2)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />

一行前と全く同じ yaml ファイルをインクルードしています.異なる名前空間に属するという違いだけです (名前空間 local_costmap は軌道のコントロールのためであり,一方で名前空間 global_costmap は global navigation planner に影響します).これはすべての値を打ち直すより大分楽になります.

その次の行は以下の通りです:

<rosparam file="$(find 2dnav_pr2)/move_base/local_costmap_params.yaml" command="load"/>

これまでのものと違い,この要素には ns attiribute が存在しません.したがって,この yaml ファイルの名前空間は親の名前空間である /move_base となります.しかし,この yaml ファイル自身の最初の数行を見て下さい:

local_costmap:
  #Independent settings for the local costmap
  publish_voxel_map: true
  global_frame: odom_combined
  robot_base_frame: base_link

このように,結局パラメータは /move_base/local_costmap の名前空間にあったとわかります.

Design tip: yaml ファイルは複雑なタイプのパラメータ,ネストされた名前空間のパラメータ,複数箇所で同じパラメータの値を再利用することを可能にしています.

launch ファイルの再利用

上記の tips の多くの動機は,異なる環境で簡単に launch ファイルを再利用できるようにすることでした.既に例として,env substitute argument を用いることで launch ファイル自体は一切変えずに振る舞いを修正できる,というところを見ました.しかし,これでは不便であったり不可能であったりする状況もあります. pr2_2dnav_gazebo パッケージを見てみましょう.これは 2d ナビゲーションアプリを含んでいますが, Gazebo simulator で使うためです.ナビゲーションのために変更された点は,我々が使う Gazebo の環境が異なる static なマップに基づいているために map_server の node が異なる引数で読み込まれなくてはならなかった,ということだけです.他の env substitution を使うこともできましたが,そうすると roslaunch できるようにするだけのために多くの環境変数をユーザーに設定させることになってしまいます.代わりに, 2dnav gazebo は以下に紹介している 2dnav-stack-amcl.launch と呼ばれる自身のトップレベルの launch ファイルを含んでいます(見易さのために少し修正してあります):

<launch>
  <include file="$(find pr2_alpha)/sim.machine" />
  <include file="$(find 2dnav_pr2)/config/new_amcl_node.xml" />
  <include file="$(find 2dnav_pr2)/config/base_odom_teleop.xml" />
  <include file="$(find 2dnav_pr2)/config/lasers_and_filters.xml" />
  <node name="map_server" pkg="map_server" type="map_server" args="$(find gazebo_worlds)/Media/materials/textures/map3.png 0.1" respawn="true" machine="c1" />
  <include file="$(find 2dnav_pr2)/config/ground_plane.xml" />
  <!-- The naviagtion stack and associated parameters -->
  <include file="$(find 2dnav_pr2)/move_base/move_base.xml" />
</launch>

最初の違いは,シミュレータ上であることが分かっているため, substitution argument を使わず sim.machine ファイルを使っている点です. 次に

<include file="$(find 2dnav_pr2)/config/map_server.xml" />

<node name="map_server" pkg="map_server" type="map_server" args="$(find gazebo_worlds)/Media/materials/textures/map3.png 0.1" respawn="true" machine="c1" />

に置き換わっています.置き換わる前でインクルードされているファイルには置き換えた後の場合と同様, node を定義しているだけですが, map ファイルが異なっています.

Design tip: アプリケーションの"トップレベル"の様相を修正するにはトップレベルの launch ファイルをコピーし,必要なところを変えましょう.

パラメータの上書き

上記のテクニックは時折不便になります.例えば, 2dnav_pr2 を使いたいけれども,変えたい部分は local costmap のパラメータを 0.5 に変えたいだけであるとします.直に local_costmap_params.yaml を変更するのがとりあえずの最も簡単な修正ですが,それだと修正したファイルを元に戻せません.代わりに local_costmap_params.yaml のコピーを作って修正することもできます.そうしたなら,そのコピーした yaml ファイルをインクルードするように move_base.xml を変えなくてはなりません.そうすると,次にそれをインクルードしている 2dnav_pr2.launch も修正しなくてはならなくなります.時間の無駄になりかねませんし,もしバージョン管理システムを使っているなら,オリジナルファイルへの変更は見ることはないでしょう.他の手として, move_base/local_costmap/resolution のパラメータはトップレベルのファイルである 2dnav_pr2.launch に定義されているので,その launch ファイルを再構成し、そのファイルに対してのみ変更したバージョンを作る方法が考えられます.もし予めどのパラメータを変えれば良いか分かっているのなら,これはよい選択でしょう.

他の選択肢としては roslaunch の上書きをすることです: パラメータは順番にセットされていきます (include の後に処理されます).そのため,さらにトップレベルとなるファイルを作ることで上書きすることができます:

<launch>
<include file="$(find 2dnav_pr2)/move_base/2dnav_pr2.launch" />
<param name="move_base/local_costmap/resolution" value="0.5"/>
</launch>

主な欠点はこの手法を使ったときに可読性が悪くなることです: roslaunch でパラメータとして設定した本当の値を知るためには, roslaunch で立ち上げたインクルードファイルを辿らなくてはなりません.しかし,こうすることで,たくさんファイルのコピーをしなくて済みます.

Design tip: 変更を加えたくない木構造の launch ファイルで,深くネストされている値を変更するためには roslaunch のパラメータを上書きしましょう.

roslaunch 変数

C Turtleの時点で, roslaunch は一部の launch ファイルの引数の値を調整することができるようになっているタグとともに argument substitution の特徴を持っています.これは,オリジナルの launch ファイルに変更を加えてどの引数が変更可能かを特定しなくてはならなくなるという犠牲を払ってパラメータを上書きしたり上記のテクニックで launch ファイルを再利用したりすることに比べて,構造化することがより汎用的で簡単な方法になりえます. roslaunch XML documentation を参考にして下さい.

Design tip: もしオリジナルの launch ファイルを修正できるなら,パラメータの上書きや roslaunch ファイルのコピーよりも roslaunch 変数を用いる方が好まれます.

Wiki: ja/roslaunch/Tutorials/Roslaunch tips for larger projects (last edited 2020-07-19 05:15:51 by YumaHiramatsu)