Python launchファイルでの話
概要
- ノード/launchファイルを呼び出す際の
condition引数に以下のインスタンスを指定するlaunch.conditions.IflessConditionlaunch.conditions.UnlessCondition
- 上記クラスは以下のように実体化する
IflessCondition(expression) UnlessCondition(expression) -
expressionには最終的に文字列としてtrueとかfalseとかになるようなものを指定する。詳細は、判定についてを参照のこと- OK例
IflessCondition("true") IflessCondition(str(True)) # launchファイルの引数を使った条件を書きたい場合はlaunch_ros.substitutions.PythonExpressionを使うと良い IflessCondition(PythonExpression(["1 == 1"])) - NG例
IflessCondition(True) # エラー IflessCondition("1 == 1") # エラー
- OK例
- 名前からわかるとおり以下のように使い分ける
-
IflessCondition(expression):expressionがtrueの場合に呼び出したい -
UnlessCondition(expression):expressionがfalseの場合に呼び出したい
-
ソースコード
最初のコードを見れば大丈夫だと思う(参考に、呼び出しているlaunchファイル、ノードのコードも載せている)
test_conditionパッケージ配下に作成している
実行有無を制御しているlaunchファイル
引数conditionで起動するノード、launchファイルを制御するようになっている
具体的には以下のノード、launchファイルを指定している
- 常に起動するノード
-
condition = trueのときに起動するノード (IfConditionを指定) -
condition = falseのときに起動するノード (UnlessConditionを指定) -
condition = trueのときに呼び出されるlaunchファイル (IfConditionを指定) -
condition = falseのときに呼び出されるlaunchファイル (UnlessConditionを指定)
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
# 実行可否を指定するためのパッケージ
from launch.conditions import IfCondition, UnlessCondition
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
def generate_launch_description():
# 実行可否を指定するための引数を定義
condition_argument = DeclareLaunchArgument("condition", default_value="true")
condition = LaunchConfiguration('condition')
return LaunchDescription([
condition_argument,
Node(
package='test_condition',
executable='test_condition',
name='node_no_condition',
output='screen',
parameters=[
{'print_message': 'Node w/ no condition!'}
]
),
# conditionがtrueの場合に起動するノード
Node(
package='test_condition',
executable='test_condition',
name='node_if_condition',
output='screen',
parameters=[
{'print_message': 'Node w/ IfCondition!'}
],
condition=IfCondition(condition) # ここでconditionがtrueのときに起動するように指定
),
# conditionがfalseの場合に起動するノード
Node(
package='test_condition',
executable='test_condition',
name='node_unless_condition',
output='screen',
parameters=[
{'print_message': 'Node w/ UnlessCondition!'}
],
condition=UnlessCondition(condition) # ここでconditionがfalseのときに起動するように指定
),
# conditionがtrueの場合に呼び出されるlaunchファイル
IncludeLaunchDescription(
PathJoinSubstitution(
[FindPackageShare("test_condition"), "launch", "base.launch.py"]
),
launch_arguments=[
('print_message', 'Launch file w/ IfCondition!')
],
condition=IfCondition(condition) # ここでconditionがtrueのときに呼び出すように指定
),
# conditionがfalseの場合に呼び出されるlaunchファイル
IncludeLaunchDescription(
PathJoinSubstitution(
[FindPackageShare("test_condition"), "launch", "base.launch.py"]
),
launch_arguments=[
('print_message', 'Launch file w/ UnlessCondition!')
],
condition=UnlessCondition(condition) # ここでconditionがfalseのときに呼び出すように指定
)
])
呼び出しているノード(参考)
パラメータprint_messageで指定された文字列を表示するだけのノードである
import rclpy
from rclpy.node import Node
class TestCondition(Node):
def __init__(self):
super().__init__('test_condition_node')
print_message = self.declare_parameter(
'print_message', 'N/A'
).get_parameter_value().string_value
# print_messageで指定された文字列を表示するのみ
self.get_logger().info(print_message)
def main():
rclpy.init()
TestCondition()
rclpy.shutdown()
呼び出しているlaunchファイル(参考)
引数として与えられたprint_messageをそのまま表示するだけのlaunchファイル
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
def generate_launch_description():
# わかりやすくするために、ノードが表示するメッセージを引数として定義
print_message_argument = DeclareLaunchArgument("print_message", default_value="N/A")
print_message = LaunchConfiguration("print_message")
# 引数として与えられた文字列をそのままノードに渡している
return LaunchDescription([
print_message_argument,
Node(
package="test_condition",
executable="test_condition",
name="launch",
output="screen",
parameters=[
{"print_message": print_message}
]
)
])
実行結果
condition:=trueとした場合、IfConditionを使っているノード、launchファイルのみが起動している
$ ros2 launch test_condition test_condition.launch.py condition:=true
[test_condition-3] [INFO] [1.1] [launch]: Launch file w/ IfCondition!
[test_condition-1] [INFO] [1.1] [node_no_condition]: Node w/ no condition!
[test_condition-2] [INFO] [1.1] [node_if_condition]: Node w/ IfCondition!
condition:=falseとした場合、IfConditionを使っているノード、launchファイルのみが起動している
$ ros2 launch test_condition test_condition.launch.py condition:=false
[test_condition-3] [INFO] [1.1] [launch]: Launch file w/ UnlessCondition!
[test_condition-2] [INFO] [1.1] [node_unless_condition]: Node w/ UnlessCondition!
[test_condition-1] [INFO] [1.1] [node_no_condition]: Node w/ no condition!
(実行結果は省略している)
判定について
該当コードのコメントにあるように、以下のようになる
| 最終的な文字列 | 判定結果 |
|---|---|
| true ※1 | 真 |
| 1 | 真 |
| false ※1 | 偽 |
| 0 | 偽 |
| 上記以外 | エラー ※2 |
※1 最終的な文字列が大文字か小文字かとは無関係に判定される(eg. Trueでも真と判定される)
※2 launch.substitutions.text_substitution.TextSubstitutionとか言うエラーが出る