At your Service: Servers and Clients

Note

Except for the particulars of the setup.py file, the way that services in ROS2 work in Python, i.e. the explanation in this section, does not depend on ament_python or ament_cmake.

In some cases, we need means of communication in which each command has an associated response. That is where Services come into play.

Create the package

We start by creating a package to use the Service we first created in The service file.

cd ~/ros2_tutorial_workspace/src
ros2 pkg create python_package_that_uses_the_services \
--build-type ament_python \
--dependencies rclpy package_with_interfaces

Overview

Before we start exploring the elements of the package, let us

  1. Create the Node with a Service Server.

  2. Create the Node with a Service Client.

  3. Update the setup.py so that ros2 run finds these programs.

Create the Node with a Service Server

TL;DR Creating a service server

  1. Add new dependencies to package.xml

  2. Import new services from <package_name>.srv import <srv_name>

  3. In a subclass of Node

    1. create a callback def callback(self, request, response):

    2. create a service server with self.service_server = self.create_service(...)

  4. Add the new Node to setup.py

Let’s start by creating a what_is_the_point_service_server_node.py in ~/ros2_tutorial_workspace/src/python_package_that_uses_the_services/python_package_that_uses_the_services with the following contents

what_is_the_point_service_server_node.py

import random
from textwrap import dedent  # https://docs.python.org/3/library/textwrap.html#textwrap.dedent

import rclpy
from rclpy.node import Node
from package_with_interfaces.srv import WhatIsThePoint


class WhatIsThePointServiceServerNode(Node):
    """A ROS2 Node with a Service Server for WhatIsThePoint."""

    def __init__(self):
        super().__init__('what_is_the_point_service_server')

        self.service_server = self.create_service(
            srv_type=WhatIsThePoint,
            srv_name='/what_is_the_point',
            callback=self.what_is_the_point_service_callback)

        self.service_server_call_count: int = 0

    def what_is_the_point_service_callback(self,
                                           request: WhatIsThePoint.Request,
                                           response: WhatIsThePoint.Response
                                           ) -> WhatIsThePoint.Response:
        """Analyses an AmazingQuote and returns what is the point.
           If the quote contains 'life', it returns a point whose sum of coordinates is 42.
           Otherwise, it returns a random point whose sum of coordinates is not 42.
        """

        # Generate the x,y,z of the point
        if "life" in request.quote.quote.lower():
            x: float = random.uniform(0, 42)
            y: float = random.uniform(0, 42 - x)
            z: float = 42 - (x + y)
        else:
            x: float = random.uniform(0, 100)
            y: float = random.uniform(0, 100)
            z: float = random.uniform(0, 100)
            if x + y + z == 42:  # So you’re telling me there’s a chance? Yes!
                x = x + 1  # Not anymore :(

        # Assign to the response
        response.point.x = x
        response.point.y = y
        response.point.z = z

        # Increase the call count
        self.service_server_call_count = self.service_server_call_count + 1

        self.get_logger().info(dedent(f"""
            This is the call number {self.service_server_call_count} to this Service Server.
            The analysis of the AmazingQuote below is complete.
            
                    {request.quote.quote}
            
            -- {request.quote.philosopher_name}
            
            The point has been sent back to the client.
        """))

        return response


def main(args=None):
    """
    The main function.
    :param args: Not used directly by the user, but used by ROS2 to configure
    certain aspects of the Node.
    """
    try:
        rclpy.init(args=args)

        what_is_the_point_service_server_node = WhatIsThePointServiceServerNode()

        rclpy.spin(what_is_the_point_service_server_node)
    except KeyboardInterrupt:
        pass
    except Exception as e:
        print(e)


if __name__ == '__main__':
    main()

The code begins with an import to the service we created. No surprise here.

import random
from textwrap import dedent  # https://docs.python.org/3/library/textwrap.html#textwrap.dedent

import rclpy
from rclpy.node import Node
from package_with_interfaces.srv import WhatIsThePoint

The Service Server must be initialised with the create_service(), as follows, with parameters that should by now be quite obvious to us.

        self.service_server = self.create_service(
            srv_type=WhatIsThePoint,
            srv_name='/what_is_the_point',
            callback=self.what_is_the_point_service_callback)

