服务
topic 有什么缺陷?其实就像没有中断的轮休系统,比较占资源。
服务是 sub 主动请求数据时 pub 才提供数据。
- 同步机制,因为 sub 先请求。
- 单服务端,可以有多个客户端。
- .srv 文件定义请求和数据结构。
加法求和
客户端发送两个数字以及求和请求,服务端求和发回来。
$ ros2 run learning_service service_adder_server
$ ros2 run learning_service service_adder_client 3 4
[INFO] [1692000933.465148982] [service_adder_client]: Result of add_two_ints: for 3 + 4 = 7
服务端代码:模板基本差不多,就是服务创建的时候要规定服务接口,这里接口是自定义的 AddTwoInts。
#!/usr/bin/env python3
# -*- coding: utf-8 -*-
"""
@作者: 古月居(www.guyuehome.com)
@说明: ROS2服务示例-提供加法器的服务器处理功能
"""
import rclpy # ROS2 Python接口库
from rclpy.node import Node # ROS2 节点类
from learning_interface.srv import AddTwoInts # 自定义的服务接口
class adderServer(Node):
def __init__(self, name):
super().__init__(name) # ROS2节点父类初始化
self.srv = self.create_service(AddTwoInts, 'add_two_ints', self.adder_callback) # 创建服务器对象(接口类型、服务名、服务器回调函数)
def adder_callback(self, request, response): # 创建回调函数,执行收到请求后对数据的处理
response.sum = request.a + request.b # 完成加法求和计算,将结果放到反馈的数据中
self.get_logger().info('Incoming request\na: %d b: %d' % (request.a, request.b)) # 输出日志信息,提示已经完成加法求和计算
return response # 反馈应答信息
def main(args=None): # ROS2节点主入口main函数
rclpy.init(args=args) # ROS2 Python接口初始化
node = adderServer("service_adder_server") # 创建ROS2节点对象并进行初始化
rclpy.spin(node) # 循环等待ROS2退出
node.destroy_node() # 销毁节点对象
rclpy.shutdown() # 关闭ROS2 Python接口
客户端:异步发送请求,就是不是发完一直在等返回值,而是发完可以继续做其他处理。
class adderClient(Node):
def __init__(self, name):
super().__init__(name) # ROS2节点父类初始化
self.client = self.create_client(AddTwoInts, 'add_two_ints') # 创建服务客户端对象(服务接口类型,服务名)
while not self.client.wait_for_service(timeout_sec=1.0): # 循环等待服务器端成功启动
self.get_logger().info('service not available, waiting again...')
self.request = AddTwoInts.Request() # 创建服务请求的数据对象
def send_request(self): # 创建一个发送服务请求的函数
self.request.a = int(sys.argv[1])
self.request.b = int(sys.argv[2])
self.future = self.client.call_async(self.request) # 异步方式发送服务请求
def main(args=None):
rclpy.init(args=args) # ROS2 Python接口初始化
node = adderClient("service_adder_client") # 创建ROS2节点对象并进行初始化
node.send_request() # 发送服务请求
while rclpy.ok(): # ROS2系统正常运行
rclpy.spin_once(node) # 循环执行一次节点
if node.future.done(): # 数据是否处理完成
try:
response = node.future.result() # 接收服务器端的反馈数据
except Exception as e:
node.get_logger().info(
'Service call failed %r' % (e,))
else:
node.get_logger().info( # 将收到的反馈信息打印输出
'Result of add_two_ints: for %d + %d = %d' %
(node.request.a, node.request.b, response.sum))
break
node.destroy_node() # 销毁节点对象
rclpy.shutdown() # 关闭ROS2 Python接口
运行方式:客户端传入数据,服务端计算后返回给客户端输出。
$ ros2 run learning_service servise_adder_server
$ ros2 run learning_service servise_adder_client 1 2
获取物品位置
基于前面的物品识别。客户端发送位置请求的时候可以获取到当前物体位置。
服务端代码:
class ImageSubscriber(Node):
def __init__(self, name):
super().__init__(name) # ROS2节点父类初始化
self.sub = self.create_subscription(
Image, 'image_raw', self.listener_callback, 10) # 创建订阅者对象(消息类型、话题名、订阅者回调函数、队列长度)
self.cv_bridge = CvBridge() # 创建一个图像转换对象,用于OpenCV图像与ROS的图像消息的互相转换
self.srv = self.create_service(GetObjectPosition, # 创建服务器对象(接口类型、服务名、服务器回调函数)
'get_target_position',
self.object_position_callback)
self.objectX = 0
self.objectY = 0
def object_detect(self, image):
hsv_img = cv2.cvtColor(image, cv2.COLOR_BGR2HSV) # 图像从BGR颜色模型转换为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') # 输出日志信息,提示已进入回调函数
image = self.cv_bridge.imgmsg_to_cv2(data, 'bgr8') # 将ROS的图像消息转化成OpenCV图像
self.object_detect(image) # 苹果检测
def object_position_callback(self, request, response): # 创建回调函数,执行收到请求后对数据的处理
if request.get == True:
response.x = self.objectX # 目标物体的XY坐标
response.y = self.objectY
self.get_logger().info('Object position\nx: %d y: %d' %
(response.x, response.y)) # 输出日志信息,提示已经反馈
else:
response.x = 0
response.y = 0
self.get_logger().info('Invalid command') # 输出日志信息,提示已经反馈
return response
def main(args=None): # ROS2节点主入口main函数
rclpy.init(args=args) # ROS2 Python接口初始化
node = ImageSubscriber("service_object_server") # 创建ROS2节点对象并进行初始化
rclpy.spin(node) # 循环等待ROS2退出
node.destroy_node() # 销毁节点对象
rclpy.shutdown() # 关闭ROS2 Python接口
客户端代码:
class objectClient(Node):
def __init__(self, name):
super().__init__(name) # ROS2节点父类初始化
self.client = self.create_client(GetObjectPosition, 'get_target_position')
while not self.client.wait_for_service(timeout_sec=1.0):
self.get_logger().info('service not available, waiting again...')
self.request = GetObjectPosition.Request()
def send_request(self):
self.request.get = True
self.future = self.client.call_async(self.request)
def main(args=None):
rclpy.init(args=args) # ROS2 Python接口初始化
node = objectClient("service_object_client") # 创建ROS2节点对象并进行初始化
node.send_request()
while rclpy.ok():
rclpy.spin_once(node)
if node.future.done():
try:
response = node.future.result()
except Exception as e:
node.get_logger().info(
'Service call failed %r' % (e,))
else:
node.get_logger().info(
'Result of object position:\n x: %d y: %d' %
(response.x, response.y))
break
node.destroy_node() # 销毁节点对象
rclpy.shutdown() # 关闭ROS2 Python接口
和之前物品识别的区别:之前物品识别是 sub 订阅摄像头,现在我们让 pub 订阅摄像头,sub 只负责发出物品位置服务请求获取当前物品位置。
这里逻辑是 client 把 get 置为 true 表示想要获取物体位置,服务端按接口给 xy 坐标赋值。
接口文件定义如下:
# GetObjectPosition.srv
bool get # 获取目标位置的指令
---
int32 x # 目标的X坐标
int32 y # 目标的Y坐标
三横线上下是请求和应答。
可以通过 ros2 service type 服务名
来查看接口。
也可以通过命令行给服务传参。
$ ros2 service call /get_target_position learning_interface/srv/GetObjectPosition "get: True"
requester: making request: learning_interface.srv.GetObjectPosition_Request(get=True)
response:
learning_interface.srv.GetObjectPosition_Response(x=497, y=458)
话题 服务是最通用的两种通讯方式,前者适合传感器类单向通信,后者适合一问一答同步性高的通信。