Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 from threading import Thread
00034 from rospy import ServiceProxy
00035 from rosservice import get_service_type
00036 from rosbridge_library.internal.ros_loader import get_service_class
00037 from rosbridge_library.internal.ros_loader import get_service_request_instance
00038 from rosbridge_library.internal.message_conversion import populate_instance
00039 from rosbridge_library.internal.message_conversion import extract_values
00040
00041
00042 class InvalidServiceException(Exception):
00043 def __init__(self, servicename):
00044 Exception.__init__(self, "Service %s does not exist" % servicename)
00045
00046
00047 class ServiceCaller(Thread):
00048
00049 def __init__(self, service, args, success_callback, error_callback):
00050 """ Create a service caller for the specified service. Use start()
00051 to start in a separate thread or run() to run in this thread.
00052
00053 Keyword arguments:
00054 service -- the name of the service to call
00055 args -- arguments to pass to the service. Can be an
00056 ordered list, or a dict of name-value pairs. Anything else will be
00057 treated as though no arguments were provided (which is still valid for
00058 some kinds of service)
00059 success_callback -- a callback to call with the JSON result of the
00060 service call
00061 error_callback -- a callback to call if an error occurs. The
00062 callback will be passed the exception that caused the failure
00063
00064 """
00065 Thread.__init__(self)
00066 self.daemon = True
00067 self.service = service
00068 self.args = args
00069 self.success = success_callback
00070 self.error = error_callback
00071
00072 def run(self):
00073 try:
00074
00075 self.success(call_service(self.service, self.args))
00076 except Exception as e:
00077
00078 self.error(e)
00079
00080
00081 def args_to_service_request_instance(service, inst, args):
00082 """ Populate a service request instance with the provided args
00083
00084 args can be a dictionary of values, or a list, or None
00085
00086 Propagates any exceptions that may be raised. """
00087 msg = {}
00088 if isinstance(args, list):
00089 msg = dict(zip(inst.__slots__, args))
00090 elif isinstance(args, dict):
00091 msg = args
00092
00093
00094 populate_instance(msg, inst)
00095
00096
00097 def call_service(service, args=None):
00098
00099
00100 service_type = get_service_type(str(service))
00101 if service_type is None:
00102 raise InvalidServiceException(service)
00103 service_class = get_service_class(service_type)
00104 inst = get_service_request_instance(service_type)
00105
00106
00107 args_to_service_request_instance(service, inst, args)
00108
00109
00110 proxy = ServiceProxy(service, service_class)
00111 response = proxy.call(inst)
00112
00113
00114 json_response = extract_values(response)
00115
00116 return json_response