The Service Server receives a WhatIsThePoint.Request and returns a WhatIsThePoint.Response.

    def what_is_the_point_service_callback(self,
                                           request: WhatIsThePoint.Request,
                                           response: WhatIsThePoint.Response
                                           ) -> WhatIsThePoint.Response:
        """Analyses an AmazingQuote and returns what is the point.
           If the quote contains 'life', it returns a point whose sum of coordinates is 42.
           Otherwise, it returns a random point whose sum of coordinates is not 42.
        """

Warning

The API for the Service Server callback is a bit weird in that needs the Response as an argument. This API might change, but for now this is what we got.

We play around with the WhatIsThePoint.Request a bit and use that result to populate a WhatIsThePoint.Response, as follows

        # Assign to the response
        response.point.x = x
        response.point.y = y
        response.point.z = z

At the end of the callback, we must return that WhatIsThePoint.Request, like so

        return response

The Service Server was quite painless, but it doesn’t do much. The Service Client might be a bit more on the painful side for the uninitiated.

Service Clients

ROS2 rclpy Service Clients are implemented using an asyncio logic (More info). In this tutorial, we briefly introduce unavoidable async concepts in Python’s asyncio, but for any extra understanding, it’s better to check the official documentation.

Create the Node with a Service Client (using a callback)

TL;DR Creating a Service Client (using a callback)

  1. Add new dependencies to package.xml

  2. Import new services from <package_name>.srv import <srv_name>

  3. In a subclass of Node

    1. (recommended) wait for service to be available service_client.wait_for_service(...).

    2. (if periodic) add a Timer with a proper timer_callback()

    3. create a callback for the future def service_future_callback(self, future: Future):

    4. create a Service Client with self.service_client = self.create_client(...)

  4. Add the new Node to setup.py

The Node

Note

This example deviates somewhat from what is done in the official examples. This implementation shown herein uses a callback and rclpy.spin(). It has many practical applications, but it’s no panacea.

We start by adding a what_is_the_point_service_client_node.py at python_package_that_uses_the_services/python_package_that_uses_the_services with the following contents.

what_is_the_point_service_client_node.py

 1import random
 2from textwrap import dedent  # https://docs.python.org/3/library/textwrap.html#textwrap.dedent
 3
 4import rclpy
 5from rclpy.task import Future
 6from rclpy.node import Node
 7
 8from package_with_interfaces.srv import WhatIsThePoint
 9
10
11class WhatIsThePointServiceClientNode(Node):
12    """A ROS2 Node with a Service Client for WhatIsThePoint."""
13
14    def __init__(self):
15        super().__init__('what_is_the_point_service_client')
16
17        self.service_client = self.create_client(
18            srv_type=WhatIsThePoint,
19            srv_name='/what_is_the_point')
20
21        while not self.service_client.wait_for_service(timeout_sec=1.0):
22            self.get_logger().info(f'service {self.service_client.srv_name} not available, waiting...')
23
24        self.future: Future = None
25
26        timer_period: float = 0.5
27        self.timer = self.create_timer(
28            timer_period_sec=timer_period,
29            callback=self.timer_callback)
30
31    def timer_callback(self):
32        """Method that is periodically called by the timer."""
33
34        request = WhatIsThePoint.Request()
35        if random.uniform(0, 1) < 0.5:
36            request.quote.quote = "I wonder about the Ultimate Question of Life, the Universe, and Everything."
37            request.quote.philosopher_name = "Creators of Deep Thought"
38            request.quote.id = 1979
39        else:
40            request.quote.quote = """[...] your living... it is always potatoes. I dream of potatoes."""
41            request.quote.philosopher_name = "a young Maltese potato farmer"
42            request.quote.id = 2013
43
44        if self.future is not None and not self.future.done():
45            self.future.cancel()  # Cancel the future. The callback will be called with Future.result == None.
46            self.get_logger().info("Service Future canceled. The Node took too long to process the service call."
47                                   "Is the Service Server still alive?")
48        self.future = self.service_client.call_async(request)
49        self.future.add_done_callback(self.process_response)
50
51    def process_response(self, future: Future):
52        """Callback for the future, that will be called when it is done"""
53        response = future.result()
54        if response is not None:
55            self.get_logger().info(dedent(f"""
56                We have thus received the point of our quote.
57
58                            {(response.point.x, response.point.y, response.point.z)}
59            """))
60        else:
61            self.get_logger().info(dedent("""
62                    The response was None. :(    
63            """))
64
65
66def main(args=None):
67    """
68    The main function.
69    :param args: Not used directly by the user, but used by ROS2 to configure
70    certain aspects of the Node.
71    """
72    try:
73        rclpy.init(args=args)
74
75        what_is_the_point_service_client_node = WhatIsThePointServiceClientNode()
76
77        rclpy.spin(what_is_the_point_service_client_node)
78    except KeyboardInterrupt:
79        pass
80    except Exception as e:
81        print(e)
82
83
84if __name__ == '__main__':
85    main()

