본문 바로가기

ROS

[ROS2] Lifecycle Node(nav2_util/LifecycleNode)

Lifecycle Node

ROS2에는 rclcpp_lifecycle::LifecycleNode에 기본적으로 lifecycle을 관리할 수 있게 해 놓았다. 하지만 관리해주는 코드를 직접 작성해야 하는 수고가 추가 적으로 있어서 ROS2의 Navigation package인 nav2에 만들어져 있는 nav2_util::LifecycleNode를 소개한다.

Lifecycle Node의 기능

Lifecycle은 node의 상태를 관리할 수 있게 해준다. Lifecycle이 관리하는 node의 상태는 다음과 같다.

  • configure : 노드를 생성할 때 필요한 상태
  • activate: 노드가 실행될 때 필요한 상태
  • deactivate: 노드가 중지 될 때 필요한 상태
  • cleanup: 노드를 처음 생성할 당시로 만드는 상태
  • shutdown: 노드를 삭제할 때 필요한 상태

여기서, nav2_util::LifecycleNode는 다음과 같이 인터페이스를 상속 받는 class를 사용한다.

#include "nav2_util/lifecycle_node.hpp"

namespace test_node
{
class TestNode : public nav2_util::LifecycleNode
{
public:
  TestNode();
  ~TestNode();

  bool loadBehaviorPlugins();
protected:
  nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
  nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
  nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
  nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
  nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
};

} // namespace navigation_behaivor

#endif

가각 on_configure , on_activate, on_deactivate, on_cleanup, on_shutdown을 override해 주어야 한다.

이제 LifecycleNode는 생성이 되었고, 이를 관리해주는 lifecycle_manager가 nav2에서 nav2_lifecycle_manager로 존재한다.

lifecycle_manager는 다음과 같은 parameter를 가진다.

  • use_sim_time
  • autostart: 각 node를 자동 실행 시키는 기능
  • node_names: 관리할 node들의 이름

이를 launch로 실행하면 다음과 같은 형식을 띄게 된다.

import os

from ament_index_python.packages import get_package_share_directory

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
from nav2_common.launch import RewrittenYaml

def generate_launch_description():
    application_dir = get_package_share_directory('test_package')
    namespace = LaunchConfiguration('namespace')
    use_sim_time = LaunchConfiguration('use_sim_time')
    autostart = LaunchConfiguration('autostart')

    lifecycle_nodes = [
      'application_server'
    ]
    
    return LaunchDescription([
      SetEnvironmentVariable('RCUTILS_LOGGING_BUFFERED_STREAM', '1'),
      DeclareLaunchArgument(
            'namespace', default_value='',
            description='Top-level namespace'),

      DeclareLaunchArgument(
          'use_sim_time', default_value='false',
          description='Use simulation (Gazebo) clock if true'),

      DeclareLaunchArgument(
          'autostart', default_value='true',
          description='Automatically startup the application'),

      Node(
        package='test_pakage',
        executable='test_node',
        output='screen',
        parameters=[configured_params],
        remappings=remappings),
      
      Node(
        package='nav2_lifecycle_manager',
        executable='lifecycle_manager',
        name='lifecycle_manager_application',
        output='screen',
        parameters=[{'use_sim_time': use_sim_time},
                    {'autostart': autostart},
                    {'node_names': lifecycle_nodes}])
    ])

이를 실행하면, lifecycle_manager가 자동으로 node관리를 해주는 모습을 확인 할 수 있다.