摄像头画面传输

  1. import rclpy # ROS2 Python接口库
  2. from rclpy.node import Node # ROS2 节点类
  3. from sensor_msgs.msg import Image # 图像消息类型
  4. from cv_bridge import CvBridge # ROS与OpenCV图像转换类
  5. import cv2 # Opencv图像处理库
  6. """
  7. 创建一个发布者节点
  8. """
  9. class ImagePublisher(Node):
  10. def __init__(self, name):
  11. super().__init__(name) # ROS2节点父类初始化
  12. self.publisher_ = self.create_publisher(Image, 'image_raw', 10) # 创建发布者对象(消息类型、话题名、队列长度)
  13. self.timer = self.create_timer(0.1, self.timer_callback) # 创建一个定时器(单位为秒的周期,定时执行的回调函数)
  14. self.cap = cv2.VideoCapture(0) # 创建一个视频采集对象,驱动相机采集图像(相机设备号)
  15. self.cv_bridge = CvBridge() # 创建一个图像转换对象,用于稍后将OpenCV的图像转换成ROS的图像消息
  16. def timer_callback(self):
  17. ret, frame = self.cap.read() # 一帧一帧读取图像
  18. if ret == True: # 如果图像读取成功
  19. self.publisher_.publish(
  20. self.cv_bridge.cv2_to_imgmsg(frame, 'bgr8')) # 发布图像消息
  21. self.get_logger().info('Publishing video frame') # 输出日志信息,提示已经完成图像话题发布
  22. def main(args=None): # ROS2节点主入口main函数
  23. rclpy.init(args=args) # ROS2 Python接口初始化
  24. node = ImagePublisher("topic_webcam_pub") # 创建ROS2节点对象并进行初始化
  25. rclpy.spin(node) # 循环等待ROS2退出
  26. node.destroy_node() # 销毁节点对象
  27. rclpy.shutdown() # 关闭ROS2 Python接口

摄像头画面订阅

  1. import rclpy # ROS2 Python接口库
  2. from rclpy.node import Node # ROS2 节点类
  3. from sensor_msgs.msg import Image # 图像消息类型
  4. from cv_bridge import CvBridge # ROS与OpenCV图像转换类
  5. import cv2 # Opencv图像处理库
  6. import numpy as np # Python数值计算库
  7. lower_red = np.array([0, 90, 128]) # 红色的HSV阈值下限
  8. upper_red = np.array([180, 255, 255]) # 红色的HSV阈值上限
  9. """
  10. 创建一个订阅者节点
  11. """
  12. class ImageSubscriber(Node):
  13. def __init__(self, name):
  14. super().__init__(name) # ROS2节点父类初始化
  15. self.sub = self.create_subscription(
  16. Image, 'image_raw', self.listener_callback, 10) # 创建订阅者对象(消息类型、话题名、订阅者回调函数、队列长度)
  17. self.cv_bridge = CvBridge() # 创建一个图像转换对象,用于OpenCV图像与ROS的图像消息的互相转换
  18. def object_detect(self, image):
  19. hsv_img = cv2.cvtColor(image, cv2.COLOR_BGR2HSV) # 图像从BGR颜色模型转换为HSV模型
  20. mask_red = cv2.inRange(hsv_img, lower_red, upper_red) # 图像二值化
  21. contours, hierarchy = cv2.findContours(
  22. mask_red, cv2.RETR_LIST, cv2.CHAIN_APPROX_NONE) # 图像中轮廓检测
  23. for cnt in contours: # 去除一些轮廓面积太小的噪声
  24. if cnt.shape[0] < 150:
  25. continue
  26. (x, y, w, h) = cv2.boundingRect(cnt) # 得到苹果所在轮廓的左上角xy像素坐标及轮廓范围的宽和高
  27. cv2.drawContours(image, [cnt], -1, (0, 255, 0), 2) # 将苹果的轮廓勾勒出来
  28. cv2.circle(image, (int(x+w/2), int(y+h/2)), 5,
  29. (0, 255, 0), -1) # 将苹果的图像中心点画出来
  30. cv2.imshow("object", image) # 使用OpenCV显示处理后的图像效果
  31. cv2.waitKey(10)
  32. def listener_callback(self, data):
  33. self.get_logger().info('Receiving video frame') # 输出日志信息,提示已进入回调函数
  34. image = self.cv_bridge.imgmsg_to_cv2(data, 'bgr8') # 将ROS的图像消息转化成OpenCV图像
  35. self.object_detect(image) # 苹果检测
  36. def main(args=None): # ROS2节点主入口main函数
  37. rclpy.init(args=args) # ROS2 Python接口初始化
  38. node = ImageSubscriber("topic_webcam_sub") # 创建ROS2节点对象并进行初始化
  39. rclpy.spin(node) # 循环等待ROS2退出
  40. node.destroy_node() # 销毁节点对象
  41. rclpy.shutdown() # 关闭ROS2 Python接口

摄像头物体识别

