一、说明
欢迎来到我在 ROS2 上的系列的第八部分。对于那些可能不熟悉该系列的人,我已经涵盖了一系列主题,包括 ROS2 简介、如何创建发布者和订阅者、自定义消息和服务创建、组合和执行器以及 DDS 和 QoS 配置。如果您还没有机会查看以前的帖子,请务必查看!在这篇文章中,我们将探讨 ROS2 的另一个重要方面:生命周期节点
在机器人领域,管理不同软件组件的生命周期可能是一项具有挑战性的任务。每个组件可能都有自己的依赖项、配置参数和要处理的运行时事件。这可能会导致复杂的启动文件和脚本,使管理和更新系统变得困难。而且,状态机设计在机器人系统中很重要,因为它们提供了一种结构化和可预测的方式来管理机器人软件组件的行为和功能。ROS1 没有用于管理软件组件生命周期的内置接口,这使得确保系统中的不同节点正常运行并有效相互通信变得具有挑战性。这就是 ROS2 的生命周期节点的用武之地——它们提供了一个标准化的接口来管理软件组件的状态,从它的创建和初始化到它的关闭和清理。
二、资源描述
在这篇文章中,我们将仔细研究 ROS2 生命周期节点、它们的好处,以及如何使用它们来管理机器人系统中不同软件组件的生命周期。我还将提供一些如何实现 ROS2 生命周期节点的示例。在这篇文章结束时,您将更好地了解 ROS2 生命周期节点以及它们如何简化机器人软件组件的管理。
在设计机器人系统时,某些组件对于系统的正常运行至关重要,可能需要特别注意管理其生命周期。在 ROS2 中,有两种类型的节点在高级别可用:
参考链接:节点
参考链接:生命周期节点
例如,考虑一个依靠摄像头进行物体检测和避障的机器人。相机配置对于确保系统接收可靠数据至关重要。要管理相机节点的生命周期,我们可以使用生命周期节点而不是标准节点。此专用节点将负责配置相机参数,例如分辨率、帧速率和曝光,以及将相机数据发布到检测和避障组件。通过这样做,我们可以确保相机节点设置正确并且其数据可靠,从而使我们能够更有效地管理其生命周期。
另一个例子,ROS导航栈,
参考:链接
其常用的机器人导航软件包,包括各种组件,例如地图服务器,成本图生成器,本地计划器和全局计划器。这些组件需要按特定顺序启动和停止,并且需要协调它们的生命周期,以确保整个导航系统的正常运行。以下是 ROS2 生命周期节点如何有益于管理导航堆栈:
通过对导航堆栈的每个组件使用 ROS2 生命周期节点,您可以确保组件以正确的顺序启动和关闭。例如,需要在成本图和规划器节点之前加载地图服务器和传感器主题。 使用 ROS2 生命周期节点 API,您可以为每个组件定义一个生命周期状态机,其中包含启动、关闭和状态之间转换所需的状态。通过定义每个节点状态之间的正确依赖关系,可以确保导航堆栈组件以正确的顺序启动和关闭。
除了管理每个组件的启动和关闭外,ROS2 生命周期节点还可用于处理运行时事件,例如导航堆栈的重新配置或对环境的更改。例如,如果机器人在导航时遇到新的障碍物,则可能需要重新配置成本图生成器以考虑新的障碍物。使用 ROS2 生命周期节点 API,您可以定义一个状态转换,以便在其他组件继续运行时处理此重新配置。
有 4 种主要状态:
1. 未配置
2.非活动
3.活动
4.完成
除了四个主要状态之外,节点的生命周期中还有六个转换状态,它们是请求转换期间的中间状态。这些转换状态是:
1.配置:正在配置节点,这通常涉及设置节点运行所需的参数和连接。
2. 清理:正在关闭节点并清理其资源。
3. 关闭:节点正在关闭,通常是为了响应这样做的请求。
4.激活:节点处于活动状态,例如通过初始化其硬件或连接到其他节点。
5. 停用:节点处于非活动状态,例如与其他节点断开连接或关闭其硬件。
6. 错误处理:转换过程中发生错误,节点正在处理错误。
在转换状态期间,将执行特定逻辑以确定转换是否成功。然后,成功或失败通过生命周期管理界面传达给生命周期管理软件。
参考:ROS2设计
好吧,让我们从一个基本的camera_node包开始。
ros2 pkg create --build-type ament_cmake camera_node --dependencies rclcpp sensor_msgs rcutils rclcpp_lifecycle lifecycle_msgs
以下是此软件包中使用的 ROS 2 软件包和消息的简要说明:
这是 ROS 2 的C++客户端库,它为编写 ROS 2 节点提供了一个瘦C++式接口。它允许用户创建发布者和订阅者、服务和客户端、操作和服务器等
:这是提供“生命周期”概念实现的扩展。生命周期节点是一种特殊类型的节点,可以经历不同的状态,例如“未配置”、“非活动”、“活动”和“已完成”。这些状态允许对节点进行更受控的初始化和关闭过程。
:这是一个 C 库,它提供了一些基本的、低级的功能,这些功能在 ROS 2 开发中很有用。例如,它提供了一个日志记录 API,允许用户记录具有不同严重性级别的消息。
:这是一个 ROS 2 软件包,为常用传感器(如摄像头、激光雷达和 IMU)提供消息类型。在提供的代码段中,使用消息类型,但它可以替换为包中的任何消息类型,例如相机节点。
:这是一个 ROS 2 包,为生命周期概念提供消息类型。例如,消息类型用于传达从节点到生命周期管理软件的生命周期转换的成功或失败。rclcpp
rclcpp_lifecycle
rclcpp
rcutils
sensor_msgs
std_msgs/msg/String
sensor_msgs
sensor_msgs/msg/Image
lifecycle_msgs
lifecycle_msgs/msg/Transition
cd camera_node && touch src/camera_node.cpp
// camera_node.cpp
#include <chrono>
#include <iostream>
#include <memory>
#include <string>
#include <thread>
#include <utility>#include "lifecycle_msgs/msg/transition.hpp"
#include "opencv2/highgui/highgui.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/publisher.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "rclcpp_lifecycle/lifecycle_publisher.hpp"
#include "rcutils/logging_macros.h"
#include "sensor_msgs/msg/image.hpp"#include "utils.cpp"using namespace std::chrono_literals;class CameraNode : public rclcpp_lifecycle::LifecycleNode
{
public:/* The constructor takes in a node_name and a boolean flag for whether to * use intra-process communication or not. The captureImage() method is * used to capture an image from the camera and process it as necessary. * It first checks whether the publisher is active or not and then creates * an image message to publish using the publisher. The image message is of * type sensor_msgs::msg::Image. The publisher is a lifecycle publisher which * means it can be activated or deactivated during runtime using the ROS2 lifecycle interface.*/explicit CameraNode(const std::string & node_name, bool intra_process_comms = false): rclcpp_lifecycle::LifecycleNode(node_name,rclcpp::NodeOptions().use_intra_process_comms(intra_process_comms)){}void publish(){static size_t count = 0;cv::Mat frame_;if (!cap_.read(frame_)) {// If the camera is disconnected, stop publishing frames.RCLCPP_ERROR(get_logger(), "Failed to read frame from camera.");return;}if (!publisher_->is_activated()) {RCLCPP_INFO(get_logger(), "Lifecycle publisher is currently inactive. Messages are not published.");} else {RCLCPP_INFO(get_logger(), "Lifecycle publisher is active. Publishing:");}sensor_msgs::msg::Image::UniquePtr msg(new sensor_msgs::msg::Image());// Pack the OpenCV image into the ROS image.msg->header.frame_id = "camera_frame";msg->height = frame_.rows;msg->width = frame_.cols;msg->encoding = mat_type2encoding(frame_.type());msg->is_bigendian = false;msg->step = static_cast<sensor_msgs::msg::Image::_step_type>(frame_.step);msg->data.assign(frame_.datastart, frame_.dataend);publisher_->publish(std::move(msg));}/* The on_configure function is called when the node is in the Configuring state of the lifecycle.* In this function, the camera is opened and checked if it is successfully opened. * Then, a publisher is created for publishing the camera image with a queue size of 10. Additionally, * a timer is created to trigger the publish function of the CameraNode class every 1 second. * Finally, an informational message is printed to indicate that the node has been configured * and the callback returns rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS. * If there is an error opening the camera, an error message is printed and the callback returns * rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::FAILURE, * indicating that the node failed to configure. */rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturnon_configure(const rclcpp_lifecycle::State &){// Open the camera.cap_.open(0);if (!cap_.isOpened()) {RCLCPP_ERROR(get_logger(), "Failed to open camera.");return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::FAILURE;}publisher_ = this->create_publisher<sensor_msgs::msg::Image>("camera_image", 10);timer_ = this->create_wall_timer(1s, std::bind(&CameraNode::publish, this));RCLCPP_INFO(get_logger(), "CameraNode configured.");return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;}/* During the activate lifecycle transition, the on_activate function is called, * which activates the publisher associated with the node. The publisher_->on_activate() * call in this function activates the publisher by notifying its subscribers that the node is * ready to publish data.* In addition, this code block also includes a log message indicating that the CameraNode * has been activated. Finally, a std::this_thread::sleep_for(2s) call is used to introduce a * delay of 2 seconds to simulate a time-consuming activation process.* The function returns rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS * to indicate that the transition was successful. */rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturnon_activate(const rclcpp_lifecycle::State &){publisher_->on_activate();RCUTILS_LOG_INFO_NAMED(get_name(), "CameraNode activated.");std::this_thread::sleep_for(2s);return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;}/* on_deactivate function, which is a callback function called when the node is in the "inactive" state.* In this function, the on_deactivate function of the publisher is called to deactivate it. * Then, a log message is printed to indicate that the node has been deactivated.* The function returns rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS * to indicate that the deactivation process has been completed successfully. */rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturnon_deactivate(const rclcpp_lifecycle::State &){publisher_->on_deactivate();RCUTILS_LOG_INFO_NAMED(get_name(), "CameraNode deactivated.");return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;}/* The on_cleanup function is a callback function that is executed when the node is being * cleaned up or shutdown. In this function, the timer_ and publisher_ are reset, * which means they are destroyed and any resources they were holding are released. * Then an information message is logged to indicate that the cleanup has been completed.* The return type of this function is rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn, * which is an enumeration that indicates whether the callback function was successful or not. * In this case, it always returns SUCCESS, which means that the cleanup was completed successfully.*/rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturnon_cleanup(const rclcpp_lifecycle::State &){timer_.reset();publisher_.reset();RCUTILS_LOG_INFO_NAMED(get_name(), "CameraNode cleanup.");return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;}/* This is the on_shutdown callback function for the CameraNode class, * which is called when the node is being shut down. * The function takes in a state argument of type rclcpp_lifecycle::State, which represents the current state * of the node when it is being shut down.* The function first resets the timer_ and publisher_ objects, and then logs an information message * indicating that the on_shutdown function is being called and prints the label of the state that the node is in.* Finally, the function returns rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS * to indicate that the shutdown procedure has completed successfully.*/rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturnon_shutdown(const rclcpp_lifecycle::State & state){timer_.reset();publisher_.reset();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;}
private:std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<sensor_msgs::msg::Image>> publisher_;std::shared_ptr<rclcpp::TimerBase> timer_;cv::VideoCapture cap_;
};int main(int argc, char * argv[])
{setvbuf(stdout, NULL, _IONBF, BUFSIZ);rclcpp::init(argc, argv);rclcpp::executors::SingleThreadedExecutor exe;std::shared_ptr<CameraNode> camera_node =std::make_shared<CameraNode>("camera_node");exe.add_node(camera_node->get_node_base_interface());exe.spin();rclcpp::shutdown();return 0;
}
让我们更新 CMakeLists.txt 并编译,
cmake_minimum_required(VERSION 3.5)
project(camera_node)# Default to C99
if(NOT CMAKE_C_STANDARD)set(CMAKE_C_STANDARD 99)
endif()# Default to C++14
if(NOT CMAKE_CXX_STANDARD)set(CMAKE_CXX_STANDARD 14)
endif()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_lifecycle REQUIRED)
find_package(lifecycle_msgs REQUIRED)
find_package(rclcpp REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(OpenCV REQUIRED COMPONENTS core highgui imgproc videoio)include_directories(include${sensor_msgs_INCLUDE_DIRS}${lifecycle_msgs_INCLUDE_DIRS}${rclcpp_lifecycle_INCLUDE_DIRS}${rclcpp_INCLUDE_DIRS})add_executable(camera_nodesrc/camera_node.cpp)target_link_libraries(camera_node${rclcpp_lifecycle_LIBRARIES}${lifecycle_msgs_LIBRARIES}${sensor_msgs_LIBRARIES}${OpenCV_LIBRARIES})install(TARGETScamera_nodeDESTINATION lib/${PROJECT_NAME})ament_package()
# Compile the package
colcon build --packages-select camera_node# Now lets run the camera_node
source install/setup.zsh# list running ros2 topics
ros2 topic list# Output
/camera_node/transition_event
/parameter_events
/rosout# listen to messages on the /camera_node/transition_event
ros2 topic echo /camera_node/transition_event # You don't see any logs in the terminal since no transitions
# have been made yet.
camera_node的当前状态是什么,如何修改节点状态?
# First lets get the service list
ros2 service list# output
/camera_node/change_state
/camera_node/describe_parameters
/camera_node/get_available_states
/camera_node/get_available_transitions
/camera_node/get_parameter_types
/camera_node/get_parameters
/camera_node/get_state
/camera_node/get_transition_graph
/camera_node/list_parameters
/camera_node/set_parameters
/camera_node/set_parameters_atomically# This is a list of services that the camera node created.
# Now lets get the current state of the camera_node
ros2 service call /camera_node/get_state lifecycle_msgs/srv/GetState {}# Output
ros2 service call /camera_node/get_state lifecycle_msgs/srv/GetState {}
requester: making request: lifecycle_msgs.srv.GetState_Request()response:
lifecycle_msgs.srv.GetState_Response(current_state=lifecycle_msgs.msg.State(id=1, label='unconfigured'))# So the camera node in unconfigured state# Change the camera_node from unconfigured to configured state
ros2 lifecycle set /camera_node configure# Now you could see the camera node changes to configured state
更改相机节点状态以配置后显示输出
我们还有另一个命令来查看camera_node的完整状态机。
ros2 lifecycle list camera_node -a # Output
- configure [1]Start: unconfiguredGoal: configuring
- transition_success [10]Start: configuringGoal: inactive
- transition_failure [11]Start: configuringGoal: unconfigured
- transition_error [12]Start: configuringGoal: errorprocessing
- cleanup [2]Start: inactiveGoal: cleaningup
- transition_success [20]Start: cleaningupGoal: unconfigured
- transition_failure [21]Start: cleaningupGoal: inactive
- transition_error [22]Start: cleaningupGoal: errorprocessing
- activate [3]Start: inactiveGoal: activating
- transition_success [30]Start: activatingGoal: active
- transition_failure [31]Start: activatingGoal: inactive
- transition_error [32]Start: activatingGoal: errorprocessing
- deactivate [4]Start: activeGoal: deactivating
- transition_success [40]Start: deactivatingGoal: inactive
- transition_failure [41]Start: deactivatingGoal: active
- transition_error [42]Start: deactivatingGoal: errorprocessing
- shutdown [5]Start: unconfiguredGoal: shuttingdown
- shutdown [6]Start: inactiveGoal: shuttingdown
- shutdown [7]Start: activeGoal: shuttingdown
- transition_success [50]Start: shuttingdownGoal: finalized
- transition_failure [51]Start: shuttingdownGoal: finalized
- transition_error [52]Start: shuttingdownGoal: errorprocessing
- transition_success [60]Start: errorprocessingGoal: unconfigured
- transition_failure [61]Start: errorprocessingGoal: finalized
- transition_error [62]Start: errorprocessingGoal: finalized
现在让我们编写订阅者节点,
cd camera_node && touch src/display_node.cpp
// display_node.cpp
#include <memory>
#include <string>#include "lifecycle_msgs/msg/transition_event.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rcutils/logging_macros.h"
#include "sensor_msgs/msg/image.hpp"#include "utils.cpp"class DisplayNode : public rclcpp::Node
{
public:explicit DisplayNode(const std::string & node_name): Node(node_name){subscriber_ = this->create_subscription<sensor_msgs::msg::Image>("camera_image", 10,std::bind(&DisplayNode::data_callback, this, std::placeholders::_1));sub_notification_ = this->create_subscription<lifecycle_msgs::msg::TransitionEvent>("/camera_image/transition_event",10,std::bind(&DisplayNode::notification_callback, this, std::placeholders::_1));}void data_callback(const sensor_msgs::msg::Image::UniquePtr msg){cv::Mat frame(msg->height, msg->width,encoding2mat_type(msg->encoding),msg->data.data());cv::imshow("window", frame);cv::waitKey(1);}void notification_callback(const lifecycle_msgs::msg::TransitionEvent::SharedPtr msg){RCLCPP_INFO(get_logger(), "notify callback: Transition from state %s to %s",msg->start_state.label.c_str(), msg->goal_state.label.c_str());}private:std::shared_ptr<rclcpp::Subscription<sensor_msgs::msg::Image>> subscriber_;std::shared_ptr<rclcpp::Subscription<lifecycle_msgs::msg::TransitionEvent>>sub_notification_;cv::Mat frame_;
};int main(int argc, char ** argv)
{setvbuf(stdout, NULL, _IONBF, BUFSIZ);rclcpp::init(argc, argv);auto display_node = std::make_shared<DisplayNode>("display_node");rclcpp::spin(display_node);rclcpp::shutdown();return 0;
}
更新 CMakeLists.txt,
add_executable(display_nodesrc/display_node.cpp)target_link_libraries(display_node${rclcpp_lifecycle_LIBRARIES}${lifecycle_msgs_LIBRARIES}${sensor_msgs_LIBRARIES}${OpenCV_LIBRARIES})install(TARGETScamera_nodedisplay_nodeDESTINATION lib/${PROJECT_NAME})
到目前为止,我们已经从命令行更改了节点状态。现在,我们将以编程方式执行此操作。我们将演示如何使用 ROS 2 生命周期服务 API 来更改节点的状态。
cd camera_node && touch src/lc_service_client.cpp
#include <chrono>
#include <memory>
#include <string>
#include <thread>#include "lifecycle_msgs/msg/state.hpp"
#include "lifecycle_msgs/msg/transition.hpp"
#include "lifecycle_msgs/srv/change_state.hpp"
#include "lifecycle_msgs/srv/get_state.hpp"#include "rclcpp/rclcpp.hpp"#include "rcutils/logging_macros.h"using namespace std::chrono_literals;static constexpr char const * lifecycle_node = "camera_node";
static constexpr char const * node_get_state_topic = "camera_node/get_state";
static constexpr char const * node_change_state_topic = "camera_node/change_state";template<typename FutureT, typename WaitTimeT>
std::future_status
wait_for_result(FutureT & future,WaitTimeT time_to_wait)
{auto end = std::chrono::steady_clock::now() + time_to_wait;std::chrono::milliseconds wait_period(100);std::future_status status = std::future_status::timeout;do {auto now = std::chrono::steady_clock::now();auto time_left = end - now;if (time_left <= std::chrono::seconds(0)) {break;}status = future.wait_for((time_left < wait_period) ? time_left : wait_period);} while (rclcpp::ok() && status != std::future_status::ready);return status;
}class LifecycleServiceClient : public rclcpp::Node
{
public:explicit LifecycleServiceClient(const std::string & node_name): Node(node_name){}voidinit(){client_get_state_ = this->create_client<lifecycle_msgs::srv::GetState>(node_get_state_topic);client_change_state_ = this->create_client<lifecycle_msgs::srv::ChangeState>(node_change_state_topic);}unsigned intget_state(std::chrono::seconds time_out = 3s){auto request = std::make_shared<lifecycle_msgs::srv::GetState::Request>();if (!client_get_state_->wait_for_service(time_out)) {RCLCPP_ERROR(get_logger(),"Service %s is not available.",client_get_state_->get_service_name());return lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN;}auto future_result = client_get_state_->async_send_request(request);auto future_status = wait_for_result(future_result, time_out);if (future_status != std::future_status::ready) {RCLCPP_ERROR(get_logger(), "Server time out while getting current state for node %s", lifecycle_node);return lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN;}// We have an succesful answer. So let's print the current state.if (future_result.get()) {RCLCPP_INFO(get_logger(), "Node %s has current state %s.",lifecycle_node, future_result.get()->current_state.label.c_str());return future_result.get()->current_state.id;} else {RCLCPP_ERROR(get_logger(), "Failed to get current state for node %s", lifecycle_node);return lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN;}}boolchange_state(std::uint8_t transition, std::chrono::seconds time_out = 3s){auto request = std::make_shared<lifecycle_msgs::srv::ChangeState::Request>();request->transition.id = transition;if (!client_change_state_->wait_for_service(time_out)) {RCLCPP_ERROR(get_logger(),"Service %s is not available.",client_change_state_->get_service_name());return false;}auto future_result = client_change_state_->async_send_request(request);auto future_status = wait_for_result(future_result, time_out);if (future_status != std::future_status::ready) {RCLCPP_ERROR(get_logger(), "Server time out while getting current state for node %s", lifecycle_node);return false;}if (future_result.get()->success) {RCLCPP_INFO(get_logger(), "Transition %d successfully triggered.", static_cast<int>(transition));return true;} else {RCLCPP_WARN(get_logger(), "Failed to trigger transition %u", static_cast<unsigned int>(transition));return false;}}private:std::shared_ptr<rclcpp::Client<lifecycle_msgs::srv::GetState>> client_get_state_;std::shared_ptr<rclcpp::Client<lifecycle_msgs::srv::ChangeState>> client_change_state_;
};void
callee_script(std::shared_ptr<LifecycleServiceClient> lc_client)
{rclcpp::WallRate time_between_state_changes(0.1); // 10s// configure{if (!lc_client->change_state(lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE)) {return;}if (!lc_client->get_state()) {return;}}// activate{time_between_state_changes.sleep();if (!rclcpp::ok()) {return;}if (!lc_client->change_state(lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE)) {return;}if (!lc_client->get_state()) {return;}}// deactivate{time_between_state_changes.sleep();if (!rclcpp::ok()) {return;}if (!lc_client->change_state(lifecycle_msgs::msg::Transition::TRANSITION_DEACTIVATE)) {return;}if (!lc_client->get_state()) {return;}}// activate it again{time_between_state_changes.sleep();if (!rclcpp::ok()) {return;}if (!lc_client->change_state(lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE)) {return;}if (!lc_client->get_state()) {return;}}// and deactivate it again{time_between_state_changes.sleep();if (!rclcpp::ok()) {return;}if (!lc_client->change_state(lifecycle_msgs::msg::Transition::TRANSITION_DEACTIVATE)) {return;}if (!lc_client->get_state()) {return;}}// we cleanup{time_between_state_changes.sleep();if (!rclcpp::ok()) {return;}if (!lc_client->change_state(lifecycle_msgs::msg::Transition::TRANSITION_CLEANUP)) {return;}if (!lc_client->get_state()) {return;}}{time_between_state_changes.sleep();if (!rclcpp::ok()) {return;}if (!lc_client->change_state(lifecycle_msgs::msg::Transition::TRANSITION_UNCONFIGURED_SHUTDOWN)){return;}if (!lc_client->get_state()) {return;}}
}int main(int argc, char ** argv)
{setvbuf(stdout, NULL, _IONBF, BUFSIZ);rclcpp::init(argc, argv);auto lc_client = std::make_shared<LifecycleServiceClient>("lc_client");lc_client->init();rclcpp::executors::SingleThreadedExecutor exe;exe.add_node(lc_client);std::shared_future<void> script = std::async(std::launch::async,std::bind(callee_script, lc_client));exe.spin_until_future_complete(script);rclcpp::shutdown();return 0;
}
修改 CMakeLists.txt,
add_executable(lc_service_clientsrc/lc_service_client.cpp)target_link_libraries(lc_service_client${rclcpp_lifecycle_LIBRARIES}${std_msgs_LIBRARIES})install(TARGETScamera_nodedisplay_nodelc_service_clientDESTINATION lib/${PROJECT_NAME})
编译并运行,
# Build
colcon build --packages-select camera_node# Run camera node - Terminal 1
ros2 run camera_node camera_node# Run display node - Terminal 2
ros2 run camera_node display_node # Run service_client - Terminal 3
ros2 run camera_node lc_service_client
六、总结
在这篇文章中,我们讨论了 ROS2 生命周期接口。生命周期界面可以更轻松地管理不同软件组件(如节点)的生命周期。
提供了使用生命周期接口实现相机节点的示例,演示了此接口如何更好地控制相机节点的状态,并允许依赖于它的其他组件监视其状态并采取相应的操作。总体而言,在 ROS2 中使用生命周期接口可以大大简化软件组件的管理,并提高基于 ROS 的系统的整体健壮性和可靠性。
我希望这些信息对您有所帮助,并且您发现它很有用。如果您有任何问题或意见,请随时告诉我。感谢您的反馈,并很乐意帮助回答您可能遇到的任何问题。感谢您抽出宝贵时间阅读本文。
我总是在LinkedIn上分享有趣的文章和更新,所以如果您想随时了解情况,请随时在平台上关注我。杰加特桑·尚穆甘