Services

Introduction

This tutorial explains the basics of ROS Services:

  • Lines beginning with $ are terminal commands.

    • To open a new terminal → use the shortcut Ctrl + Alt + T.

    • To open a new tab inside an existing terminal → use the shortcut Ctrl + Shift + T.

    • To kill a process in a terminal → use the shortcut Ctrl + C.

  • Lines beginning with # indicate the syntax of the commands.

  • Code is separated in boxes.

  • Code is case sensitive.

Turtle Control (Services)

Reset Service Client

The turtlesim Node offers Services based on different service types. The most simple type is an empty service. Using an empty service, no data is exchanged between the server and the client. It can be used to just send a signal to a ROS2 Node without the need of a feedback.

Turtlesim offers a reset Service to clear the turtlesim window spawn a new turtle to the initial position. To use this service, run the following:

$ ros2 run turtlesim turtlesim_node

$ ros2 run turtlesim turtle_teleop_key

Make sure to move your turtle a little bit around.

$ ros2 service call /reset std_srvs/srv/Empty {}

We can of course also call a Service from within a Node.

Given below is an example of a service client calling the reset service of the turtlesim_node. The service is called, if the turtle leaves a defined geofence. Go through the explanation before you start with the exercise.

Listing 11 turtlesim reset service
#!/usr/bin/env python3

import rclpy
from std_srvs.srv import Empty
from turtlesim.msg import Pose

def callback(msg):
    if not 3.0 < msg.x < 7.0:
        reset()
    if not 3.0 < msg.y < 7.0:
        reset()

def reset():
    global reset_service
    while not reset_service.wait_for_service(timeout_sec=1.0):
        print('service not available, trying again...')
    reset_service.call_async(Empty.Request())

def main():
    global reset_service
    rclpy.init()
    myfirstsrvclient = rclpy.create_node('myfirstserviceclient')
    myfirstsrvclient.create_subscription(Pose, '/turtle1/pose', callback, 10)
    reset_service = myfirstsrvclient.create_client(Empty, 'reset')
    try:
        rclpy.spin(myfirstsrvclient)
    except KeyboardInterrupt:
        pass
    myfirstsrvclient.destroy_node()
    rclpy.shutdown()

if __name__ == '__main__':
    main()

Reset Service Client Node explanation

from std_srvs.srv import Empty

