【生命周期节点】
【生命周期节点】
※特点:状态可被读取和设置
注:战队现使用手写心跳节点Heartbeat,用于监测节点运行状态
命令行操作
//启动官方示例
$ ros2 run lifecycle lifecycle_talker
//订阅话题并查看服务列表
$ ros2 topic list
/lc_talker/transition_event
$ ros2 topic echo /lc_talker/transition_event
$ ros2 service list
/lc_talker/change_state
/lc_talker/describe_parameters
/lc_talker/get_available_states
/lc_talker/get_available_transitions
/lc_talker/get_parameter_types
/lc_talker/get_parameters
/lc_talker/get_state
/lc_talker/get_transition_graph
/lc_talker/list_parameters
/lc_talker/set_parameters
/lc_talker/set_parameters_atomically
生命周期节点的状态设置和获取通过服务通信进行
change_state:改变节点状态
get_state:获取当前状态
//获取lc_talker节点的当前状态
//【传统方式】
$ ros2 service call /lc_talker/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'))
//【ROS2工具】
$ ros2 lifecycle get /lc_talker
unconfigured [1]
生命周期节点四种可保持状态:
待配置 Unconfigured
待激活 Inactive
已激活 Active
已结束 Finalized
中间转换状态
配置中 Configuring
清理中 CleaningUp
关闭中 ShuttingDown
激活中 Activating
失活中 Deactivating
错误处理中 ErrorProcessing
//查看可切换的状态
$ ros2 lifecycle list /lc_talker

可用的指令:
configure 配置
shutdown 关闭
activate 激活
deactivate 失活
cleanup 清理
destory 销毁
//改变节点状态:set命令/调用change_state服务
$ ros2 lifecycle set /lc_talker configure//配置



//激活节点
$ ros2 lifecycle set /lc_talker activate



$ ros2 topic list
/lc_talker/transition_event
/lifecycle_chatter
$ ros2 topic echo /lifecycle_chatter

状态改变请求
成功 SUCCESS
失败 FAILURE
错误 ERROR
处理图示

※Configure->Inactive->Active
代码操作
#include"rclcpp/rclcpp.hpp"
#include"rclcpp_lifecycle/lifecycle_node.hpp"
//替换变量名称
using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
class LearnLifeCycleNode : public rclcpp_lifecycle::LifecycleNode{
public:
LearnLifeCycleNode() : rclcpp_lifecycle::LifecycleNode("lifecyclenode"){
timer_period_=1.0;
timer_=nullptr;
RCLCPP_INFO(get_logger(),"%s:已创建",get_name());
}
//继承指令
//override:对基类中同名虚函数的重写
CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override{
//明确告诉编译器忽略变量 state,即使它在函数中未被实际使用,也避免编译器发出未使用变量的警告
(void) state;
timer_period_=1.0;
RCLCPP_INFO(get_logger(),"on_configure():配置周期timer_period");
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override{
(void) state;
timer_=create_wall_timer(
std::chrono::seconds(static_cast<int>(timer_period_)),//static_cast<int>类型转换
[this](){RCLCPP_INFO(get_logger(),"定时器输出进行中...");}
);
RCLCPP_INFO(get_logger(),"on_activate():处理激活指令,创建定时器");
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override{
(void) state;
timer_.reset();
RCLCPP_INFO(get_logger(),"on_deactivate():处理失活指令,停止定时器");
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override{
(void) state;
timer_.reset();
RCLCPP_INFO(get_logger(),"on_deactivate():处理关闭指令");
return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
}
private:
rclcpp::TimerBase::SharedPtr timer_;//定时器
double timer_period_;//定时器状态
};
int main(int argc,char** argv){
rclcpp::init(argc,argv);
auto node=std::make_shared<LearnLifeCycleNode>();
rclcpp::spin(node->get_node_base_interface());//get_node_base_interface 函数返回一个指向节点基础接口的指针
rclcpp::shutdown();
return 0;
}
运行


样例
https://blog.csdn.net/weixin_64037619/article/details/143099050?ops_request_misc=%257B%2522request%255Fid%2522%253A%2522ca4f507fae11f0641626c05c67de2e3f%2522%252C%2522scm%2522%253A%252220140713.130102334..%2522%257D&request_id=ca4f507fae11f0641626c05c67de2e3f&biz_id=0&utm_medium=distribute.pc_search_result.none-task-blog-2~all~sobaiduend~default-1-143099050-null-null.142^v101^pc_search_result_base5&utm_term=%E7%94%9F%E5%91%BD%E5%91%A8%E6%9C%9F%E8%8A%82%E7%82%B9&spm=1018.2226.3001.4187
红绿灯生命周期的封装
/*
需求:红绿灯生命周期
流程:
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;
}

浙公网安备 33010602011771号