Managed nodes
生命周期的介绍
生命周期(或更正确地说,管理)节点是ROS 2独有的。它们是包含状态机转换的节点,用于ROS 2服务器的启动和关闭。这有助于ROS系统在启动和关闭时的确定性行为。它还帮助用户以合理的方式构建商业用途和调试的程序。
当节点启动时,它处于未配置状态,只处理节点的构造函数,这不应包含任何ROS网络设置或参数读取。通过启动系统,或提供的生命周期管理器,节点需要通过配置转换到非活动状态。之后,通过激活阶段转换可以激活节点。
这个状态将允许节点处理信息并完全设置以运行。配置阶段,触发on_configure()方法,将设置所有参数、ROS网络接口,对于安全系统,所有动态分配的内存。激活阶段,触发on_activate()方法,将激活ROS网络接口并设置程序中的任何状态以开始处理信息。
要关闭,我们转换到去激活,清理,关闭,并最终处于完成状态。网络接口被停用并停止处理,按这些阶段分别释放内存,干净地退出。
生命周期节点框架在这个项目中得到了广泛的使用,所有服务器都利用它。对于所有ROS系统,如果可能的话,最好使用生命周期节点。
在Nav2中,我们使用LifecycleNodes的包装器,nav2_util LifecycleNode。这个包装器简化了LifecycleNodes的许多复杂性,适用于典型应用。它还包括了与生命周期管理器的bond连接,以确保服务器转换后仍然保持活动。如果服务器崩溃,它会让生命周期管理器知道,并将系统转换到下,以防止严重故障。
生命周期节点的状态
LifecycleNode 节点的状态主要分为基本状态(Primary States)和切换状态(Transition States)。主要状态是任何节点都可以做相应的任务的稳态,切换状态切换过程中短暂的临时状态。这些中间状态的结果用于指示两个主要状态之间的转换是否成功。主要由5个部分组成:
-
状态机
-
状态
-
标准接口
-
命令行接口(CLI)
-
启动文件
生命周期节点基于一个有限状态机,具体包含以下主要状态:
-
未配置(Unconfigured):
节点初始状态。在此状态下,节点尚未完成初始化。
-
配置(Configured):
节点已被配置但尚未激活。在这一状态下,节点已经准备好所有必需的资源和配置,准备进入激活状态。
-
激活(Active):
节点正在活跃运行。在这一状态下,节点已完全激活并执行其主要功能。
-
非活跃(Inactive):
节点未在活跃执行。这是从激活状态暂停到的状态,可用于临时暂停节点活动。
-
关闭(Shutting down):
节点正在关闭。在此过程中,节点会清理所有资源,准备停止运行。
-
终止(Finalized):
节点已完全停止并进行了资源清理。
-
错误处理(Error processing):
如果在生命周期的任何阶段发生错误,节点将进入此状态。在这一状态下,可以进行错误诊断和恢复操作。
生命周期转换
节点状态之间的转换通过一组预定义的转换来管理,包括:
-
配置(configure):
从未配置到配置状态。
-
清理(cleanup):
从配置回到未配置状态。
-
激活(activate):
从配置到激活状态。
-
去激活(deactivate):
从激活到非活跃状态。
-
关闭(shutdown):
从任何状态到关闭状态。
案例1
创建生命周期节点,每一次切换状态打印相关配置话题
# 创建功能包
ros2 pkg create lifecycle_node --build-type ament_cmake --dependencies rclcpp sensor_msgs geometry_msgs OpenCV cv_bridge image_transport nav2_msgs tf2_ros base_interfaces_demo rclcpp_lifecycle --node-name lifecycle_demo
lifecycle_demo.cpp
/*
需求:简单实现生命周期节点的实现
流程:
1.导包;
2.初始化ROS2客户端;
3.自定义节点类;
4.调用spain函数,并传入节点对象;
5.资源释放。
*/
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_lifecycle/lifecycle_node.hpp>
// 3.定义节点类;
class SensorLifecycleNode : public rclcpp_lifecycle::LifecycleNode
{
public:
SensorLifecycleNode() : LifecycleNode("sensorLifecycleNode")
{
RCLCPP_INFO(this->get_logger(), "节点创建成功!!!");
}
/*
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn 是方法的返回类型,它是一个枚举类型,用于指示配置操作的结果。常用的返回值包括 SUCCESS 和 FAILURE,分别表示配置成功和失败。
on_configure 是一个生命周期管理回调方法,这个名称由ROS 2生命周期节点的约定定义,特定于配置阶段的处理。
const rclcpp_lifecycle::State & 是一个引用传递的参数,它提供了调用此回调时节点所处的当前状态的信息。
*/
// 当节点配置时调用回调函数
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure(const rclcpp_lifecycle::State &)
{
RCLCPP_INFO(this->get_logger(), "Sensor configured.");
// 返回成功状态
return LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
// 当节点激活时调用的回调函数
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate(const rclcpp_lifecycle::State &)
{
RCLCPP_INFO(this->get_logger(), "Sensor activate.");
return LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
// 当节点停用时调用回调函数
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &)
{
RCLCPP_INFO(this->get_logger(), "Sensor deactivated.");
return LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
// 当节点清理时调用回调函数
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &)
{
RCLCPP_INFO(this->get_logger(), "Sensor cleaned up.");
return LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
// 当节点关闭时调用的回调函数
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &)
{
// 在控制台输出传感器关闭的信息
RCLCPP_INFO(this->get_logger(), "Sensor shutdown.");
// 返回成功状态
return LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
private:
};
int main(int argc, char *argv[])
{
// 2.初始化 ROS2 客户端;
rclcpp::init(argc, argv);
auto Node = std::make_shared<SensorLifecycleNode>();
// 4.调用spin函数,并传入节点对象指针。
// Node->get_node_base_interface(): 指向SensorLifecycleNode的智能指针,get_node_base_interface()是rclcpp_lifecycle::LifecycleNode类的一个成员函数,
// 它返回一个可以用于spin函数的节点基础接口指针。这个基础接口封装了节点的核心功能,使spin函数能够访问并调用节点的回调。
rclcpp::spin(Node->get_node_base_interface());
// 5.释放资源;
rclcpp::shutdown();
return 0;
}
# 编译
colcon build
# 运行
ros2 run lifecycle_node lifecycle_demo
# 终端使用命令切换状态
ros2 lifecycle set /sensorLifecycleNode configure
ros2 lifecycle set /sensorLifecycleNode activate
ros2 lifecycle set /sensorLifecycleNode deactivate
ros2 lifecycle set /sensorLifecycleNode cleanup
ros2 lifecycle set /sensorLifecycleNode shutdown
注:生命周期和image_transport库相互不兼容,所以后续将不再使用image_transport库
实战项目---红绿灯生命周期的封装
/*
需求:红绿灯生命周期
流程:
1.导包;
2.初始化ROS2客户端;
3.自定义节点类;
4.调用spain函数,并传入节点对象;
5.资源释放。
*/
#include <rclcpp/rclcpp.hpp>
#include <cv_bridge/cv_bridge.h>
#include <image_transport/image_transport.hpp>
#include <sensor_msgs/msg/image.hpp>
#include <std_msgs/msg/bool.hpp>
#include <opencv2/opencv.hpp>
#include <rclcpp_lifecycle/lifecycle_node.hpp>
#include <rclcpp_lifecycle/lifecycle_publisher.hpp>
using std::placeholders::_1;
using namespace cv;
// 3.定义节点类;
class traffic_light_status : public rclcpp_lifecycle::LifecycleNode
{
public:
traffic_light_status() : rclcpp_lifecycle::LifecycleNode("traffic_light_status")
{
// 动态调参
this->declare_parameter<int>("red_threshold_", 120);
this->declare_parameter<int>("roi_x", 220);
this->declare_parameter<int>("roi_y", 150);
this->declare_parameter<int>("roi_width", 420);
this->declare_parameter<int>("roi_hight", 190);
this->declare_parameter<int>("size_x", 20);
this->declare_parameter<int>("size_y", 20);
}
// 当节点配置时调用回调函数
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure(const rclcpp_lifecycle::State &) override
{
// rclcpp_lifecycle::LifecycleNode到rclcpp::Node的转换,使用shared_from_this()提供的智能指针直接转换,因为LifecycleNode是从Node继承来的
// 先转换为rclcpp::Node*,然后创建一个新的shared_ptr。
// 先获得裸指针,再用裸指针创建对应的std::shared_ptr<rclcpp::Node>。
// 使用dynamic_cast进行安全转换,确保转换过程中的类型安全。如果dynamic_cast失败(即如果this不是一个rclcpp::Node),它将返回nullptr。
auto raw_node_ptr = dynamic_cast<rclcpp::Node *>(this->get_node_base_interface().get());
if (!raw_node_ptr)
{
RCLCPP_ERROR(this->get_logger(), "rclcpp::Node*转换失败!!");
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::FAILURE;
}
auto node_shared_ptr = std::shared_ptr<rclcpp::Node>(raw_node_ptr);
auto it = std::make_shared<image_transport::ImageTransport>(node_shared_ptr);
image_sub_ = it->subscribe("camera2/image_raw", 1, std::bind(&traffic_light_status::imageCallback, this, _1));
traffic_light_publisher_ = this->create_publisher<std_msgs::msg::Bool>("/traffic_light_status", 10);
red_threshold_ = this->get_parameter("red_threshold_").as_int();
roi_x = this->get_parameter("roi_x").as_int();
roi_y = this->get_parameter("roi_y").as_int();
roi_width = this->get_parameter("roi_width").as_int();
roi_hight = this->get_parameter("roi_hight").as_int();
size_x = this->get_parameter("size_x").as_int();
size_y = this->get_parameter("size_y").as_int();
RCLCPP_INFO(this->get_logger(), "TrafficLightStatus node configured");
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
// 当节点激活时调用的回调函数
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate(const rclcpp_lifecycle::State &) override
{
traffic_light_publisher_->on_activate();
RCLCPP_INFO(this->get_logger(), "TrafficLightStatus node activated");
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
// 当节点停用时调用回调函数
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &) override
{
traffic_light_publisher_->on_deactivate();
RCLCPP_INFO(this->get_logger(), "TrafficLightStatus node deactivated");
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
// 当节点清理时调用回调函数
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &) override
{
image_sub_.shutdown();
traffic_light_publisher_.reset();
RCLCPP_INFO(this->get_logger(), "TrafficLightStatus node cleaned up");
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
// 当节点关闭时调用的回调函数
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &) override
{
RCLCPP_INFO(this->get_logger(), "TrafficLightStatus node shutting down");
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
private:
image_transport::Subscriber image_sub_;
rclcpp_lifecycle::LifecyclePublisher<std_msgs::msg::Bool>::SharedPtr traffic_light_publisher_;
// 动态调参
int red_threshold_;
int roi_x;
int roi_y;
int roi_width;
int roi_hight;
int size_x;
int size_y;
void imageCallback(const sensor_msgs::msg::Image::ConstSharedPtr &msg)
{
cv_bridge::CvImagePtr cv_ptr;
try
{
cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
Mat frame = cv_ptr->image;
// 检测红灯发布状态
std_msgs::msg::Bool light_status_msg;
light_status_msg.data = detectRedLight(frame);
traffic_light_publisher_->publish(light_status_msg);
waitKey(1);
}
catch (const cv_bridge::Exception &e)
{
RCLCPP_ERROR(this->get_logger(), "cv_bridge exception: %s", e.what());
}
}
bool detectRedLight(const Mat &img)
{
Mat copy_img = img.clone(); // 复制一张原图
// 裁剪图像
cv::Rect roiRect(roi_x, roi_y, roi_width, roi_hight);
// 对裁剪后的图像进行处理
cv::Mat frame_roi = copy_img(roiRect);
// imshow("红绿灯",frame_roi);
Mat bgr_channels[3]; // 分离图像通道
split(frame_roi, bgr_channels); // 分离BGR通道
Mat red_minus_green; // 红色通道减去绿色通道的结果
subtract(bgr_channels[2], bgr_channels[1], red_minus_green); // 计算红色减去绿色的结果
threshold(red_minus_green, red_minus_green, red_threshold_, 255, THRESH_BINARY); // 应用阈值
Mat element = getStructuringElement(MORPH_RECT, Size(size_x, size_y)); // 结构化元素
dilate(red_minus_green, red_minus_green, element); // 膨胀操作
// imshow("红绿灯二值图",red_minus_green);
std::vector<std::vector<Point>> contours; // 存储轮廓
findContours(red_minus_green, contours, RETR_TREE, CHAIN_APPROX_SIMPLE); // 寻找轮廓
// 计算最大红色区域的大小
double maxArea = 0;
for (const auto &contour : contours)
{
double area = contourArea(contour); // 计算每个轮廓的面积
std::cout << "area" << area << std::endl;
if (area > maxArea)
{
maxArea = area; // 更新最大面积
}
}
const double AREA_THRESHOLD = 1200; // 设定面积阈值
if (maxArea > AREA_THRESHOLD) // 如果最大面积超过阈值
{
Mat red_detection_result = Mat::zeros(img.size(), CV_8UC3); // 创建结果图像
drawContours(red_detection_result, contours, -1, Scalar(0, 0, 255), 3); // 绘制轮廓
imshow("红灯检测", red_detection_result); // 显示检测结果
waitKey(1); // 等待1毫秒
return true; // 返回真,表示检测到红色信号
}
return false;
}
};
int main(int argc, char *argv[])
{
// 2.初始化 ROS2 客户端;
rclcpp::init(argc, argv);
// 4.调用spin函数,并传入节点对象指针。
auto node = std::make_shared<traffic_light_status>();
rclcpp::spin(node->get_node_base_interface());
// 5.释放资源;
rclcpp::shutdown();
return 0;
}
# 编译
colcon build
# 运行
ros2 run lifecycle_node traffic_light_status_lifecycle
# 生命周期
ros2 lifecycle set /traffic_light_status configure
ros2 lifecycle set /traffic_light_status activate
ros2 lifecycle set /traffic_light_status deactivate
ros2 lifecycle set /traffic_light_status cleanup
ros2 lifecycle set /traffic_light_status shutdown