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


rosbridge_library
Author(s): Jonathan Mace
autogenerated on Thu Jan 2 2014 11:53:35