Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011 import rospy
00012 import unique_id
00013 import rocon_service_pair_msgs.msg as rocon_service_pair_msgs
00014 import rocon_python_comms
00015 import threading
00016
00017
00018
00019
00020
00021 class Jagi(object):
00022 __slots__ = [
00023 'server',
00024 'requests',
00025 'lock',
00026 ]
00027
00028 def __init__(self):
00029 self.server = rocon_python_comms.ServicePairServer('testies', self.callback, rocon_service_pair_msgs.TestiesPair)
00030 self.requests = []
00031 self.lock = threading.Lock()
00032
00033 def callback(self, request_id, msg):
00034 '''
00035 @param request_id
00036 @type uuid_msgs/UniqueID
00037 @param msg
00038 @type ServiceRequest
00039 '''
00040 rospy.loginfo("received '%s'" % msg.data)
00041 self.lock.acquire()
00042 self.requests.append((request_id, msg))
00043 self.lock.release()
00044
00045 def spin(self):
00046 while not rospy.is_shutdown():
00047 self.lock.acquire()
00048 if self.requests:
00049 for (request_id, unused_msg) in self.requests:
00050 response = rocon_service_pair_msgs.TestiesResponse()
00051 response.data = "I heard ya dude"
00052 self.server.reply(request_id, response)
00053 self.lock.release()
00054 rospy.sleep(0.5)
00055
00056
00057
00058
00059
00060
00061 if __name__ == '__main__':
00062
00063 rospy.init_node('example_rocon_pair_server')
00064 jagi = Jagi()
00065 jagi.spin()