ROS2(dashing)のLaunchConfigurationとDeclareLaunchArgumentって何が違うねんというのがROS2本読んでもちっとも解らなかったので、結局ソース読んで調べてみたのででメモ。
LaunchDescription
launchファイルは最後にLaunchDescriptionを返すのだけど、そこに配列として「何を実行するのか?」の実行順序が記載されている。注意して欲しいのはこの関数の実行が終わったあと、適当なタイミングで実行されるという事です。この関数が呼ばれている最中ではないです。 その未来において使う「変数」がconfiguratonです。LaunchConfiguration オブジェクトでその変数を参照できるけどそのconfigurationを宣言するわけじゃないので注意(以下参照)。 その変数はLaunchContextというオブジェクトに格納されているのですが、launchファイルを書く限りではros2 launchコマンドを叩く度に作られるグローバル変数ぐらいに思っててOKっぽい。
実行順序
LaunchDescriptionに登録されたaction(Node だとかのlaunch.actionにあるものしか実行できない)は配列の順番に呼び出されていきます。IncludeLaunchDescriptionが存在する場合は、その中身を全部処理してから次を実行します。以下の「実行結果」の「A after include is 0」に着目してください。再帰プログラムに慣れてる人は0,1,2じゃなくて0,0,0になってるのに気持ち悪さを感じるかもしれません。Configurationは単なるグローバル変数なので、一番深いネストで書き換えられた値がそのまま浅いネストにも影響を与えています。
つまりIncludelaunchDescriptionをする人はInclude先でどんなConfigurationを使っているかを把握してないと自分のInclude後にConfigurationを破壊されてて意図通りに動かないリスクがあります。InculdeDescriptionはlaunchファイルの最後にやるほうが安全だし、余りlaunchConfigurationを文字定数のdefine代わりに多用するのは避けたがよいでしょう。本当に何かを変えるためのConfigです。
ちなみにInclude時にlaunch_argumentにパラメータを与える方式でやっても、configurationが上書きされてしまいます
LaunchConfigの文字列結合
LaunchConfigを文字列として結合したい時は、配列として結合したい文字を並べるだけです。LogInfo(msg=[])の部分をみてください。LogInfo等のlaunch.actionが引数にlaunch.substitutionsにあるものをとるときは、それぞれを評価して文字列に直して、実行結果を単純に結合してくれます。
PythonExpression
PythonExpressionはLaunchConfigと同じlaunch.substitutionsです。まさに実行時に評価されるという意味では解りやすい存在です。LaunchDescriptonに渡した配列のまさにその要素が実行されるときに、引数に与えられた文字列(substitutions)を評価した結果を文字列に返します。”0==0″とやれば文字列’true’が帰ってきます。以下のテスト用launchファイルでは、これを使うことでAを1づつ減算して再帰ループを実装しています。
Condition
LaunchDescriptionに渡すactionは必ず引数にconditionをもっているので、ここにtrue/falseを設定すれば良いです。現実的にLaunchConfiguration等のsubstitutionsの値を元に判断するので、IfConditionを使って、substitutionsからbool型へ変換する必要があります。
DeclareLaunchArgumentとLaunchConfiguration
ようやく本題のDeclareLaunchArgumentとLaunchConfigurationについてです。DeclareLaunchArgumentは「その名前の、configureが存在しなければ、default値でconfigureを作成する」というactionです。
actionなので、LaunchDescriptionの配列の中に書きます。
LaunchConfigurationは「configurationが存在すればその値を取得、なければdefault値を取得する」です。launchファイルにおけるグローバル変数的な存在である「configuration」をセットしないで、見るだけです注意が必要です。「実行結果」でも「B before Arg is 5」という風に最初はconfiguration「B」が存在しないので、LaunchConfigurationのdefaultである5がでていますが、「B after Arg is 10」の所では,「B」というconfigurationは存在しないのでDeclareLaunchArgumentによってdefault値10にセットされてしまい、二回目のBの評価の時10になっています(実行結果の「B after Arg is 10」)。
ちなみにLaunchArgumentとして登録しておくとros2 launch -s a.launch.pyとしたときにArgument 一覧表示できるので、設定パラメータでON/OFFするという普通の使い方をするならArgumentで登録しておいた方が良い。Argumentを使わずにLaunchConfigだけ使うシチュエーションは、今回の再帰呼び出しみたいな例のように、Include先と情報を共有したいときぐらいかな?
テスト用Launchファイル
実行結果
[INFO] [launch]: All log files can be found below /home/akira/.ros/log/2020-05-23-17-37-35-296662-MintVM-23167
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [launch.user]: B before Arg is 5
[INFO] [launch.user]: B after Arg is 10
[INFO] [launch.user]: ROS_Distributon is dashing
[INFO] [launch.user]: A is 2
[INFO] [launch.user]: B before Arg is 10
[INFO] [launch.user]: B after Arg is 10
[INFO] [launch.user]: A is 1
[INFO] [launch.user]: B before Arg is 10
[INFO] [launch.user]: B after Arg is 10
[INFO] [launch.user]: A is 0
[INFO] [launch.user]: A after incldue is 0
[INFO] [launch.user]: A after incldue is 0
[INFO] [launch.user]: A after incldue is 0