同步与异步服务的客户端对比 [Alyssa@6523]

级别: 中级 [Alyssa@6524]

时间: 10分钟 [Alyssa@6525]

简介

本指南旨在警告用户与Python同步的服务(service)客户端 call() API相关的风险。同步调用服务时很容易错误的导致死锁,因此我们不建议使用 call()[Alyssa@6526]

对于希望使用同步调用并意识到陷阱的有经验的用户,我们提供了一个如何正确使用 call() 的例子。我们还强调了随之而来的死锁的可能情况。 [Alyssa@6527]

因为我们建议避免同步调用,本指南还将介绍推荐的替代方法 -- 异步调用 ( call_async() ) 的特点和用法。 [待校准@6528]

C++ 服务调用API仅在异步中可用,因此本指南中的比较和示例与Python服务和客户端有关。这里给出的异步的定义通常适用于C++,但也有一些例外。 [Alyssa@6529]

1 同步调用 [Alyssa@6530]

当向服务发送请求时,同步客户端将阻瑟调用线程,直到收到响应为止; 在调用期间,该线程上不会做任何其他事情。调用可能需要任意时间才能完成。完成后,响应将直接返回给客户端。 [Alyssa@6531]

以下是如何从客户端节点正确执行同步服务调用的示例,类似于 简单的服务端和客户端 教程中的异步节点。 [Alyssa@6532]

import sys
from threading import Thread

from example_interfaces.srv import AddTwoInts
import rclpy
from rclpy.node import Node

class MinimalClientSync(Node):

    def __init__(self):
        super().__init__('minimal_client_sync')
        self.cli = self.create_client(AddTwoInts, 'add_two_ints')
        while not self.cli.wait_for_service(timeout_sec=1.0):
            self.get_logger().info('service not available, waiting again...')
        self.req = AddTwoInts.Request()

    def send_request(self):
        self.req.a = int(sys.argv[1])
        self.req.b = int(sys.argv[2])
        return self.cli.call(self.req)
        # This only works because rclpy.spin() is called in a separate thread below.
        # Another configuration, like spinning later in main() or calling this method from a timer callback, would result in a deadlock.

def main():
    rclpy.init()

    minimal_client = MinimalClientSync()

    spin_thread = Thread(target=rclpy.spin, args=(minimal_client,))
    spin_thread.start()

    response = minimal_client.send_request()
    minimal_client.get_logger().info(
        'Result of add_two_ints: for %d + %d = %d' %
        (minimal_client.req.a, minimal_client.req.b, response.sum))

    minimal_client.destroy_node()
    rclpy.shutdown()


if __name__ == '__main__':
    main()

请注意,在 main() 内部,客户端在单独的线程中调用 rclpy.spinsend_requestrclpy.spin 都是阻塞的,所以它们需要在不同的线程上。 [Alyssa@6533]

1.1 同步死锁 [Alyssa@6534]

同步 call() API有几种导致死锁的方式。 [Alyssa@6535]

评论中提到的例子,未能创建单独的线程自旋 rclpy 是导致死锁的一个原因。当客户端阻塞线程等待响应,但响应只能返回同一线程,客户端不会停止等待,不能做任何别的事情。 [Alyssa@6536]

死锁的另一个原因是通过在订阅者、计时器回调函数或服务回调函数中同步调用服务来阻塞 rclpy.spin 。例如,如果同步客户端的 send_request 被放在一个回调中: [Alyssa@6537]

def trigger_request(msg):
    response = minimal_client.send_request()  # This will cause deadlock
    minimal_client.get_logger().info(
        'Result of add_two_ints: for %d + %d = %d' %
        (minimal_client.req.a, minimal_client.req.b, response.sum))
subscription = minimal_client.create_subscription(String, 'trigger', trigger_request, 10)

rclpy.spin(minimal_client)

发生死锁是因为 rclpy.spin 不会先用 send_request 调用来阻塞回调函数。通常,回调函数应该只能执行轻快的操作。 [Alyssa@6538]

警告

发生死锁时,您将不会收到任何服务被阻塞的指示。不会引发警告或异常,堆栈跟踪中没有指示,调用也不会失败。 [Alyssa@6539]

2 异步调用 [Alyssa@6540]

rclpy 中的异步调用是完全安全的,也是调用服务的推荐方法。与同步调用不同,它们可以在任何地方创建,而不用冒着阻塞其他ROS和非ROS进程的风险。 [Alyssa@6541]

异步客户端将在向服务发送请求后立即返回 future ,该值指示调用和响应是否完成 (而不是响应本身的值)。可以随时查询返回的 future 的响应。 [Alyssa@6542]

由于发送请求不会阻塞任何线程,因此可以使用循环在同一线程中自旋 rclpy 和检查 future ,例如: [Alyssa@6543]

while rclpy.ok():
    rclpy.spin_once(node)
    if future.done():
        #Get response

Python的 简单的服务端和客户端 教程说明了如何执行异步服务调用,并使用循环检索 future[Alyssa@6544]

future 也可以使用计时器或回调函数来检索,就像在 这个例子 中,以一个专用线程或其他方法来检索。作为调用方,由您决定如何存储 future ,检查其状态,并检索您的响应。 [Alyssa@6545]

总结

不建议实施同步服务客户端。它们容易发生死锁,但不会在死锁发生时提供任何问题指示。如果必须使用同步调用,1 Synchronous calls 部分的例子是这样做的一种安全的方式. 你也应该要了解 1.1 Sync deadlock 部分的概述的导致死锁的状况。相反我们建议改用异步服务客户端。 [机器人@6547]