Note: This tutorial assumes that you have completed the previous tutorials: Create ServicePair Messages. |
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. |
Writing a ServicePair Server (Python)
Description: Simple example of a service pair server in python.Keywords: servicepair, rocon
Tutorial Level: INTERMEDIATE
Next Tutorial: Writing a ServicePair Client (Python)
Contents
Overview
This tutorial demonstrates how to write a service pair server in python. There are two ways to do this but in both all you need is a callback function to provide to the ServicePairServer class. In the first method this callback will run directly, and in the second method, this callback will be put into a thread.
Non-Threaded
1 #!/usr/bin/env python
2
3 import rospy
4 from chatter.msg import ChatterRequest, ChatterResponse, ChatterPair
5 from rocon_python_comms import ServicePairServer
6
7 class ChatterServer(object):
8
9 def __init__(self):
10 self.server = ServicePairServer('chatter', self.callback, ChatterPair)
11
12 def callback(self, request_id, msg):
13 rospy.loginfo("Server : I heard %s" % msg.babble)
14 response = ChatterResponse()
15 response.reply = "I heard %s" % msg.babble
16 self.server.reply(request_id, response)
17
18 if __name__ == '__main__':
19 rospy.init_node('chatter_server', anonymous=True)
20 chatter_server = ChatterServer()
21 rospy.spin()
Threaded
Use this when your callback will take either an indeterminate amount of time to resolve or it requires non-negligible work. To configure the server, just toggle the use_threads variable to True:
1 self.server = ServicePairServer('chatter', self.callback, ChatterPair, use_threads=True)