roscpp overview: Initialization and Shutdown | Basics | Advanced: Traits [ROS C Turtle] | Advanced: Custom Allocators [ROS C Turtle] | Advanced: Serialization and Adapting Types [ROS C Turtle] | Publishers and Subscribers | Services | Parameter Server | Timers (Periodic Callbacks) | NodeHandles | Callbacks and Spinning | Logging | Names and Node Information | Time | Exceptions | Compilation Options | Advanced: Internals | tf/Overview | tf/Tutorials | C++ Style Guide

Service definitions, request messages and response messages

See also: roscpp messages overview

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 roscpp message overview). roscpp converts these srv files into C++ 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:

  • my_package/srv/Foo.srv

    • my_package::Foo

    • my_package::Foo::Request

    • my_package::Foo::Response

Generated Structure

  • The roscpp service generator generates a structure like this:
       1 namespace my_package
       2 {
       3 struct Foo
       4 {
       5   class Request
       6   {
       7     ...
       8   };
       9 
      10   class Response
      11   {
      12     ...
      13   };
      14 
      15   Request request;
      16   Response response;
      17 }; 
      18 }
    

The Request class provides the input to the service. The Response class is returned to the client as the service's output.

Creating Service Request/Responses

  • There are two versions of any service call method: one which takes, for example, the Foo struct shown above, and one that takes separate Request and Response objects. Filling out either is very simple. To use the Foo struct itself:

       1 my_package::Foo foo;
       2 foo.request.<var> = <value>;
       3 ...
       4 <call>(foo);
    
    To use separate objects:
       1 my_package::Foo::Request req;
       2 my_package::Foo::Response res;
       3 req.<var> = <value>;
       4 ...
       5 <call>(req, res);
    

Calling Services

See also: ros::service::call() API docs, ros::NodeHandle::serviceClient() API docs, ros::ServiceClient API docs, ros::service namespace API docs

There are two ways of calling a service in roscpp, the "handle" way and the "bare" way.

Bare

  • For convenience, the ros::service namespace provides a call method, which does not require creation of a NodeHandle:

       1 //remember that ros::init(...) must have been called
       2 my_package::Foo foo;
       3 ...
       4 if (ros::service::call("my_service_name", foo))
       5 {
       6   ...
       7 }
    

    The ros::service namespace also provides some convenience functions such as exists() and waitForService(). See the ros::service namespace API docs for more information.

Handle

  • The handle way works more similar to how the rest of roscpp works, in that you are returned a ros::ServiceClient which is then used to call the service:

    ros::ServiceClient client = nh.serviceClient<my_package::Foo>("my_service_name");
    my_package::Foo foo;
    ...
    if (client.call(foo))
    {
      ...
    }

    ros::ServiceClient also has a number of other useful methods suchs as exists() and waitForExistence(). See the ros::ServiceClient API docs for more information.

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.

You can create a persistent connection by using the optional second argument to ros::NodeHandle::serviceClient():

   1 ros::ServiceClient client = nh.serviceClient<my_package::Foo>("my_service_name", true);

Note: with persistent services, you can tell if the connection failed by testing the handle:

if (client)
{
  ...
}

ros::ServiceClient handles are reference counted internally, so they can be copied and once the last copy is destroyed the persistent connection will drop. You may also manually shutdown the connection with the ros::ServiceClient::shutdown() method.

Providing Services

See also: ros::NodeHandle::advertiseService() API docs, ros::ServiceServer API docs

In roscpp you provide a service by creating a ros::ServiceServer through the ros::NodeHandle::advertiseService() method. advertiseService() works very similar to how the subscribe() method works, in that you provide a service name and a callback to be invoked when the service is called.

Options

There are a number of different versions of advertiseService(), for different types of callbacks, but the general signature is:

template<class MReq, class MRes>
ros::ServiceServer nh.advertiseService(const std::string& service, <callback>);
  • MReq [usually unnecessary]

    • This is a template argument specifying the request message type. For most versions you do not need to explicitly define this, as the compiler can deduce it from the callback function.

    MRes [usually unnecessary]

    • This is a template argument specifying the response message type. For most versions you do not need to explicitly define this, as the compiler can deduce it from the callback function.

    service

    • The name of the service to provide

    <callback>

    • The callback to invoke when a request has arrived

Callback Signature

The signature of the service callback is:

bool callback(MReq& request, MRes& response);

where MReq and MRes match the request/response types provided to advertiseService(). A return value of true means the service succeeded, and the response object has been filled with the necessary data. A return value of false means the call has failed and the response object will not be sent to the caller.

Callback Types

roscpp supports any callback supported by boost::function:

  1. functions
  2. class methods
  3. functor objects (including boost::bind)

Functions

Functions are the easiest to use:

   1 bool callback(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response)
   2 {
   3   return true;
   4 }
   5 
   6 ros::ServiceServer service = nh.advertiseService("my_service", callback);

Class Methods

Class methods are also easy, though they require an extra parameter:

   1 bool Foo::callback(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response)
   2 {
   3   return true;
   4 }
   5 
   6 Foo foo_object;
   7 ros::ServiceServer service = nh.advertiseService("my_service", &Foo::callback, &foo_object);

Functor Objects

A functor object is a class that declares operator(), e.g.:

   1 class Foo
   2 {
   3 public:
   4   bool operator()(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response)
   5   {
   6     return true;
   7   }
   8 };

A functor passed to advertiseService() must be copyable. The Foo functor could be used with advertiseService() like so:

   1 ros::ServiceServer srv = nh.advertiseService<std_srvs::Empty::Request, std_srvs::Empty::Response>("my_service", Foo());

Note: when using functor objects you must explicitly specify the request and response types as template arguments, because the compiler cannot deduce them in this case.

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, you can pass a std::map<std::string, std::string> to the ros::NodeHandle::serviceClient() method as its third argument:

   1 std::map<std::string, std::string> header;
   2 header["val1"] = "val";
   3 header["val2"] = "val";
   4 ros::ServiceClient client = nh.serviceClient<my_package::Foo>("my_service_name", false, header);

On the server side the Request object has a __connection_header field, which is a pointer to a std::map<std::string, std::string>.

Wiki: roscpp/Overview/Services (last edited 2012-03-14 15:35:24 by JonathanBohren)