接收摄像头的数据并进行识别,将识别的结果发布出去

  1. import rclpy # ROS2 Python接口库
  2. from rclpy.node import Node # ROS2 节点类
  3. from sensor_msgs.msg import Image # 图像消息类型
  4. from cv_bridge import CvBridge # ROS与OpenCV图像转换类
  5. import cv2 # Opencv图像处理库
  6. import numpy as np # Python数值计算库
  7. from learning_interface.msg import ObjectPosition # 自定义的目标位置消息
  8. lower_red = np.array([0, 90, 128]) # 红色的HSV阈值下限
  9. upper_red = np.array([180, 255, 255]) # 红色的HSV阈值上限
  10. """
  11. 创建一个订阅者节点
  12. """
  13. class ImageSubscriber(Node):
  14. def __init__(self, name):
  15. super().__init__(name) # ROS2节点父类初始化
  16. self.sub = self.create_subscription(
  17. Image, 'image_raw', self.listener_callback, 10) # 创建订阅者对象(消息类型、话题名、订阅者回调函数、队列长度)
  18. self.pub = self.create_publisher(
  19. ObjectPosition, "object_position", 10) # 创建发布者对象(消息类型、话题名、队列长度)
  20. self.cv_bridge = CvBridge() # 创建一个图像转换对象,用于OpenCV图像与ROS的图像消息的互相转换
  21. self.objectX = 0
  22. self.objectY = 0
  23. def object_detect(self, image):
  24. hsv_img = cv2.cvtColor(image, cv2.COLOR_BGR2HSV) # 图像从BGR颜色模型转换为HSV模型
  25. mask_red = cv2.inRange(hsv_img, lower_red, upper_red) # 图像二值化
  26. contours, hierarchy = cv2.findContours(
  27. mask_red, cv2.RETR_LIST, cv2.CHAIN_APPROX_NONE) # 图像中轮廓检测
  28. for cnt in contours: # 去除一些轮廓面积太小的噪声
  29. if cnt.shape[0] < 150:
  30. continue
  31. (x, y, w, h) = cv2.boundingRect(cnt) # 得到苹果所在轮廓的左上角xy像素坐标及轮廓范围的宽和高
  32. cv2.drawContours(image, [cnt], -1, (0, 255, 0), 2) # 将苹果的轮廓勾勒出来
  33. cv2.circle(image, (int(x+w/2), int(y+h/2)), 5, # 将苹果的图像中心点画出来
  34. (0, 255, 0), -1)
  35. self.objectX = int(x+w/2)
  36. self.objectY = int(y+h/2)
  37. cv2.imshow("object", image) # 使用OpenCV显示处理后的图像效果
  38. cv2.waitKey(50)
  39. def listener_callback(self, data):
  40. self.get_logger().info('Receiving video frame') # 输出日志信息,提示已进入回调函数
  41. image = self.cv_bridge.imgmsg_to_cv2(data, 'bgr8') # 将ROS的图像消息转化成OpenCV图像
  42. position = ObjectPosition()
  43. self.object_detect(image) # 苹果检测
  44. position.x, position.y = int(self.objectX), int(self.objectY)
  45. self.pub.publish(position) # 发布目标位置
  46. def main(args=None): # ROS2节点主入口main函数
  47. rclpy.init(args=args) # ROS2 Python接口初始化
  48. node = ImageSubscriber("topic_webcam_sub") # 创建ROS2节点对象并进行初始化
  49. rclpy.spin(node) # 循环等待ROS2退出
  50. node.destroy_node() # 销毁节点对象
  51. rclpy.shutdown() # 关闭ROS2 Python接口

接收识别的结果,并打印结果

  1. import rclpy # ROS2 Python接口库
  2. from rclpy.node import Node # ROS2 节点类
  3. from std_msgs.msg import String # 字符串消息类型
  4. from learning_interface.msg import ObjectPosition # 自定义的目标位置消息
  5. """
  6. 创建一个订阅者节点
  7. """
  8. class SubscriberNode(Node):
  9. def __init__(self, name):
  10. super().__init__(name) # ROS2节点父类初始化
  11. self.sub = self.create_subscription(\
  12. ObjectPosition, "/object_position", self.listener_callback, 10) # 创建订阅者对象(消息类型、话题名、订阅者回调函数、队列长度
  13. def listener_callback(self, msg): # 创建回调函数,执行收到话题消息后对数据的处理
  14. self.get_logger().info('Target Position: "(%d, %d)"' % (msg.x, msg.y)) # 输出日志信息,提示订阅收到的话题消息
  15. def main(args=None): # ROS2节点主入口main函数
  16. rclpy.init(args=args) # ROS2 Python接口初始化
  17. node = SubscriberNode("interface_position_sub") # 创建ROS2节点对象并进行初始化
  18. rclpy.spin(node) # 循环等待ROS2退出
  19. node.destroy_node() # 销毁节点对象
  20. rclpy.shutdown() # 关闭ROS2 Python接口

ros2的摄像头节点

常用的usb相机驱动一般都是通用的,ROS中也集成了usb相机的标准驱动,我们只需要通过这样一行指令,就可以安装好,无论你用什么样的相机,只要符合usb接口协议,就可以直接使用ROS中的相机驱动节点,发布标准的图像话题了。

  1. sudo apt install ros-humble-usb-cam

打开摄像头节点

  1. ros2 run usb_cam usb_cam_node_exe