話題通信接口的定義也是類似的,繼續(xù)從之前的機器視覺案例中來衍生,我們想把服務換成話題,周期發(fā)布目標識別的位置,不管有沒有人需要。
運行效果
現(xiàn)在我們會運行三個節(jié)點:
第一個節(jié)點,將驅(qū)動相機并發(fā)布圖像話題,此時的話題數(shù)據(jù)使用的是ROS中標準定義的Image圖像消息;
第二個節(jié)點,會運行視覺識別功能,識別目標的位置,這個位置我們希望封裝成話題消息,發(fā)布出去,誰需要使用誰就來訂閱;
第三個節(jié)點,訂閱位置話題,打印到終端中。
啟動三個終端,分別運行以上節(jié)點:
$ ros2 run usb_cam usb_cam_node_exe$ ros2 run learning_topic interface_object_pub$ ros2 run learning_topic interface_object_sub
接口定義
在這個例程中,我們使用ObjectPosition.msg定義了服務通信的接口:
learning_interface/msg/ObjectPosition.msg
int32 x # 表示目標的X坐標int32 y # 表示目標的Y坐標
話題消息的內(nèi)容是一個位置,我們使用x、y坐標值進行描述。
完成定義后,還需要在功能包的CMakeLists.txt中配置編譯選項,讓編譯器在編譯過程中,根據(jù)接口定義,自動生成不同語言的代碼:
...find_package(rosidl_default_generators REQUIRED)rosidl_generate_interfaces(${PROJECT_NAME} "msg/ObjectPosition.msg")...
程序調(diào)用
我們在代碼中再來重點看下接口的使用方法。
發(fā)布者接口調(diào)用
learning_topic/interface_object_pub.py
#!/usr/bin/env python3# -*- coding: utf-8 -*-"""@作者: 古月居@說明: ROS2接口示例-發(fā)布目標位置"""import rclpy # ROS2 Python接口庫from rclpy.node import Node # ROS2 節(jié)點類from sensor_msgs.msg import Image # 圖像消息類型from cv_bridge import CvBridge # ROS與OpenCV圖像轉(zhuǎn)換類import cv2 # Opencv圖像處理庫import numpy as np # Python數(shù)值計算庫from learning_interface.msg import ObjectPosition # 自定義的目標位置消息lower_red = np.array([0, 90, 128]) # 紅色的HSV閾值下限upper_red = np.array([180, 255, 255]) # 紅色的HSV閾值上限"""創(chuàng)建一個訂閱者節(jié)點"""class ImageSubscriber(Node): def __init__(self, name): super().__init__(name) # ROS2節(jié)點父類初始化 self.sub = self.create_subscription( Image, 'image_raw', self.listener_callback, 10) # 創(chuàng)建訂閱者對象(消息類型、話題名、訂閱者回調(diào)函數(shù)、隊列長度) self.pub = self.create_publisher( ObjectPosition, "object_position", 10) # 創(chuàng)建發(fā)布者對象(消息類型、話題名、隊列長度) self.cv_bridge = CvBridge() # 創(chuàng)建一個圖像轉(zhuǎn)換對象,用于OpenCV圖像與ROS的圖像消息的互相轉(zhuǎn)換 self.objectX = 0 self.objectY = 0 def object_detect(self, image): hsv_img = cv2.cvtColor(image, cv2.COLOR_BGR2HSV) # 圖像從BGR顏色模型轉(zhuǎn)換為HSV模型 mask_red = cv2.inRange(hsv_img, lower_red, upper_red) # 圖像二值化 contours, hierarchy = cv2.findContours( mask_red, cv2.RETR_LIST, cv2.CHAIN_APPROX_NONE) # 圖像中輪廓檢測 for cnt in contours: # 去除一些輪廓面積太小的噪聲 if cnt.shape[0] < 150: continue (x, y, w, h) = cv2.boundingRect(cnt) # 得到蘋果所在輪廓的左上角xy像素坐標及輪廓范圍的寬和高 cv2.drawContours(image, [cnt], -1, (0, 255, 0), 2) # 將蘋果的輪廓勾勒出來 cv2.circle(image, (int(x+w/2), int(y+h/2)), 5, # 將蘋果的圖像中心點畫出來 (0, 255, 0), -1) self.objectX = int(x+w/2) self.objectY = int(y+h/2) cv2.imshow("object", image) # 使用OpenCV顯示處理后的圖像效果 cv2.waitKey(50) def listener_callback(self, data): self.get_logger().info('Receiving video frame') # 輸出日志信息,提示已進入回調(diào)函數(shù) image = self.cv_bridge.imgmsg_to_cv2(data, 'bgr8') # 將ROS的圖像消息轉(zhuǎn)化成OpenCV圖像 position = ObjectPosition() self.object_detect(image) # 蘋果檢測 position.x, position.y = int(self.objectX), int(self.objectY) self.pub.publish(position) # 發(fā)布目標位置def main(args=None): # ROS2節(jié)點主入口main函數(shù) rclpy.init(args=args) # ROS2 Python接口初始化 node = ImageSubscriber("topic_webcam_sub") # 創(chuàng)建ROS2節(jié)點對象并進行初始化 rclpy.spin(node) # 循環(huán)等待ROS2退出 node.destroy_node() # 銷毀節(jié)點對象 rclpy.shutdown() # 關閉ROS2 Python接口
訂閱者接口調(diào)用
learning_topic/interface_object_sub.py
#!/usr/bin/env python3# -*- coding: utf-8 -*-"""@作者: 古月居@說明: ROS2接口示例-訂閱目標位置"""import rclpy # ROS2 Python接口庫from rclpy.node import Node # ROS2 節(jié)點類from std_msgs.msg import String # 字符串消息類型from learning_interface.msg import ObjectPosition # 自定義的目標位置消息"""創(chuàng)建一個訂閱者節(jié)點"""class SubscriberNode(Node): def __init__(self, name): super().__init__(name) # ROS2節(jié)點父類初始化 self.sub = self.create_subscription( ObjectPosition, "/object_position", self.listener_callback, 10) # 創(chuàng)建訂閱者對象(消息類型、話題名、訂閱者回調(diào)函數(shù)、隊列長度 def listener_callback(self, msg): # 創(chuàng)建回調(diào)函數(shù),執(zhí)行收到話題消息后對數(shù)據(jù)的處理 self.get_logger().info('Target Position: "(%d, %d)"' % (msg.x, msg.y))# 輸出日志信息,提示訂閱收到的話題消息def main(args=None): # ROS2節(jié)點主入口main函數(shù) rclpy.init(args=args) # ROS2 Python接口初始化 node = SubscriberNode("interface_position_sub") # 創(chuàng)建ROS2節(jié)點對象并進行初始化 rclpy.spin(node) # 循環(huán)等待ROS2退出 node.destroy_node() # 銷毀節(jié)點對象 rclpy.shutdown() # 關閉ROS2 Python接口
接口命令行操作
接口命令的常用操作如下:
$ ros2 interface list # 查看系統(tǒng)接口列表$ ros2 interface sh
-
接口
+關注
關注
33文章
8612瀏覽量
151290 -
相機
+關注
關注
4文章
1354瀏覽量
53656 -
通信接口
+關注
關注
3文章
239瀏覽量
30999 -
ROS
+關注
關注
1文章
278瀏覽量
17022
發(fā)布評論請先 登錄
相關推薦
評論