LifecycleNode讲解及实例
文章目录
- 前言
- LifecycleNode是什么
- 背景
- 生命周期
- 状态定义
- Unconfigured
- Inactive
- Active
- Finalized
- 转换逻辑图示
- 标准接口
- 代码实现&测试
- 代码
- 测试
- 总结
前言
本文用来记录什么是LifecycleNode,做背景介绍及基本原理的介绍及分析如何使用。1
LifecycleNode是什么
背景
节点的托管生命周期允许更好地控制ROS系统的状态。它将允许roslaunch在允许任何组件开始执行其行为之前确保所有组件都已正确实例化。它还允许重新启动或在线更换节点。
本文档最重要的概念是,受管节点提供已知接口,根据已知的生命周期状态机执行,否则可被视为黑盒。这使得节点开发人员可以自由决定如何提供托管生命周期功能,同时还确保为管理节点而创建的任何工具都可以与任何兼容的节点一起使用。
生命周期
有四个主要状态:
Unconfigured
Inactive
Active
Finalized
还存在6个过渡状态,它们是在所请求的过渡期间的中间状态。
Configuring
CleaningUp
ShuttingDown
Activating
Deactivating
ErrorProcessing
在转换状态中,将执行逻辑以确定转换是否成功。成功或失败应通过生命周期管理界面传达给生命周期管理软件。
有7个过渡暴露于监督流程,它们是:
create
configure
cleanup
activate
deactivate
shutdown
destroy
状态定义
Unconfigured
这是节点在实例化后立即处于的生命周期状态。这也是节点在发生错误后可能返回的状态。
- 节点可以经由
configure
转换转换到Inactive
状态 - 节点可以经由
shutdown
转换转换到Finalized
状态
Inactive
此状态表示当前未执行任何处理的节点。
此状态的主要目的是允许节点在运行时进行配置(更改配置参数、添加和删除主题发布/订阅等),而不更改其行为。
当处于这种状态时,节点将不会接收任何执行时间来读取主题、执行数据处理、响应功能服务请求等。
在非活动状态下,将不会读取和/或处理到达托管主题的任何数据。数据保留将受为主题配置的QoS策略的约束。
对处于非活动状态的节点的任何托管服务请求都不会被应答(对于调用者来说,它们将立即失败)。
- 节点可以经由
shutdown
转换转换到Finalized
状态 - 节点可以经由
cleanup
转换转换到Unconfigured
状态 - 节点可以经由
activate
转换转换到Active
状态
Active
这是节点生命周期的主要状态。在这种状态下,节点执行任何处理,响应服务请求,读取和处理数据,产生输出等。
如果在此状态下发生节点/系统无法处理的错误,则节点将转换到 ErrorProcessing
。
- 节点可以经由
deactivate
转换转换到Inactive
状态 - 节点可以经由
shutdown
转换转换到Finalized
状态
Finalized
Finalized
状态是节点在被销毁之前立即结束的状态。这个状态总是终结的,从这里开始的唯一转变就是被摧毁。
转换逻辑图示
下边这张图用来说明状态切换之间的关系,如果看不懂也没关系,可以根据后续的测试代码切换一遍流程即可理解。2
标准接口
服务(Service):3
-
/change_state
- 调用触发合法转换 -
/get_available_transitions
- 显示合法的转换 -
/get_state
- 显示当前状态 -
/get_available_states
- 列出所有状态 -
/get_transition_graph
- 显示完整状态机
主题(Topic):
/transition_event
- 发布正在进行的转换
代码实现&测试
代码
# CMakeLists.txt
cmake_minimum_required(VERSION 3.8)
project(my_lifecycle_node)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(lifecycle_msgs REQUIRED)
find_package(std_msgs REQUIRED)
add_executable(my_lifecycle_node
src/my_lifecycle_node.cpp)
ament_target_dependencies(my_lifecycle_node rclcpp rclcpp_lifecycle lifecycle_msgs std_msgs)
install(TARGETS
my_lifecycle_node
DESTINATION lib/${PROJECT_NAME}
)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# comment the line when a copyright and license is added to all source files
set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# comment the line when this package is in a git repo and when
# a copyright and license is added to all source files
set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
ament_package()
# package.xml
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>my_lifecycle_node</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="https://blog.csdn.net/Bing_Lee">dev</maintainer>
<license>TODO: License declaration</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<depend>rclcpp</depend>
<depend>rclcpp_lifecycle</depend>
<depend>lifecycle_msgs</depend>
<depend>std_msgs</depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>
#include <iostream>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_lifecycle/lifecycle_node.hpp>
#include "lifecycle_msgs/msg/transition.hpp"
#include "std_msgs/msg/string.hpp"
using namespace std::chrono_literals;
class my_lifecycle_node : public rclcpp_lifecycle::LifecycleNode
{
public:
explicit my_lifecycle_node(const std::string& node_name, bool intra_process_comms = false)
: rclcpp_lifecycle::LifecycleNode(node_name, rclcpp::NodeOptions().use_intra_process_comms(intra_process_comms)) {}
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure(
const rclcpp_lifecycle::State&)
{
RCLCPP_INFO(get_logger(), "on_configure() is called.");
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate(
const rclcpp_lifecycle::State&)
{
RCUTILS_LOG_INFO_NAMED(get_name(), "on_activate() is called.");
std::this_thread::sleep_for(2s);
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(
const rclcpp_lifecycle::State&)
{
RCUTILS_LOG_INFO_NAMED(get_name(), "on_deactivate() is called.");
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup(
const rclcpp_lifecycle::State&)
{
RCUTILS_LOG_INFO_NAMED(get_name(), "on cleanup() is called.");
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown(
const rclcpp_lifecycle::State& state)
{
RCUTILS_LOG_INFO_NAMED(get_name(), "on shutdown() is called from state %s.", state.label().c_str());
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
};
int main(int argc, char** argv)
{
rclcpp::init(argc, argv);
auto node = std::make_shared<my_lifecycle_node>("my_lifecycle_node");
rclcpp::spin(node->get_node_base_interface());
rclcpp::shutdown();
return 0;
}
# 文件结构
$ tree my_lifecycle_node/
my_lifecycle_node/
├── CMakeLists.txt
├── include
│ └── my_lifecycle_node
├── package.xml
└── src
└── my_lifecycle_node.cpp
测试
# 编译
$ colcon build --packages-up-to my_lifecycle_node
# bash 安装配置
$ source install/setup.bash
# 运行
$ ros2 run my_lifecycle_node my_lifecycle_node
新开一个窗口
$ ros2 service list
/my_lifecycle_node/change_state
/my_lifecycle_node/describe_parameters
/my_lifecycle_node/get_available_states
/my_lifecycle_node/get_available_transitions
/my_lifecycle_node/get_parameter_types
/my_lifecycle_node/get_parameters
/my_lifecycle_node/get_state
/my_lifecycle_node/get_transition_graph
/my_lifecycle_node/list_parameters
/my_lifecycle_node/set_parameters
/my_lifecycle_node/set_parameters_atomically
$ ros2 topic list
/my_lifecycle_node/transition_event
/parameter_events
/rosout
状态切换
# 当前状态
$ ros2 lifecycle get /my_lifecycle_node
unconfigured [1]
# 配置节点
$ ros2 lifecycle set /my_lifecycle_node configure
Transitioning successful
$ ros2 lifecycle get /my_lifecycle_node
inactive [2]
# 激活节点
$ ros2 lifecycle set /my_lifecycle_node activate
Transitioning successful
$ ros2 lifecycle get /my_lifecycle_node
active [3]
# 停止节点
$ ros2 lifecycle set /my_lifecycle_node deactivate
Transitioning successful
$ ros2 lifecycle get /my_lifecycle_node
inactive [2]
# 获取当前节点可转换的状态
$ ros2 lifecycle list /my_lifecycle_node
- cleanup [2]
Start: inactive
Goal: cleaningup
- activate [3]
Start: inactive
Goal: activating
- shutdown [6]
Start: inactive
Goal: shuttingdown
# 杀掉节点
$ ros2 lifecycle set /my_lifecycle_node shutdown
Transitioning successful
$ ros2 lifecycle get /my_lifecycle_node
finalized [4]
# 尝试切换杀掉的(状态为finalized)节点,失败
$ ros2 lifecycle set /my_lifecycle_node configure
Unknown transition requested, available ones are:
总结
本文对于LifecycleNode做了整体的说明和测试,说明了中间的变换关系,方便大家理解和用于实际使用中。
ros.rog Class LifecycleNode ↩︎
Managed nodes (ros2.org) ↩︎
ROS2----LifecycleNode生命周期节点总结 ↩︎