<> <> == Service definitions, request messages and response messages == See also: [[roscpp/Overview/Messages|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/Overview/Messages|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: {{{ #!cplusplus namespace my_package { struct Foo { class Request { ... }; class Response { ... }; Request request; Response response; }; } }}} 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: {{{ #!cplusplus my_package::Foo foo; foo.request. = ; ... (foo); }}} To use separate objects: {{{ #!cplusplus my_package::Foo::Request req; my_package::Foo::Response res; req. = ; ... (req, res); }}} == Calling Services == See also: [[http://www.ros.org/doc/api/roscpp/html/namespaceros_1_1service.html#33d9fb0f32ff8bbac4db4188d657715d|ros::service::call() API docs]], [[http://www.ros.org/doc/api/roscpp/html/classros_1_1NodeHandle.html#571ee8eb0a453274f788cd8696d00966|ros::NodeHandle::serviceClient() API docs]], [[http://www.ros.org/doc/api/roscpp/html/classros_1_1ServiceClient.html|ros::ServiceClient API docs]], [[http://www.ros.org/doc/api/roscpp/html/namespaceros_1_1service.html|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`: {{{ #!cplusplus //remember that ros::init(...) must have been called my_package::Foo foo; ... if (ros::service::call("my_service_name", foo)) { ... } }}} The `ros::service` namespace also provides some convenience functions such as `exists()` and `waitForService()`. See the [[http://www.ros.org/doc/api/roscpp/html/namespaceros_1_1service.html|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_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 [[http://www.ros.org/doc/api/roscpp/html/classros_1_1ServiceClient.html|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()`: {{{ #!cplusplus ros::ServiceClient client = nh.serviceClient("my_service_name", true); }}} '''Note:''' with persistent services, you can tell if the connection failed by testing the handle: {{{ #!cpluslpus 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: [[http://www.ros.org/doc/api/roscpp/html/classros_1_1NodeHandle.html#9e26dbb04e53372cd6388c67e27626bc|ros::NodeHandle::advertiseService() API docs]], [[http://www.ros.org/doc/api/roscpp/html/classros_1_1ServiceServer.html|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: {{{ #!cpluslpus template ros::ServiceServer nh.advertiseService(const std::string& service, ); }}} `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 `` The callback to invoke when a request has arrived === Callback Signature === The signature of the service callback is: {{{ #!cpluslpus 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 [[http://www.boost.org/doc/libs/1_37_0/doc/html/function.html|boost::function]]: 1. functions 1. class methods 1. functor objects (including [[http://www.boost.org/doc/libs/1_37_0/libs/bind/bind.html|boost::bind]]) ==== Functions ==== Functions are the easiest to use: {{{ #!cplusplus bool callback(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response) { return true; } ros::ServiceServer service = nh.advertiseService("my_service", callback); }}} ==== Class Methods ==== Class methods are also easy, though they require an extra parameter: {{{ #!cplusplus bool Foo::callback(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response) { return true; } Foo foo_object; ros::ServiceServer service = nh.advertiseService("my_service", &Foo::callback, &foo_object); }}} ==== Functor Objects ==== A functor object is a class that declares `operator()`, e.g.: {{{ #!cplusplus class Foo { public: bool operator()(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response) { return true; } }; }}} A functor passed to `advertiseService()` must be '''copyable'''. The `Foo` functor could be used with `advertiseService()` like so: {{{ #!cplusplus ros::ServiceServer srv = nh.advertiseService("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` to the `ros::NodeHandle::serviceClient()` method as its third argument: {{{ #!cplusplus std::map header; header["val1"] = "val"; header["val2"] = "val"; ros::ServiceClient client = nh.serviceClient("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`.