(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Example service

Description: This tutorial shows how to make an embedded linux application offer a service to ROS service clients

Tutorial Level: BEGINNER

Next Tutorial: VEXPro servo position control example

We'll continue our exploration into rosserial for embedded linux by creating a service program for our embeddded linux box.

The publish/subscribe model described in previous tutorials is good for sending data around the system - it decouples data producers from data consumers so that neither knows or cares if the other is active, inactive, or restarting. It's well-suited to one-way data flow. However, that model has limitations; there are situations when a client wants to request something to be done and know whether it was successful or what the result was. For example, a system startup node may want to request another node to run diagnostics and return the result, or to change mode or grab something and return whether the request was successful. For those purposes, the traditional client-server model is more appropriate. Rosserial allows the embedded linux box to act as either a client or a server. This tutorial describes the example code that acts as a server and offers a service to any clients that request it.

The code

Use your favorite editor or IDE to open the ExampleService.cpp tutorial code which is found in examples/ExampleService.cpp. You should see the following:

   1 /*
   2  * rosserial_embeddedlinux service server example
   3  *
   4  * Advertises a service it offers. Prints the string sent to the service
   5  * and responds with an alternating string. It also publishes "hello world" on /chatter,
   6  * just to show it's alive.
   7  * The service request can be sent from the ROS command line with e.g.
   8  * $ rosservice call /test_srv "Hullo mate!"
   9  */
  10 
  11 #include <ros.h>
  12 #include <std_msgs/String.h>
  13 #include <rosserial_embeddedlinux/Test.h>
  14 #include <stdio.h>
  15 
  16 ros::NodeHandle  nh;
  17 using rosserial_embeddedlinux::Test;
  18 #define ROSSRVR_IP "192.168.15.149"
  19 
  20 int i=0;
  21 void svcCallback(const Test::Request & req, Test::Response & res){
  22         if((i++)%2)
  23                 res.output = "hello";
  24         else
  25                 res.output = "ros";
  26         printf("Service request message: \"%s\" received, responding with: %s\n", req.input, res.output);
  27 }
  28 ros::ServiceServer<Test::Request, Test::Response> server("test_srv",&svcCallback);
  29 
  30 std_msgs::String str_msg;
  31 ros::Publisher chatter("chatter", &str_msg);
  32 
  33 char hello[13] = "hello world!";
  34 
  35 int main()
  36 {
  37         nh.initNode(ROSSRVR_IP);
  38         nh.advertiseService(server);
  39         nh.advertise(chatter);
  40 
  41         str_msg.data = hello;
  42 
  43         while(1) {
  44                 chatter.publish(&str_msg);
  45                 nh.spinOnce();
  46                 sleep(1);
  47         }
  48 }

The code explained

Now let's break the code down.

  11 #include <ros.h>
  12 #include <std_msgs/String.h>
  13 #include <rosserial_embeddedlinux/Test.h>
  14 

The program is very similar to that of the subscriber in the previous tutorial example. The Test.h header file is automatically generated from the service message definition in rosserial_embeddedlinux/srv/Test.srv. More information on creating service messages is found at rosserial messages

  21 void svcCallback(const Test::Request & req, Test::Response & res){
  22         if((i++)%2)
  23                 res.output = "hello";
  24         else
  25                 res.output = "ros";
  26         printf("Service request message: \"%s\" received, responding with: %s\n", req.input, res.output);
  27 }
  28 ros::ServiceServer<Test::Request, Test::Response> server("test_srv",&svcCallback);

svcCallback is the function called when a service request is received. It is passed a reference to the incoming request message, and to an outgoing response message which it must fill. It fills alternate outgoing response messages with "hello" then "ros", for a little variety (but only a little). Then it prints the incoming request message data. The Test Request and Response messages simply carry a string.

After defining the callback function, you declare the name of the server, the names of its request and response messages, the name of the service offered, and the callback function name.

Subsequent lines declare a publisher, as was done in the example publisher tutorial.

  37         nh.initNode(ROSSRVR_IP);
  38         nh.advertiseService(server);
  39         nh.advertise(chatter);

As before, you need to initialize your node handle, passing it the IP of the system running the rosserial_python proxy. Then you have to advertise the service being offered (and the publisher we instantiated too).

  43         while(1) {
  44                 chatter.publish(&str_msg);
  45                 nh.spinOnce();
  46                 sleep(1);
  47         }

Finally, the program enters a loop, continually publishing "hello" and calling spinOnce() to give the interface a chance to receive any service requests and call the callback function.

Testing the code

As before, use your system-specific procedures to build the program and load it onto your embedded linux system.

If you haven't already done so, launch roscore on your ros workstation and start the rosserial_python.py proxy application that passes your embedded linux ROS messages to and from the rest of ROS. You can specify tcp or the name of a serial port connected to your embedded linux system.

$ rosrun rosserial_python serial_node.py tcp

Now start the ExampleService application on your embedded linux system.

$ ./ExampleService
connected to server
EmbeddedHardware.h: opened comm port successfully

Finally, run the rosservice utility on the ROS workstation several times to send several service requests to your embedded system:

$ rosservice call /test_srv "Hullo mate"
$ rosservice call /test_srv "Hullo mate"
...

Observe the ExampleService program printing a message each time it receives a messsage:

Service request message: "Hullo mate" received, responding with: ros
Service request message: "Hullo mate" received, responding with: hello
Service request message: "Hullo mate" received, responding with: ros
Service request message: "Hullo mate" received, responding with: hello

Wiki: rosserial_embeddedlinux/Tutorials/Example service (last edited 2012-09-26 03:06:36 by PaulBouchier)