ros_loader.py
Go to the documentation of this file.
00001 import time
00002 #!/usr/bin/env python
00003 # Software License Agreement (BSD License)
00004 #
00005 # Copyright (c) 2012, Willow Garage, Inc.
00006 # All rights reserved.
00007 #
00008 # Redistribution and use in source and binary forms, with or without
00009 # modification, are permitted provided that the following conditions
00010 # are met:
00011 #
00012 #  * Redistributions of source code must retain the above copyright
00013 #    notice, this list of conditions and the following disclaimer.
00014 #  * Redistributions in binary form must reproduce the above
00015 #    copyright notice, this list of conditions and the following
00016 #    disclaimer in the documentation and/or other materials provided
00017 #    with the distribution.
00018 #  * Neither the name of Willow Garage, Inc. nor the names of its
00019 #    contributors may be used to endorse or promote products derived
00020 #    from this software without specific prior written permission.
00021 #
00022 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 # POSSIBILITY OF SUCH DAMAGE.
00034 
00035 import roslib
00036 import rospy
00037 
00038 from threading import Lock
00039 
00040 """ ros_loader contains methods for dynamically loading ROS message classes at
00041 runtime.  It's achieved by using roslib to load the manifest files for the
00042 package that the respective class is contained in.
00043 
00044 Methods typically return the requested class or instance, or None if not found
00045 """
00046 
00047 # Variable containing the loaded classes
00048 _loaded_msgs = {}
00049 _loaded_srvs = {}
00050 _msgs_lock = Lock()
00051 _srvs_lock = Lock()
00052 
00053 
00054 class InvalidTypeStringException(Exception):
00055     def __init__(self, typestring):
00056         Exception.__init__(self, "%s is not a valid type string" % typestring)
00057 
00058 
00059 class InvalidPackageException(Exception):
00060     def __init__(self, package, original_exception):
00061         Exception.__init__(self,
00062            "Unable to load the manifest for package %s. Caused by: %s"
00063            % (package, original_exception.message)
00064        )
00065 
00066 
00067 class InvalidModuleException(Exception):
00068     def __init__(self, modname, subname, original_exception):
00069         Exception.__init__(self,
00070            "Unable to import %s.%s from package %s. Caused by: %s"
00071            % (modname, subname, modname, str(original_exception))
00072         )
00073 
00074 
00075 class InvalidClassException(Exception):
00076     def __init__(self, modname, subname, classname, original_exception):
00077         Exception.__init__(self,
00078            "Unable to import %s class %s from package %s. Caused by %s"
00079            % (subname, classname, modname, str(original_exception))
00080         )
00081 
00082 
00083 def get_message_class(typestring):
00084     """ Loads the message type specified.
00085 
00086     Returns the loaded class, or throws exceptions on failure """
00087     return _get_msg_class(typestring)
00088 
00089 
00090 def get_service_class(typestring):
00091     """ Loads the service type specified.
00092 
00093     Returns the loaded class, or None on failure """
00094     return _get_srv_class(typestring)
00095 
00096 
00097 def get_message_instance(typestring):
00098     """ If not loaded, loads the specified type.
00099     Then returns an instance of it, or None. """
00100     cls = get_message_class(typestring)
00101     return cls()
00102 
00103 
00104 def get_service_instance(typestring):
00105     """ If not loaded, loads the specified type.
00106     Then returns an instance of it, or None. """
00107     cls = get_service_class(typestring)
00108     return cls()
00109 
00110 
00111 def get_service_request_instance(typestring):
00112     cls = get_service_class(typestring)
00113     return cls._request_class()
00114 
00115 
00116 def get_service_response_instance(typestring):
00117     cls = get_service_class(typestring)
00118     return cls._response_class()
00119 
00120 
00121 def _get_msg_class(typestring):
00122     """ If not loaded, loads the specified msg class then returns an instance
00123     of it
00124 
00125     Throws various exceptions if loading the msg class fails """
00126     global _loaded_msgs, _msgs_lock
00127     return _get_class(typestring, "msg", _loaded_msgs, _msgs_lock)
00128 
00129 
00130 def _get_srv_class(typestring):
00131     """ If not loaded, loads the specified srv class then returns an instance
00132     of it
00133 
00134     Throws various exceptions if loading the srv class fails """
00135     global _loaded_srvs, _srvs_lock
00136     return _get_class(typestring, "srv", _loaded_srvs, _srvs_lock)
00137 
00138 
00139 def _get_class(typestring, subname, cache, lock):
00140     """ If not loaded, loads the specified class then returns an instance
00141     of it.
00142 
00143     Loaded classes are cached in the provided cache dict
00144 
00145     Throws various exceptions if loading the msg class fails """
00146 
00147     # First, see if we have this type string cached
00148     cls = _get_from_cache(cache, lock, typestring)
00149     if cls is not None:
00150         return cls
00151 
00152     # Now normalise the typestring
00153     modname, classname = _splittype(typestring)
00154     norm_typestring = modname + "/" + classname
00155 
00156     # Check to see if the normalised type string is cached
00157     cls = _get_from_cache(cache, lock, norm_typestring)
00158     if cls is not None:
00159         return cls
00160 
00161     # Load the class
00162     cls = _load_class(modname, subname, classname)
00163 
00164     # Cache the class for both the regular and normalised typestring
00165     _add_to_cache(cache, lock, typestring, cls)
00166     _add_to_cache(cache, lock, norm_typestring, cls)
00167 
00168     return cls
00169 
00170 
00171 def _load_class(modname, subname, classname):
00172     """ Loads the manifest and imports the module that contains the specified
00173     type.
00174 
00175     Logic is similar to that of roslib.message.get_message_class, but we want
00176     more expressive exceptions.
00177 
00178     Returns the loaded module, or None on failure """
00179     global loaded_modules
00180 
00181     try:
00182         # roslib maintains a cache of loaded manifests, so no need to duplicate
00183         roslib.launcher.load_manifest(modname)
00184     except Exception as exc:
00185         raise InvalidPackageException(modname, exc)
00186 
00187 
00188     try:
00189         pypkg = __import__('%s.%s' % (modname, subname))
00190     except Exception as exc:
00191         raise InvalidModuleException(modname, subname, exc)
00192 
00193     try:
00194         return getattr(getattr(pypkg, subname), classname)
00195     except Exception as exc:
00196         raise InvalidClassException(modname, subname, classname, exc)
00197 
00198 
00199 def _splittype(typestring):
00200     """ Split the string the / delimiter and strip out empty strings
00201 
00202     Performs similar logic to roslib.names.package_resource_name but is a bit
00203     more forgiving about excess slashes
00204     """
00205     splits = [x for x in typestring.split("/") if x]
00206     if len(splits) == 2:
00207         return splits
00208     raise InvalidTypeStringException(typestring)
00209 
00210 
00211 def _add_to_cache(cache, lock, key, value):
00212     lock.acquire()
00213     cache[key] = value
00214     lock.release()
00215 
00216 
00217 def _get_from_cache(cache, lock, key):
00218     """ Returns the value for the specified key from the cache.
00219     Locks the lock before doing anything. Returns None if key not in cache """
00220     lock.acquire()
00221     ret = None
00222     if key in cache:
00223         ret = cache[key]
00224     lock.release()
00225     return ret


rosbridge_library
Author(s): Jonathan Mace
autogenerated on Mon Oct 6 2014 06:58:09