#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import CompressedImage
from cv_bridge import CvBridge
import cv2
import numpy as np
from rclpy.qos import QoSProfile, QoSReliabilityPolicy, QoSDurabilityPolicy
class ImagePublisher(Node):
def __init__(self):
# 初始化节点,节点名称为 'image_publisher'
super().__init__('image_publisher')
# 创建一个发布者,发布到 /image_data 话题,消息类型为 sensor_msgs/Image
self.publisher_ = self.create_publisher(CompressedImage, '/image', 10)
# 设置发布频率(每秒1次)
self.timer_period = 1.0 # 1秒
self.timer = self.create_timer(self.timer_period, self.timer_callback)
# 用于将OpenCV图像转换为ROS 2图像消息的桥接器
self.bridge = CvBridge()
# 计数器,用于生成不同的图像
self.count = 0
def timer_callback(self):
# 生成一个简单的图像(例如:渐变图像)
width, height = 640, 480
image = np.zeros((height, width, 3), dtype=np.uint8)
cv2.rectangle(image, (0, 0), (width, height), (0, 255, 0), -1)
cv2.putText(image, f"Count: {self.count}", (50, 50), cv2.FONT_HERSHEY_SIMPLEX, 1, (255, 255, 255), 2)
# 将OpenCV图像转换为ROS 2图像消息
ros_image = self.bridge.cv2_to_imgmsg(image, encoding="bgr8")
# 发布图像消息
self.publisher_.publish(ros_image)
self.get_logger().info(f"发布图像数据: Count {self.count}")
# 增加计数器
self.count += 1
def main(args=None):
# 初始化ROS 2
rclpy.init(args=args)
# 创建发布者节点
image_publisher = ImagePublisher()
# 运行节点
rclpy.spin(image_publisher)
# 销毁节点并关闭ROS 2
image_publisher.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()raceback (most recent call last):
File "/home/hxs/dev/image_pub.py", line 61, in <module>
main()
File "/home/hxs/dev/image_pub.py", line 54, in main
rclpy.spin(image_publisher)
File "/opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/__init__.py", line 226, in spin
executor.spin_once()
File "/opt/ros/humble/lo