Go to the documentation of this file.00001
00002
00003 import roslib; roslib.load_manifest('flexbe_core')
00004 import rospy
00005 from threading import Timer
00006 import time
00007
00008 from flexbe_core.logger import Logger
00009
00010
00011 class ProxyServiceCaller(object):
00012 """
00013 A proxy for calling services.
00014 """
00015 _services = {}
00016
00017 def __init__(self, topics = {}):
00018 """
00019 Initializes the proxy with optionally a given set of clients.
00020
00021 @type topics: dictionary string - message class
00022 @param topics: A dictionay containing a collection of topic - message type pairs.
00023 """
00024
00025 for topic, msg_type in topics.iteritems():
00026 self.setupService(topic, msg_type)
00027
00028
00029 def setupService(self, topic, msg_type, persistent=False, wait_duration=10):
00030 """
00031 Tries to set up a service caller for calling it later.
00032
00033 @type topic: string
00034 @param topic: The topic of the service to call.
00035
00036 @type msg_type: service class
00037 @param msg_type: The type of messages of this service.
00038
00039 @type persistent: bool
00040 @param persistent: Defines if this service caller is persistent.
00041
00042 @type wait_duration: int
00043 @param wait_duration: Defines how long to wait for the given service if it is not available right now.
00044 """
00045 if topic not in ProxyServiceCaller._services:
00046 warning_sent = False
00047 available = False
00048 try:
00049 t = Timer(1, self._print_wait_warning, [topic])
00050 t.start()
00051 rospy.wait_for_service(topic, wait_duration)
00052 available = True
00053 except rospy.exceptions.ROSException, e:
00054 available = False
00055
00056 try:
00057 t.cancel()
00058 except Exception as ve:
00059
00060 warning_sent = True
00061
00062 if not available:
00063 Logger.logerr("Service client %s timed out!" % topic)
00064 else:
00065 ProxyServiceCaller._services[topic] = rospy.ServiceProxy(topic, msg_type, persistent)
00066 if warning_sent:
00067 Logger.loginfo("Finally found action client %s..." % (topic))
00068
00069
00070 def is_available(self, topic):
00071 """
00072 Checks if the service on the given topic is available.
00073
00074 @type topic: string
00075 @param topic: The topic of interest.
00076 """
00077 return topic in ProxyServiceCaller._services
00078
00079
00080 def call(self, topic, request):
00081 """
00082 Performs a service call on the given topic.
00083
00084 @type topic: string
00085 @param topic: The topic to call.
00086
00087 @type request: service
00088 @param request: The request to send to this service.
00089 """
00090 if topic not in ProxyServiceCaller._services:
00091 rospy.logwarn('ProxyServiceCaller: topic not yet registered!')
00092 return
00093
00094 try:
00095 return ProxyServiceCaller._services[topic].call(request)
00096 except Exception, e:
00097 print 'error: ' + str(e)
00098 raise
00099
00100
00101 def _print_wait_warning(self, topic):
00102 Logger.logwarn("Waiting for service client %s..." % (topic))