Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Service clients freeze on multi-client cases. #1163

Closed
kjjpc opened this issue Jun 28, 2024 · 1 comment
Closed

Service clients freeze on multi-client cases. #1163

kjjpc opened this issue Jun 28, 2024 · 1 comment

Comments

@kjjpc
Copy link

kjjpc commented Jun 28, 2024

Bug report

  • Operating System:
    • ros:jazzy docker image
  • Installation type:
    • binaries
  • Version or commit hash:
    • ros-jazzy-ros-base=0.11.0-1 of apt package
  • DDS implementation:
    • Fast DDS (Default DDS of jazzy)
  • Client library (if applicable):
    • rclcpp, rclpy

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

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

class MinimalService(Node):
    def __init__(self):
        super().__init__('minimal_service')
        self.srv = self.create_service(AddTwoInts, 'add_two_ints', self.add_two_ints_callback)

    def add_two_ints_callback(self, request, response):
        response.sum = request.a + request.b
        return response

def main(args=None):
    rclpy.init(args=args)
    minimal_service = MinimalService()
    rclpy.spin(minimal_service)
    rclpy.shutdown()

if __name__ == '__main__':
    main()

Service Client (run on 3 terminals)

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.

@kjjpc
Copy link
Author

kjjpc commented Jul 8, 2024

This issue is resolved by changing the qos parameter like following.

        qos = qos_profile_services_default
        qos.history = HistoryPolicy.KEEP_ALL
        self.cli = self.create_client(AddTwoInts, 'add_two_ints', qos_profile = qos)

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.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

1 participant