At your Service: Servers and Clients#
Changed in version Jazzy: The contents of this session were expanded and the example simplified. The previous version is available at the Humble tutorials.
In some cases, we need means of communication in which each command has an associated response. That is where services come into play.
We provide services by creating a ServiceServer. The service server will provide a service that can be accessed by one or more ServiceClients.
In this sense, a service is much less of an abstract entity than a topic.
Each service should only have a single service server that will receive a Request and provide a Response.
Diagram#
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
ros2 pkg create output
going to create a new package
package name: python_package_that_uses_the_services
destination directory: /root/ros2_tutorial_workspace/src
package format: 3
version: 0.0.0
description: TODO: Package description
maintainer: ['root <murilo.marinho@manchester.ac.uk>']
licenses: ['TODO: License declaration']
build type: ament_python
dependencies: ['rclpy', 'package_with_interfaces']
creating folder ./python_package_that_uses_the_services
creating ./python_package_that_uses_the_services/package.xml
creating source folder
creating folder ./python_package_that_uses_the_services/python_package_that_uses_the_services
creating ./python_package_that_uses_the_services/setup.py
creating ./python_package_that_uses_the_services/setup.cfg
creating folder ./python_package_that_uses_the_services/resource
creating ./python_package_that_uses_the_services/resource/python_package_that_uses_the_services
creating ./python_package_that_uses_the_services/python_package_that_uses_the_services/__init__.py
creating folder ./python_package_that_uses_the_services/test
creating ./python_package_that_uses_the_services/test/test_copyright.py
creating ./python_package_that_uses_the_services/test/test_flake8.py
creating ./python_package_that_uses_the_services/test/test_pep257.py
[WARNING]: Unknown license 'TODO: License declaration'. This has been set in the package.xml, but no LICENSE file has been created.
It is recommended to use one of the ament license identifiers:
Apache-2.0
BSL-1.0
BSD-2.0
BSD-2-Clause
BSD-3-Clause
GPL-3.0-only
LGPL-3.0-only
MIT
MIT-0
Overview#
File structure
This will be the file structure for the Service tutorial. Highlighted are the main files for the ServiceServer and ServiceClient.
python_package_that_uses_the_services
|-- package.xml
|-- python_package_that_uses_the_services
| |-- __init__.py
| |-- add_points_service_client_introspection_node.py
| |-- add_points_service_client_node.py
| |-- add_points_service_server_introspection_node.py
| `-- add_points_service_server_node.py
|-- resource
| `-- python_package_that_uses_the_services
|-- setup.cfg
|-- setup.py
`-- test
|-- test_copyright.py
|-- test_flake8.py
`-- test_pep257.py
Before we start exploring the elements of the package, let us
Create the Node with a Service Server.
Create the Node with a Service Client.
Update the
setup.pyso that ros2 run finds these programs.
Create the Node with a Service Server#
TL;DR Creating a service server
Add new dependencies to
package.xmlImport new services
from <package_name>.srv import <srv_name>In a subclass of
Nodecreate a callback
def callback(self, request, response):create a service server with
self.service_server = self.create_service(...)
Add the new Node to
setup.py
Let’s start by creating a add_points_service_server_node.py.
import rclpy
from rclpy.node import Node
from package_with_interfaces.srv import AddPoints
class AddPointsServiceServerNode(Node):
"""A ROS2 Node with a Service Server for AddPoints."""
def __init__(self):
super().__init__('add_points_service_server')
self.service_server = self.create_service(
srv_type=AddPoints,
srv_name='/add_points',
callback=self.add_points_service_callback)
self.service_server_call_count: int = 0
def add_points_service_callback(self,
request: AddPoints.Request,
response: AddPoints.Response
) -> AddPoints.Response:
"""
Adds the two points `a` and `b` in the request and returns the `result`.
"""
response.result.x = request.a.x + request.b.x
response.result.y = request.a.y + request.b.y
response.result.z = request.a.z + request.b.z
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)
add_points_service_server_node = AddPointsServiceServerNode()
rclpy.spin(add_points_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 rclpy
from rclpy.node import Node
from package_with_interfaces.srv import AddPoints
class AddPointsServiceServerNode(Node):
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=AddPoints,
srv_name='/add_points',
callback=self.add_points_service_callback)
The Service Server receives a AddPoints.Request and returns a AddPoints.Response.
def add_points_service_callback(self,
request: AddPoints.Request,
response: AddPoints.Response
) -> AddPoints.Response:
"""
Adds the two points `a` and `b` in the request and returns the `result`.
"""
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 use the members of AddPoints.Request to calculate and populate the AddPoints.Response. At the end of the callback, we must return that AddPoints.Request.
response.result.x = request.a.x + request.b.x
response.result.y = request.a.y + request.b.y
response.result.z = request.a.z + request.b.z
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#
In rclpy, service clients are implemented using an asyncio logic (more info).
In this tutorial, we briefly introduce unavoidable async concepts in Python’s asyncio. For extra understanding, please check the official documentation.
The reasons for asyncio are very simple. We do not know when the Response of a service will be available. Then, when a service is called, we do not want our Node with a ServiceClient to get stuck while waiting for it.
Using asyncio allows the Node to do other things while the Response is received and processed.
In contrast with a Message, we need to worry about blocking the Node with a ServiceServer because a Service demands a response.
Create the Node with a Service Client (using a callback)#
TL;DR Creating a Service Client (using a callback)
Add new dependencies to
package.xmlImport new services
from <package_name>.srv import <srv_name>In a subclass of
Node(recommended) wait for service to be available
service_client.wait_for_service(...).(if periodic) add a
Timerwith a propertimer_callback()create a callback for the future
def service_future_callback(self, future: Future):create a Service Client with
self.service_client = self.create_client(...)
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 add_points_service_client_node.py at python_package_that_uses_the_services/python_package_that_uses_the_services with the following contents.
add_points_service_client_node.py
1import random
2
3import rclpy
4from rclpy.task import Future
5from rclpy.node import Node
6
7from package_with_interfaces.srv import AddPoints
8
9
10class AddPointsServiceClientNode(Node):
11 """A ROS2 Node with a Service Client for AddPoints, that call the service periodically."""
12
13 def __init__(self):
14 super().__init__('add_points_service_client')
15
16 self.service_client = self.create_client(
17 srv_type=AddPoints,
18 srv_name='/add_points')
19
20 while not self.service_client.wait_for_service(timeout_sec=1.0):
21 self.get_logger().info(f'service {self.service_client.srv_name} not available, waiting...')
22
23 self.future: Future = None
24
25 timer_period: float = 0.5
26 self.timer = self.create_timer(
27 timer_period_sec=timer_period,
28 callback=self.timer_callback)
29
30 def timer_callback(self):
31 """Method that is periodically called by the timer."""
32
33 request = AddPoints.Request()
34
35 request.a.x = random.uniform(0, 1000)
36 request.a.y = random.uniform(0, 1000)
37 request.a.z = random.uniform(0, 1000)
38
39 request.b.x = random.uniform(0, 1000)
40 request.b.y = random.uniform(0, 1000)
41 request.b.z = random.uniform(0, 1000)
42
43 if self.future is not None and not self.future.done():
44 self.future.cancel() # Cancel the future. The callback will be called with Future.result == None.
45 self.get_logger().warn("Service Future canceled. The Node took too long to process the service call."
46 "Is the Service Server still alive?")
47 self.future = self.service_client.call_async(request)
48 self.future.add_done_callback(self.process_response)
49
50 def process_response(self, future: Future):
51 """Callback for the future, that will be called when it is done"""
52 response = future.result()
53 if response is not None:
54 self.get_logger().info(f"The result was {(response.result.x, response.result.y, response.result.z)}")
55 else:
56 self.get_logger().info("The response was None.")
57
58
59def main(args=None):
60 """
61 The main function.
62 :param args: Not used directly by the user, but used by ROS2 to configure
63 certain aspects of the Node.
64 """
65 try:
66 rclpy.init(args=args)
67
68 add_points_service_client_node = AddPointsServiceClientNode()
69
70 rclpy.spin(add_points_service_client_node)
71 except KeyboardInterrupt:
72 pass
73 except Exception as e:
74 print(e)
75
76
77if __name__ == '__main__':
78 main()
Imports#
To have access to the service, we import it with from <package>.srv import <Service>.
import random
import rclpy
from rclpy.task import Future
from rclpy.node import Node
from package_with_interfaces.srv import AddPoints
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=AddPoints,
srv_name='/add_points')
(Recommended) Wait for the Service Server to be available#
Warning
The order of execution and speed of Nodes depend on a complicated web of relationships between ROS2, the operating system, and the workload of the machine. It would be naive to expect the server to always be active before the client, even if the server Node is started before the client Node.
In many cases, having the result of the service is of particular importance (hence the use of a service and not messages). In that case, we have to wait until service_client.wait_for_service(), as shown below.
while not self.service_client.wait_for_service(timeout_sec=1.0):
self.get_logger().info(f'service {self.service_client.srv_name} not available, waiting...')
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 = AddPoints.Request()
request.a.x = random.uniform(0, 1000)
request.a.y = random.uniform(0, 1000)
request.a.z = random.uniform(0, 1000)
request.b.x = random.uniform(0, 1000)
request.b.y = random.uniform(0, 1000)
request.b.z = random.uniform(0, 1000)
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().warn("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().warn("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(f"The result was {(response.result.x, response.result.y, response.result.z)}")
else:
self.get_logger().info("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.
1from setuptools import find_packages, setup
2
3package_name = 'python_package_that_uses_the_services'
4
5setup(
6 name=package_name,
7 version='0.0.0',
8 packages=find_packages(exclude=['test']),
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='root',
17 maintainer_email='murilo.marinho@manchester.ac.uk',
18 description='TODO: Package description',
19 license='TODO: License declaration',
20 tests_require=['pytest'],
21 entry_points={
22 'console_scripts': [
23 'add_points_service_client_node = '
24 'python_package_that_uses_the_services.add_points_service_client_node:main',
25 'add_points_service_client_just_once_node = '
26 'python_package_that_uses_the_services.add_points_service_client_just_once_node:main',
27 'add_points_service_server_node = '
28 'python_package_that_uses_the_services.add_points_service_server_node:main',
29 'add_points_service_client_introspection_node = '
30 'python_package_that_uses_the_services.add_points_service_client_introspection_node:main',
31 'add_points_service_server_introspection_node = '
32 'python_package_that_uses_the_services.add_points_service_server_introspection_node:main',
33 ],
34 },
35)
Build and source#
Before we proceed, let us build and source once.
cd ~/ros2_tutorial_workspace
colcon build
source install/setup.bash
Note
For additional explanation and troubleshooting tips, see Always source after you build.
Warning
colcon will not work properly if your terminal has an active venv.
Testing Service Server and Client#
ros2 run python_package_that_uses_the_services add_points_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] [1753667386.959416097] [add_points_service_client]: service /add_points not available, waiting...
[INFO] [1753667387.967904375] [add_points_service_client]: service /add_points not available, waiting...
[INFO] [1753667388.978200250] [add_points_service_client]: service /add_points not available, waiting...
In another terminal, we run the add_points_service_server_node, as follows
ros2 run python_package_that_uses_the_services add_points_service_server_node
The server Node will output nothing, whereas the client Node will output, periodically,
[INFO] [1753667415.876223138] [add_points_service_client]: The result was (853.122385593111, 613.3399959983066, 722.6376752208978)
[INFO] [1753667416.373657638] [add_points_service_client]: The result was (645.418992882397, 560.9466217293334, 874.7214190239486)
[INFO] [1753667416.875945305] [add_points_service_client]: The result was (1270.7448356640075, 345.69676803639936, 953.6879012399689)
[INFO] [1753667417.376013639] [add_points_service_client]: The result was (1203.944887411107, 733.5131783020975, 927.902266740569)
[INFO] [1753667417.872921291] [add_points_service_client]: The result was (671.9458297091917, 1210.490009902154, 545.6078440547075)
[INFO] [1753667418.371451541] [add_points_service_client]: The result was (629.0766519110047, 872.0699525880541, 581.7396957576223)
[INFO] [1753667418.873213958] [add_points_service_client]: The result was (579.0485532702639, 1714.0365146695003, 396.1743388215037)
[INFO] [1753667419.375147834] [add_points_service_client]: The result was (545.2849740451343, 1629.1832720438556, 945.1871456532875)