ROS2 Launchでライフサイクル制御
概要
ライフサイクルをもつROSノードであるマネージドROSノードをROS2のLaunchで制御します.
これができると,ROSノードの正確な起動管理などができるようになると思います.
はじめに
ROS2のLaunchシステムは,ROSノードの実行手順を厳密に記述することができるため,ノードの準備ができてから別のノードを起動したり,特定のノードを最後に終了させたり,といったことができます.
ただし,ROSノードの実行状態を取得するには,ライフサイクルをもつROSノード(マネージドROSノード)である必要があります.
この記事では,マネージドROSノードをROS2のLaunchで制御するまでを以下の流れで解説します.
1. シンプルなマネージドROSノードを作成
2. ROS2コマンドのlifecycleを使って動作確認
3. LaunchをつかってマネージドROSノードを制御
マネージドROSノード(Managed ROS Nodes)
マネージドROSノードのライフサイクルの状態遷移は図1のようになっています.
(参考文献[4]の図をこの記事に合わせて修正)
https://gyazo.com/2d378f8b4636c1f6b4e58e52bf1f5b53
図1:ライフサイクルの状態遷移図
状態には,定常状態である4つの基本状態(Primary States)と一時的な中間状態である6つの遷移状態(Transition States)があります[1].
図1において,白いボックスが基本状態で,黒いボックスが遷移状態を示しています.
基本状態(定常状態)
Unconfigured
Inactive
Active
Finalized
遷移状態 (中間状態)
Configuring
Activating
Deactivating
CleaningUp
ShuttingDown
ErrorProcessing
基本状態において,トランジション(transitions)を呼び出すことで,遷移状態に移ります.
table:呼び出すことができるトランジション
lifecycle_msgs.msg.Transition
configure TRANSITION_CONFIGURE
activate TRANSITION_ACTIVATE
deactivate TRANSITION_DEACTIVATE
cleanup TRANSITION_CLEANUP
shutdown TRANSITION_UNCONFIGURED_SHUTDOWN
TRANSITION_INACTIVE_SHUTDOWN
TRANSITION_ACTIVE_SHUTDOWN
遷移状態では,マネージドROSノード内で実装した処理を行い,その結果で次の基本状態へ移ります.
LifeccyleNodesを継承して,コールバック関数を実装することで,遷移状態の処理が行えます.
コールバック関数において,SUCCESS, FAILURE, ERRORのいずれかを返し,それに応じた基本状態へ移ります.
code:lifecycle.cpp
...
class LifecycleDemo : public rclcpp_lifecycle::LifecycleNode
{
...
using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
CallbackReturn on_configure(const rclcpp_lifecycle::State &)
{
...
return CallbackReturn::SUCCESS;
// return CallbackReturn::FAILURE;
// return CallbackReturn::ERROR;
}
...
}
...
table:コールバック関数
遷移状態 コールバック関数
Configuring on_configure
Activating on_activate
Deactivating on_deactivate
CleaningUp on_cleanup
ShuttingDown on_shutdown
ErrorProcessing on_error
コマンドでROSノードのライクサイクルを制御
マネージドROSノードの確認
ROS2のコマンドであるlifecycleを使って,ROSノードのライフサイクルを制御してみます.
まず,ROSノードを実行します.
$ ros2 run launch_lifecycle_demo lifecycle
次に,別のターミナルを立ち上げて,以下のコマンドでライフサイクルに対応したノードの一覧を表示させます.
$ ros2 lifecycle nodes
/demo_node と表示されれば成功です.
基本状態の確認
以下のコマンドで現在の基本状態を確認します.
$ ros2 lifecycle get /demo_node
起動して最初の状態であるunconfiguredが表示されていると思います.
呼び出せるトランジションの確認
lifecycle listを使うと指定するノードの現在の基本状態から呼び出せるトランジションを確認できます.
$ ros2 lifecycle list /demo_node
基本状態はunconfiguredなので,呼び出せるトランジションはconfigureとshutdownになります.
code: stdout
Start: unconfigured
Goal: configuring
Start: unconfigured
Goal: shuttingdown
トランジションの呼出
トランジションを呼び出し基本状態を変更します.
$ ros2 lifecycle set /demo_node configure
Transitioning successfulと表示されれば成功です.ROSノードを実行したターミナルでもなにか表示されているはず.
遷移した基本状態の確認
再び基本状態を確認します.
$ ros2 lifecycle get /demo_node
コールバック関数on_configureがSUCCESSを返すので基本状態はinactiveになっているはず.
呼び出せるトランジションを確認して状態遷移を行ってみたり,コールバック関数の戻り値を変更して遷移する状態を変えてみたりして,動作を確認してみてください.
Launchでライクサイクルを制御
Launchシステムで,ライフサイクルを制御します.
Launchスクリプトの基本的な記述
generate_launch_description関数を作成して,アクションを追加したLaunchDescriptionのオブジェクトを返すのが基本的な記述になります.
例えば,以下のスクリプトは,ROSノードを起動させることができます.
code:lifecycle.launch.py
def generate_launch_description():
ld = launch.LaunchDescription()
# パッケージと実行するノードを指定.
demo_node = launch_ros.actions.LifecycleNode(
node_name='demo_node',
package='launch_lifecycle_demo', node_executable='lifecycle', output='screen')
# アクションを追加
ld.add_action(from_unconfigured_to_inactive)
return ld
イベントの発行
ChangeStateで,トランジションを設定したイベントを作成して,EmitEventで発行します.
code:lifecycle.launch.py
to_inactive = launch.actions.EmitEvent(
event=launch_ros.events.lifecycle.ChangeState(
lifecycle_node_matcher=launch.events.matches_action(demo_node),
transition_id=lifecycle_msgs.msg.Transition.TRANSITION_CONFIGURE,
)
)
イベントの取得
OnStateTransitionで取得するイベントを設定して,RegisterEventHandlerに登録します.
goal_stateに基本状態を指定します.下記の例だと,inactiveに遷移したイベントを取得して,entities配列に含まれるアクションを実行します.
start_stateには,遷移状態を指定します.
イベントを取得する状態によっては,goal_stateとstart_state の両方を指定しないと意図しない動作になるかもしれません.
code:lifecycle.launch.py
from_inactive_to_finalized = launch.actions.RegisterEventHandler(
launch_ros.event_handlers.OnStateTransition(
target_lifecycle_node=demo_node,
start_state = 'deactivating',
goal_state='inactive',
entities=[
launch.actions.LogInfo(msg="<< Inactive >>"),
launch.actions.EmitEvent(event=launch_ros.events.lifecycle.ChangeState(
lifecycle_node_matcher=launch.events.matches_action(demo_node),
transition_id=lifecycle_msgs.msg.Transition.TRANSITION_INACTIVE_SHUTDOWN,
)),
],
)
)
終了処理
基本状態がFinalizedになったとき,launch.events.Shutdownイベントを発生させてプロセスを終了します.
これは,実行中のすべてのノードに「SIGINT」シグナルを送信します.
code:lifecycle.launch.py
from_finalized_to_exit = launch.actions.RegisterEventHandler(
launch_ros.event_handlers.OnStateTransition(
target_lifecycle_node=demo_node, goal_state='finalized',
entities=[
launch.actions.LogInfo(msg="<< Finalized >>"),
launch.actions.EmitEvent(event=launch.events.Shutdown()),
],
)
)
おわりに
ROS2のLaunchシステムで,マネージドROSノードのライフサイクルを制御する方法を解説しました.
ライフサイクルをもつROSノードの実装が増えて,ROSシステム全体の管理が正確に安全にできるようになるといいですね.
参考文献
[1]demos/lifcycle README
[2]ROS 2 Launch System
[3]Architecture of launch
[4]Managed nodes
[5]ZED Lifecycle
[6]近藤 豊,「ROS2ではじめよう 次世代ロボットプログラミング」, 技術評論社, 2019, pp. 94 -- 100, pp. 109 --118