Imports the service message Empty from the ROS Package std_srvs (http://wiki.ros.org/std_srvs).

Let’s check the main function first before we go in the details of the other functions:

    reset_service = myfirstsrvclient.create_client(Empty, 'reset')

Line 24 is new to us, but it is analog to publisher and subscriber. We create a service client instance on the node object. Also know from publisher and subscriber we have to pass the message type as first argument, which is the Empty service message in this case.

The second argument we need to pass is the name of the service. The name is given by the turtlesim node: reset

That’s all to define our client. Now we need to call it. For that purpose we are “abusing” the turtle1/pose topic offered by turtlesim:

    myfirstsrvclient.create_subscription(Pose, '/turtle1/pose', callback, 10)

It is subscribing to the topic and will call the service depending on specific input values from the topic:

def callback(msg):
    if not 3.0 < msg.x < 7.0:
        reset()
    if not 3.0 < msg.y < 7.0:
        reset()

So, the final service call itself is happening in the reset function:

def reset():
    global reset_service
    while not reset_service.wait_for_service(timeout_sec=1.0):
        print('service not available, trying again...')
    reset_service.call_async(Empty.Request())

First we need to check, if the service is available:

    while not reset_service.wait_for_service(timeout_sec=1.0):
        print('service not available, trying again...')

The wait_for_service function offers the possibility to create a timeout in case the service server is not responding.

    reset_service.call_async(Empty.Request())

In this line finally the service call happens using call_async on our service client object passing a Request Message from the Empty Service. Every Service Message offers a Request and a Response with different variables to be accessed inside the Request and Response. Also one of them or like in this case both of them can be empty.

Reset Service Client Exercise

→ Create a new pacakge in your ~/robot_ws/src named srv_examples.

→ Inside that package create a Node called turtlesim_geofence_reset_srv.py and paste the code example from the top inside.

Start the needed ROS Nodes:

$ ros2 run turtlesim turtlesim_node

$ ros2 run turtlesim turtle_teleop_key

$ ros2 run srv_examples turtlesim_geofence_reset_srv

→ The turtle should now reset, if you move it outside of the geofence.

Gripper Service Server

Most service messages include a request and a response object. The following example Node shows a Service Server that offers the option to change the state of a virtual gripper: open or close. It uses a SetBool Service called open_gripper.

Listing 12 open gripper service
#!/usr/bin/env python3

import rclpy
from std_srvs.srv import SetBool

gripper_opened = True

def open_gripper_callback(request, response):
        global gripper_opened
        if request.data:
            if gripper_opened:
                response.success = False
                response.message = 'Opening gripper failed. Gripper was already opened.'
            else:
                response.success = True
                response.message = 'Opening gripper succeeded. Gripper is open now.'
                print('The gripper is open.')
        else:
            if gripper_opened:
                response.success = True
                response.message = 'Closing gripper succeeded. Gripper is closed now.'
                print('The gripper is closed.')
            else:
                response.success = False
                response.message = 'Closing gripper failed. Gripper was already closed.'
        if response.success:
            gripper_opened = not gripper_opened
        return response

def main():
    rclpy.init()
    myfirstsrvserver = rclpy.create_node('myfirstserviceserver')
    myfirstsrvserver.create_service(SetBool, 'open_gripper', open_gripper_callback)
    print('The gripper is open.')
    try:
        rclpy.spin(myfirstsrvserver)
    except KeyboardInterrupt:
        pass
    myfirstsrvserver.destroy_node()
    rclpy.shutdown()

if __name__ == '__main__':
    main()

Service Server explanation

The service message SetBool includes a Request object with one field: bool data and a Response object with two fields: bool success, string message

For detailed information, check: SetBool Service Message .

    myfirstsrvserver.create_service(SetBool, 'open_gripper', open_gripper_callback)

A service server instance is created on the node object myfirstsrvserver using the function create_service. It needs three arguments as input:

First argument passed is the Service Message type: SetBool

Second argument is the Service name: open_gripper. This is free to choose.

And the third and last argument is a function, which is executed, if the Service is called. This is analog to a Subscriber. The difference is that the Service additionally returns a value to the incoming request, which in fact a Subscriber can’t.

The function being called is named open_gripper_callback. So, we need to define this function.

def open_gripper_callback(request, response):

This line defines the function open_gripper_callback and comes automatically with two arguments being passed. This is always the case for a service callback function. The first argument is always the request and the second one is the response, which we need to return something. To keep it simple they are called request and response in this example, but they can have any name.

Remember: the Response object includes two fields, which we can fill now:

        if request.data:
            if gripper_opened:
                response.success = False
                response.message = 'Opening gripper failed. Gripper was already opened.'
            else:
                response.success = True
                response.message = 'Opening gripper succeeded. Gripper is open now.'
                print('The gripper is open.')
        else:
            if gripper_opened:
                response.success = True
                response.message = 'Closing gripper succeeded. Gripper is closed now.'
                print('The gripper is closed.')
            else:
                response.success = False
                response.message = 'Closing gripper failed. Gripper was already closed.'

We can define different outcomes depending on the request …

        if request.data:

… and depending on the current state of our virtual gripper:

            if gripper_opened:

Using all four combinations of those two states, the response success field can be determined:

                response.success = True
                response.success = False

Also the message field of the response can be different:

                response.message = 'Opening gripper failed. Gripper was already opened.'
                response.message = 'Opening gripper succeeded. Gripper is open now.'
                response.message = 'Closing gripper succeeded. Gripper is closed now.'
                response.message = 'Closing gripper failed. Gripper was already closed.'

Finally the response is send to the Service Client that called the Service:

        return response

Gripper Service exercise

→ Inside the srv_examples package create a Node called open_gripper_service_server.py and paste the code example from the top inside.

Start the Node:

$ ros2 run srv_examples open_gripper_service_server

Now you can call the service from the terminal:

$ ros2 service call /open_gripper std_srvs/srv/SetBool data:\ true

→ Develope another Node called invert_gripper_service_client. The Node should invert the current state of the gripper by calling the open_gripper Service and checking the result of the response.

If you want to learn more about services, please check: `ROS2 Service Tutorial <https://index.ros.org/doc/ros2/Tutorials/Writing-A-Simple-Py-Service-And-Client/`__ .