[Documentation] [TitleIndex] [WordIndex

Service definitions, request messages, and response messages

ROS Services are defined by srv files, which contains a request message and a response message. These are identical to the messages used with ROS Topics (see rospy message overview). rospy converts these srv files into Python source code and creates three classes that you need to be familiar with: service definitions, request messages, and response messages. The names of these classes come directly from the srv filename:

Service Definition

Service Request Messages

Service Response Messages

Service proxies

See also: http://docs.ros.org/api/rospy/html/rospy.impl.tcpros_service.ServiceProxy-class.html

You call a service by creating a rospy.ServiceProxy with the name of the service you wish to call. You often will want to call rospy.wait_for_service() to block until a service is available.

If a service returns an error for the request, a rospy.ServiceException will be raised. The exception will contain any error messages that the service sent.

   1 rospy.wait_for_service('add_two_ints')
   2 add_two_ints = rospy.ServiceProxy('add_two_ints', AddTwoInts)
   3 try:
   4   resp1 = add_two_ints(x, y)
   5 except rospy.ServiceException as exc:
   6   print("Service did not process request: " + str(exc))

rospy.ServiceProxy(name, service_class, persistent=False, headers=None)

rospy.wait_for_service(service, timeout=None)

Advanced users: you don't need to create a ROS node in order to make service calls with a rospy.ServiceProxy.

Calling services

rospy.ServiceProxy instances are callable, which means that you can invoke them just as you would with methods, e.g.:

   1 add_two_ints = rospy.ServiceProxy('add_two_ints', AddTwoInts)
   2 add_two_ints(1, 2)

There are three different ways of passing arguments to a call that range from an explicit style, where you provide a service request Message instance, to two implicit styles that create the request Message for you.

Important note: Some standard types are not casted automatically. If your service message contains complex messages, even if it is an std_msgs/String, you will have to create an instance of that Message class to pass as an argument in all three examples below. For instance, if the service in the code snippet above accepted two strings as arguments, you would have called it like the following:

   1 from std_msgs.msg import String
   2 
   3 add_two_ints = rospy.ServiceProxy('add_two_ints', AddTwoInts)
   4 add_two_ints(String(1), String(2))

Explicit style:

Implicit style with in-order arguments:

Implicit style with keyword arguments

There are three types of exceptions that can be raised:

Persistent connections

ROS also allows for persistent connections to services. With a persistent connection, a client stays connected to a service. Otherwise, a client normally does a lookup and reconnects to a service each time. This potentially allows for a client to connect to a different node each time it does a service call, assuming the lookup returns a different node.

Persistent connections should be used carefully. They greatly improve performance for repeated requests, but they also make your client more fragile to service failures. Clients using persistent connections should implement their own reconnection logic in the event that the persistent connection fails.

rospy.ServiceProxy(name, service_class, persistent=True)

Providing services

See also: http://docs.ros.org/api/rospy/html/rospy.impl.tcpros_service.Service-class.html

In rospy, you provide a Service by creating a rospy.Service instance with a callback to invoke when new requests are received. Each inbound request is handled in its own thread, so services must be thread-safe.

rospy.Service(name, service_class, handler, buff_size=65536)

You can also streamline returning values from a service handler so that you don't have to manually create the Response instance. The valid set of return types from a handler are:

A handler can return a tuple or list of the arguments for creating the response instance. For example, we could replace the add_two_ints function above with:

def add_two_ints(req):
  return [req.a + req.b]

The AddTwoIntsResponse only takes in a single argument, so we can streamline this by just returning the sum:

def add_two_ints(req):
  return req.a + req.b

A handler can also return a dictionary with keyword arguments for creating the response object. To continue your add_two_ints example, we could return:

def add_two_ints(req):
  return {'sum': req.a + req.b}

This will set the 'sum' field of the response.

(Waiting for) shutdown

There are two common usage patterns for shutting down a service. You can either explicitly terminate the service by calling its shutdown() method, or you can use use a spin() method, which will occupy your current thread until shutdown is initiated. There are two spin() methods you can use: each Service instance has a spin() method, which exits with either the Service or node is shutdown, and there is the more general rospy.spin() method, which just waits for the node to shutdown.

Explicitly stop a Service:

   1 s = rospy.Service('add_two_ints', rospy_tutorials.srv.AddTwoInts, add_two_ints)
   2 ...
   3 s.shutdown('shutdown reason')

Wait for shutdown:

   1 s = rospy.Service('add_two_ints', rospy_tutorials.srv.AddTwoInts, add_two_ints)
   2 s.spin() #returns when either service or node is shutdown

Service connection headers

Connection headers are a feature of both ROS Topics and ROS Services that enable additional metadata to be sent when the initial connection is made between two nodes. ROS uses these headers to pass in basic information such as the callerid of the connecting client.

In the case of services, this feature can be customized to implement advanced features like "sessions" (i.e. cookies). Services clients can send additional metadata of their own, such as an identifier to associate with the request.

On the client side, the ServiceProxy passed an additional headers parameter with a dictionary of string keys ad values to send. On the service side, the additional headers can be accessed in the _connection_header field of the request message.

rospy.ServiceProxy(name, service_class, headers=header_dictionary)

request._connection_header


2024-11-16 17:44