Imports

To have access to the service, we import it with from <package>.srv import <Service>.

from package_with_interfaces.srv import WhatIsThePoint

Instantiate a Service Client

We instantiate a Service Client with Node.create_client(). The values of srv_type and srv_name must match the ones used in the Service Server.

        self.service_client = self.create_client(
            srv_type=WhatIsThePoint,
            srv_name='/what_is_the_point')

Instantiate a Future as a class attribute

As part of the async framework, we instantiate a Future (More info). In this example it is important to have it as an attribute of the class so that we do not lose the reference to it after the callback.

        self.future: Future = None

Instantiate a Timer

Whenever periodic work must be done, it is recommended to use a Timer, as we already learned in Use a Timer for periodic work (when using rclpy.spin()).

        timer_period: float = 0.5
        self.timer = self.create_timer(
            timer_period_sec=timer_period,
            callback=self.timer_callback)

The need for a callback for the Timer, should also be no surprise.

    def timer_callback(self):
        """Method that is periodically called by the timer."""

Service Clients use <srv>.Request()

Given that services work in a request-response model, the Service Client must instantiate a suitable <srv>.Request() and populate its fields before making the service call, as shown below. To make the example more interesting, it randomly switches between two possible quotes.

        request = WhatIsThePoint.Request()
        if random.uniform(0, 1) < 0.5:
            request.quote.quote = "I wonder about the Ultimate Question of Life, the Universe, and Everything."
            request.quote.philosopher_name = "Creators of Deep Thought"
            request.quote.id = 1979
        else:
            request.quote.quote = """[...] your living... it is always potatoes. I dream of potatoes."""
            request.quote.philosopher_name = "a young Maltese potato farmer"
            request.quote.id = 2013

Make service calls with call_async()

The async framework in ROS2 is based on Python’s asyncio that we already saw in Python’s asyncio.

Note

At first glance, it might feel that all this trouble to use async is unjustified. However, Nodes in practice will hardly ever do one service call and be done. Many Nodes in a complex system will have a composition of many service servers, service clients, publishers, and subscribers. Blocking the entire Node while it waits for the result of a service is, in most cases, a bad design.

The recommended way to call a service is through call_async(), which is the reason why we are working with async logic. In general, the result of call_async(), a Future, will not have the result of the service call at the next line of our program.

There are many ways to address the use of a Future. One of them, specially tailored to interface async with callback-based frameworks is the Future.add_done_callback(). If the Future is already done by the time we call add_done_callback(), it is supposed to call the callback for us.

The benefit of this is that the callback will not block our resources until the response is ready. When the response is ready, and the ROS2 executor gets to processing Future callbacks, our callback will be called automagically.

        if self.future is not None and not self.future.done():
            self.future.cancel()  # Cancel the future. The callback will be called with Future.result == None.
            self.get_logger().info("Service Future canceled. The Node took too long to process the service call."
                                   "Is the Service Server still alive?")
        self.future = self.service_client.call_async(request)
        self.future.add_done_callback(self.process_response)

Given that we are periodically calling the service, before replace the class Future with the next service call, we can check if the service call was done with Future.done(). If it is not done, we can use Future.cancel() so that our callback can handle this case as well. For instance, if the Service Server has been shutdown, the Future would never be done.

        if self.future is not None and not self.future.done():
            self.future.cancel()  # Cancel the future. The callback will be called with Future.result == None.
            self.get_logger().info("Service Future canceled. The Node took too long to process the service call."
                                   "Is the Service Server still alive?")
        self.future = self.service_client.call_async(request)
        self.future.add_done_callback(self.process_response)

