You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
I run 1 service server and 3 service clients which call service on high frequency as a stress test.
Attached are python codes, but same result on c++ codes.
import rclpy
from rclpy.node import Node
from example_interfaces.srv import AddTwoInts
class MinimalClientAsync(Node):
def __init__(self):
super().__init__('minimal_client_async')
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...')
def send_request(self, a, b):
self.req = AddTwoInts.Request()
self.req.a = a
self.req.b = b
self.future = self.cli.call_async(self.req)
rclpy.spin_until_future_complete(self, self.future)
return self.future.result()
def main(args=None):
rclpy.init(args=args)
minimal_client = MinimalClientAsync()
for i in range(1000000000):
response = minimal_client.send_request(1, 2)
if i%10000 == 0:
minimal_client.get_logger().info(
'Result of add_two_ints: for %d + %d = %d' %
(1, 2, response.sum))
minimal_client.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
Expected behavior
Continue to display results from service server repeatedly
Actual behavior
The service client sometimes freezes in spin_until_future_complete. The service client doesn't progress at all when it freezes. Even though 2 of 3 clients are terminated, the freeze client doesn't continue the computation loop.
The freeze occurs not only high frequency cases but also low frequency multi-client cases.
The text was updated successfully, but these errors were encountered:
The default qos parameter of service is keep last 10 data, and it is not enough for multi-client cases.
In ROS2, all service response from service server is published to all clients other than the caller, it means the buffer can be filled up by the responses for other callers and the response for the caller can be lost.
The default qos parameter of service client is not suitable for multi-client cases, which are often the case in ROS2. The default qos parameters should be changed.
I will create an issue on rwm repository that the default qos parameter is defined on.
Bug report
Steps to reproduce issue
I run 1 service server and 3 service clients which call service on high frequency as a stress test.
Attached are python codes, but same result on c++ codes.
Service Server
Service Client (run on 3 terminals)
Expected behavior
Continue to display results from service server repeatedly
Actual behavior
The service client sometimes freezes in spin_until_future_complete. The service client doesn't progress at all when it freezes. Even though 2 of 3 clients are terminated, the freeze client doesn't continue the computation loop.
The freeze occurs not only high frequency cases but also low frequency multi-client cases.
The text was updated successfully, but these errors were encountered: