33 from threading
import Thread
34 from rospy
import ServiceProxy, resolve_name
35 from rosservice
import get_service_type
44 Exception.__init__(self,
"Service %s does not exist" % servicename)
49 def __init__(self, service, args, success_callback, error_callback):
50 """ Create a service caller for the specified service. Use start() 51 to start in a separate thread or run() to run in this thread. 54 service -- the name of the service to call 55 args -- arguments to pass to the service. Can be an 56 ordered list, or a dict of name-value pairs. Anything else will be 57 treated as though no arguments were provided (which is still valid for 58 some kinds of service) 59 success_callback -- a callback to call with the JSON result of the 61 error_callback -- a callback to call if an error occurs. The 62 callback will be passed the exception that caused the failure 76 except Exception
as e:
82 """ Populate a service request instance with the provided args 84 args can be a dictionary of values, or a list, or None 86 Propagates any exceptions that may be raised. """ 88 if isinstance(args, list):
89 msg = dict(zip(inst.__slots__, args))
90 elif isinstance(args, dict):
101 service = resolve_name(service)
103 service_type = get_service_type(str(service))
104 if service_type
is None:
113 proxy = ServiceProxy(service, service_class)
114 response = proxy.call(inst)
def populate_instance(msg, inst)
def get_service_request_instance(typestring)
def get_service_class(typestring)
def call_service(service, args=None)
def __init__(self, servicename)
def __init__(self, service, args, success_callback, error_callback)
def args_to_service_request_instance(service, inst, args)