The Future callback

The callback for the Future must receive a Future as an argument. Having it as an attribute of the Node’s class allows us to access ROS2 method such as get_logger() and other contextual information.

The result of the Future is obtained using Future.result(). The response might be None in some cases, so we must check it before trying to use the result, otherwise we will get a nasty exception.

    def process_response(self, future: Future):
        """Callback for the future, that will be called when it is done"""
        response = future.result()
        if response is not None:
            self.get_logger().info(dedent(f"""
                We have thus received the point of our quote.

                            {(response.point.x, response.point.y, response.point.z)}
            """))
        else:
            self.get_logger().info(dedent("""
                    The response was None. :(    
            """))


Update the setup.py

As we already learned in Making ros2 run work, we must adjust the setup.py to refer to the Nodes we just created.

setup.py

 1from setuptools import setup
 2
 3package_name = 'python_package_that_uses_the_services'
 4
 5setup(
 6    name=package_name,
 7    version='0.0.0',
 8    packages=[package_name],
 9    data_files=[
10        ('share/ament_index/resource_index/packages',
11            ['resource/' + package_name]),
12        ('share/' + package_name, ['package.xml']),
13    ],
14    install_requires=['setuptools'],
15    zip_safe=True,
16    maintainer='murilo',
17    maintainer_email='murilomarinho@ieee.org',
18    description='TODO: Package description',
19    license='TODO: License declaration',
20    tests_require=['pytest'],
21    entry_points={
22        'console_scripts': [
23            'what_is_the_point_service_client_node = '
24            'python_package_that_uses_the_services.what_is_the_point_service_client_node:main',
25            'what_is_the_point_service_server_node = '
26            'python_package_that_uses_the_services.what_is_the_point_service_server_node:main'
27        ],
28    },
29)

Build and source

Before we proceed, let us build and source once.

cd ~/ros2_tutorial_workspace
colcon build
source install/setup.bash

Note

If you don’t remember why we’re building with these commands, see Always source after you build.

Testing Service Server and Client

ros2 run python_package_that_uses_the_services what_is_the_point_service_client_node

when running the client Node, the server is still not active. In that case, the client node will keep waiting for it, as follows

[INFO] [1684293008.888276849] [what_is_the_point_service_client]: service /what_is_the_point not available, waiting...
[INFO] [1684293009.890589539] [what_is_the_point_service_client]: service /what_is_the_point not available, waiting...
[INFO] [1684293010.892778194] [what_is_the_point_service_client]: service /what_is_the_point not available, waiting...

In another terminal, we run the python_package_uses_the_service_node, as follows

ros2 run python_package_that_uses_the_services what_is_the_point_service_server_node

The server Node will then output, periodically,

[INFO] [1684485151.608507798] [what_is_the_point_service_server]:
This is the call number 1 to this Service Server.
The analysis of the AmazingQuote below is complete.

        [...] your living... it is always potatoes. I dream of potatoes.

-- a young Maltese potato farmer

The point has been sent back to the client.

[INFO] [1684485152.092508332] [what_is_the_point_service_server]:
This is the call number 2 to this Service Server.
The analysis of the AmazingQuote below is complete.

        I wonder about the Ultimate Question of Life, the Universe, and Everything.

-- Creators of Deep Thought

The point has been sent back to the client.

[INFO] [1684485152.592516148] [what_is_the_point_service_server]:
This is the call number 3 to this Service Server.
The analysis of the AmazingQuote below is complete.

        I wonder about the Ultimate Question of Life, the Universe, and Everything.

-- Creators of Deep Thought

The point has been sent back to the client.

and the client Node will output, periodically,

[INFO] [1684485151.609611689] [what_is_the_point_service_client]:
We have thus received the point of our quote.

            (18.199457100225292, 33.14595477433704, 52.65262570058381)

[INFO] [1684485152.093228181] [what_is_the_point_service_client]:
We have thus received the point of our quote.

            (11.17170193214362, 9.384897014549527, 21.443401053306854)

[INFO] [1684485152.593294259] [what_is_the_point_service_client]:
We have thus received the point of our quote.

            (16.58535176162403, 0.6180505400411676, 24.796597698334804)