技術
ROS2 ライフサイクルノード、launchファイルによる状態遷移の紹介
2023/01/24
SHARE
電気設計・プログラムを担当している金城と申します。
私は最近の開発ではROS2を使用しています。
ROS2から新しく「ライフサイクルノード(管理されたノード)」という概念が導入されています。
特徴はノードに状態(ライフサイクル)を持っており、設定状態やアクティブな状態を外部から簡単に管理できるようになっている点です。
複数のROSノードの起動・設定の順番・設定失敗・終了時の動作をより正確に書くことができるようになったというところにメリットがあります。
今回はこのライフサイクルノードの状態遷移方法について、私が行っている方法を紹介します。
ライフサイクルの状態について
ライフサイクルノードには下記の状態と、状態遷移で行う操作があります。
この状態に応じた操作を定義しておくことで、管理しやすい単位を作っているわけですね。
ライフサイクル状態
- Unconfigured ・・・ノード起動直後の初期化する前の状態
- Inactive ・・・初期化設定が終わったあとの未運転の状態
- Active ・・・運転中の状態
- Finalized ・・・ノードが終了した状態
状態遷移操作
- create ・・・ノード起動中
- configure・・・初期化設定をする
- cleanup・・・初期化設定を一旦排除する
- activate・・・ノード運転状態にする
- deactivate・・・ノードを未運転状態にする
- shutdown・・・ノードを終了させる
- destroy ・・・ノードを破棄
状態遷移の方法
ライフサイクルノードの状態遷移を行うときには、大体次の3つが考えられると思います。
- コンソールから ros2 lifecycle set —-コマンドで遷移させる
- 状態遷移ノードを作成して、ライフサイクルノードの状態遷移サービス(change_state)を外部から呼び出す
- launchファイルのなかで状態遷移イベントを発行する
①はコンソールからコマンド実行するのでテストのときには使えますが、ある程度実運用向きではない・・・・・
②は全ライフサイクルノードの状態遷移と状態確認のサービスを管理するノードを別に作りますので、非常に細かい制御も出来ますがちょっと面倒・・・・
というわけで、③のlaunchファイルの中で状態遷移のイベントを書く方法を選んでいます。
launchファイルによる状態遷移の記述
ROS2のlaunchファイルでは、launch.LaunchDescription()の中に、実行するアクション(ノード起動など)を記述します。
イベントハンドラ登録アクション(launch.actions.RegisterEventHandler())を利用して 特定のイベント起きたときに、状態遷移のイベントを発行します。
今回はよく使っているものを抜粋していますが、状態遷移以外にもいろいろなイベント・アクションがありますので、下記ページを参考にしてください。
- ROS 2 Documentation:Humble – Using event handlers
- GitHub ROS2/launch:Architecture of launch
- GitHub ROS2/launch_ros
アクション
launchファイル実行のときに実行する内容です。
イベントハンドラ
イベントハンドラに、トリガとなるイベントを記述します。
中には登録したイベントが起きたときに実行するアクションを記述します。
ここでは私が開発していてよく使うものを列挙しました。
イベント
使用例
最後に使用例を示します。例では次の条件で動く状態管理を想定しています。
Launchファイル
# tes_launch.py
import launch
import launch.actions
import launch.event_handlers.on_process_start
import launch_ros.actions
import launch_ros.events
import launch_ros.events.lifecycle
import lifecycle_msgs.msg
def generate_launch_description():
test_lifecycle_node = launch_ros.actions.LifecycleNode( #ライフサイクルノード
package=’test_lifecycle_pkg’,
executable=’test_lifecycle_node’,
parameters = [{‘config_file’:’./setting/config.yaml’}], #ROSパラメータ設定
arguments=[‘–ros-args’,’–log-level’,INFO], #引数
name=’test_lifecycle_node’, namespace=”,
)
rqt_gui_node = launch_ros.actions.Node(#通常ノード:(試しにrqt)
package=’rqt_gui’,
executable=’rqt_gui’,
arguments=[‘–hide-title’,’-lt’], #引数
name=’rqt_gui’, namespace=”,
)
return launch.LaunchDescription([
# ノードを起動する
rqt_gui_node,
test_lifecycle_node,
# 状態遷移を行う
launch.actions.RegisterEventHandler(#イベントハンドラの登録
launch.event_handlers.on_process_start.OnProcessStart(#プロセス起動イベント
target_action=rqt_gui_node,#ターゲットのノード
on_start=[
launch.actions.LogInfo(msg=”transition start :test_lifecycle_node :configuring”),
# test_lifecycle_nodeをconfigur遷移させるイベントを登録
launch.actions.EmitEvent(
event=launch_ros.events.lifecycle.ChangeState(
lifecycle_node_matcher=launch.events.matches_action(test_lifecycle_node),
transition_id=lifecycle_msgs.msg.Transition.TRANSITION_CONFIGURE,
)),
],
)
),
# configuring後、inactive状態になったらactivateに遷移
launch.actions.RegisterEventHandler(#イベントハンドラの登録
launch_ros.event_handlers.OnStateTransition(#lifecycle_nodeが状態遷移したときのイベント
target_lifecycle_node=test_lifecycle_node,# ターゲットノード
start_state=’configuring’, goal_state=’inactive’,# どの状態からどの状態へ遷移したかを書く
entities=[
launch.actions.LogInfo(msg=”transition start :test_lifecycle_node :activating”),
# test_lifecycle_nodeをactivate状態に遷移させるイベントを登録
launch.actions.EmitEvent(
event=launch_ros.events.lifecycle.ChangeState(
lifecycle_node_matcher=launch.events.matches_action(test_lifecycle_node),
transition_id=lifecycle_msgs.msg.Transition.TRANSITION_ACTIVATE,
)),
],
)
),
#rqt_gui_nodeが終了した(画面が閉じられた)らtest_lifecycle_nodeもactivate→shutdownシーケンスを実行する
launch.actions.RegisterEventHandler(# rqtのウィンドウが閉じられたらシャットダウンする
launch.event_handlers.OnProcessExit(#プロセスが終了した時にに発行されるイベント
target_action=rqt_gui_node,
on_exit=[
launch.actions.LogInfo(msg=”the rqt window was closed”),
# test_lifecyce_nodeをシャットダウンさせるイベント
launch.actions.EmitEvent(
event=launch_ros.events.lifecycle.ChangeState(
lifecycle_node_matcher=launch.events.matches_action(test_lifecycle_node),
transition_id=lifecycle_msgs.msg.Transition.TRANSITION_ACTIVE_SHUTDOWN ,
)
),
]
)
)
# rqt_gui_nodeがfinalized状態になったらlaunchシステムを終了する
launch.actions.RegisterEventHandler(
launch_ros.event_handlers.OnStateTransition(
target_lifecycle_node=rqt_gui_node,
goal_state=’finalized’,
entities=[
launch.actions.LogInfo(msg=”<< Finalized >>”),
#launchシステムを終了する
launch.actions.EmitEvent(event=launch.events.Shutdown()),
],
)
),
])
これでlaunchファイルでも、ライフサイクルノードを使用して下記のような動作をわかりやすく書くことができそうです。
- 機器通信ノードがconfigure(初期化)に失敗したときに制御ノードを初期化しない、またはactive状態にしない
- 機器通信が切れたときにError状態に遷移、再度configureに遷移させて初期化させる
- 特定のノードがError状態に遷移したときに、制御ノードをdeactivate遷移させて動作を止める
エラー発生時のシステムの耐久性というのは開発者にとって永遠のテーマです。
まだ私も高度なライフサイクルのシステムは作れていませんが、ライフサイクルノードを活用して堅牢なシステムを構築していきたいと思います!