class_loader_imp.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2008, 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 * Author: Eitan Marder-Eppstein
00036 *********************************************************************/
00037 
00038 //NOTE: this should really never be included on its own, but just in case someone is bad we'll guard
00039 
00040 #ifndef PLUGINLIB_CLASS_LOADER_IMP_H_
00041 #define PLUGINLIB_CLASS_LOADER_IMP_H_
00042 
00043 #include "boost/bind.hpp"
00044 #include <list>
00045 #include <stdexcept>
00046 
00047 namespace pluginlib {
00048   template <class T>
00049   ClassLoader<T>::ClassLoader(std::string package, std::string base_class, std::string attrib_name) : package_(package), base_class_(base_class), attrib_name_(attrib_name)
00050   {
00051     classes_available_ = determineAvailableClasses();
00052   }
00053 
00054   template <class T>
00055   void ClassLoader<T>::loadLibraryForClass(const std::string & lookup_name)
00056   {
00057     std::string library_path;
00058     ClassMapIterator it = classes_available_.find(lookup_name);
00059     if (it != classes_available_.end()){
00060       library_path = it->second.library_path_;
00061     }
00062     else
00063     {
00064       throw LibraryLoadException(getErrorStringForUnknownClass(lookup_name));
00065     }
00066     library_path.append(Poco::SharedLibrary::suffix());
00067     try
00068     {
00069       ROS_DEBUG("Attempting to load library %s for class %s",
00070                 library_path.c_str(), lookup_name.c_str());
00071       
00072       loadClassLibraryInternal(library_path, lookup_name);
00073     }
00074     catch (Poco::LibraryLoadException &ex)
00075     {
00076       std::string error_string = "Failed to load library " + library_path + ". Make sure that you are calling the PLUGINLIB_REGISTER_CLASS macro in the library code, and that names are consistent between this macro and your XML. Error string: " + ex.displayText();
00077       throw LibraryLoadException(error_string);
00078     }
00079     catch (Poco::NotFoundException &ex)
00080     {
00081       std::string error_string = "Failed to find library " + library_path + ". Are you sure that the library you need has been built? Error string: " + ex.displayText();
00082       throw LibraryLoadException(error_string);
00083     }
00084   }
00085 
00086   template <class T>
00087   int ClassLoader<T>::unloadLibraryForClass(const std::string& lookup_name)
00088   {
00089     ClassMapIterator it = classes_available_.find(lookup_name);
00090     if (it != classes_available_.end())
00091     {
00092       std::string library_path = it->second.library_path_;
00093       library_path.append(Poco::SharedLibrary::suffix());
00094       ROS_DEBUG("Attempting to unload library %s for class %s",
00095                 library_path.c_str(), lookup_name.c_str());
00096 
00097       return unloadClassLibraryInternal(library_path);
00098     } else {
00099       throw LibraryUnloadException(getErrorStringForUnknownClass(lookup_name));
00100     }
00101   }
00102 
00103   template <class T>
00104   ClassLoader<T>::~ClassLoader()
00105   {
00106     for (LibraryCountMap::iterator it = loaded_libraries_.begin(); it != loaded_libraries_.end(); ++it)
00107     {
00108       if ( it->second > 0)
00109         unloadClassLibrary(it->first);
00110     }
00111   }
00112 
00113 
00114   template <class T>
00115   bool ClassLoader<T>::isClassLoaded(const std::string& lookup_name)
00116   {
00117     try
00118     {
00119       return poco_class_loader_.canCreate(getClassType(lookup_name));
00120     }
00121     catch (Poco::RuntimeException &ex)
00122     {
00123       return false;
00124     }
00125   }
00126 
00127   template <class T>
00128   std::vector<std::string> ClassLoader<T>::getDeclaredClasses()
00129   {
00130     std::vector<std::string> lookup_names;
00131     for (ClassMapIterator it = classes_available_.begin(); it != classes_available_.end(); ++it)
00132     {
00133       lookup_names.push_back(it->first);
00134     }
00135     return lookup_names;
00136   }
00137 
00138   template <class T>
00139   void ClassLoader<T>::refreshDeclaredClasses()
00140   {
00141     // determine classes not currently loaded for removal
00142     std::list<std::string> remove_classes;
00143     for (std::map<std::string, ClassDesc>::const_iterator it = classes_available_.begin(); it != classes_available_.end(); it++)
00144     {
00145       std::string library_path = it->second.library_path_;
00146       library_path.append(Poco::SharedLibrary::suffix());
00147       if (loaded_libraries_.find(library_path) == loaded_libraries_.end() || loaded_libraries_[library_path] == 0)
00148       {
00149         remove_classes.push_back(it->first);
00150       }
00151     }
00152     while (!remove_classes.empty())
00153     {
00154       classes_available_.erase(remove_classes.front());
00155       remove_classes.pop_front();
00156     }
00157 
00158     // add new classes
00159     std::map<std::string, ClassDesc> updated_classes = determineAvailableClasses();
00160     for (std::map<std::string, ClassDesc>::const_iterator it = updated_classes.begin(); it != updated_classes.end(); it++)
00161     {
00162       if (classes_available_.find(it->first) == classes_available_.end())
00163       {
00164         classes_available_.insert(std::pair<std::string, ClassDesc>(it->first, it->second));
00165       }
00166     }
00167   }
00168 
00169   template <class T>
00170   std::string ClassLoader<T>::getName(const std::string& lookup_name)
00171   {
00172     //remove the package name to get the raw plugin name
00173     std::vector<std::string> split;
00174     boost::split(split, lookup_name, boost::is_any_of("/"));
00175     return split.back();
00176   }
00177 
00178   template <class T>
00179   bool ClassLoader<T>::isClassAvailable(const std::string& lookup_name)
00180   {
00181     return classes_available_.find(lookup_name) != classes_available_.end();
00182   }
00183 
00184   template <class T>
00185   std::string ClassLoader<T>::getClassType(const std::string& lookup_name)
00186   {
00187     ClassMapIterator it = classes_available_.find(lookup_name);
00188     if (it != classes_available_.end())
00189       return it->second.derived_class_;
00190     return "";
00191   }
00192 
00193   template <class T>
00194   std::string ClassLoader<T>::getClassDescription(const std::string& lookup_name)
00195   {
00196     ClassMapIterator it = classes_available_.find(lookup_name);
00197     if (it != classes_available_.end())
00198       return it->second.description_;
00199     return "";
00200   }
00201 
00202   template <class T>
00203   std::string ClassLoader<T>::getBaseClassType() const
00204   {
00205     return base_class_;
00206   }
00207 
00208   template <class T>
00209   std::string ClassLoader<T>::getClassLibraryPath(const std::string& lookup_name)
00210   {
00211     ClassMapIterator it = classes_available_.find(lookup_name);
00212     if (it != classes_available_.end())
00213       return it->second.library_path_;
00214     return "";
00215   }
00216 
00217   template <class T>
00218   std::string ClassLoader<T>::getClassPackage(const std::string& lookup_name)
00219   {
00220     ClassMapIterator it = classes_available_.find(lookup_name);
00221     if (it != classes_available_.end())
00222       return it->second.package_;
00223     return "";
00224   }
00225 
00226   template <class T>
00227   std::string ClassLoader<T>::getPluginManifestPath(const std::string& lookup_name)
00228   {
00229     ClassMapIterator it = classes_available_.find(lookup_name);
00230     if (it != classes_available_.end())
00231       return it->second.plugin_manifest_path_;
00232     return "";
00233   }
00234 
00235   template <class T>
00236   T* ClassLoader<T>::createClassInstance(const std::string& lookup_name, bool auto_load)
00237   {
00238     if(auto_load && !isClassLoaded(lookup_name))
00239       loadLibraryForClass(lookup_name);
00240 
00241     try{
00242       return poco_class_loader_.create(getClassType(lookup_name));
00243     }
00244     catch(const Poco::RuntimeException& ex){
00245       std::string error_string = "The class " + lookup_name + " could not be loaded. Error: " + ex.displayText();
00246       throw CreateClassException(error_string);
00247     }
00248   }
00249   
00250   template <class T>
00251   boost::shared_ptr<T> ClassLoader<T>::createInstance(const std::string& lookup_name)
00252   {
00253     T* instance = createUnmanagedInstance(lookup_name);
00254     return boost::shared_ptr<T>(instance, boost::bind(&ClassLoader<T>::garbageInstance, this, _1, lookup_name));
00255   }
00256 
00257   template <class T>
00258   T* ClassLoader<T>::createUnmanagedInstance(const std::string& lookup_name)
00259   {
00260     loadLibraryForClass(lookup_name);
00261 
00262     T* instance = 0;
00263     try{
00264       instance = poco_class_loader_.create(getClassType(lookup_name));
00265     }
00266     catch(const Poco::RuntimeException& ex){
00267       std::string error_string = "The class " + lookup_name + " could not be loaded. Error: " + ex.displayText();
00268       // call unload library to keep load/unload counting consistent
00269       unloadLibraryForClass(lookup_name);
00270       throw CreateClassException(error_string);
00271     }
00272     return instance;
00273   }
00274 
00275   template <class T>
00276   void ClassLoader<T>::garbageInstance(T* p, const std::string& lookup_name)
00277   {
00278     if (p)
00279     {
00280       delete p;
00281       p = 0;
00282     }
00283     unloadLibraryForClass(lookup_name);
00284   }
00285 
00286   template <class T>
00287   bool ClassLoader<T>::unloadClassLibrary(const std::string& library_path)
00288   {
00289     LibraryCountMap::iterator it = loaded_libraries_.find(library_path);
00290     if (it == loaded_libraries_.end())
00291     {
00292       ROS_DEBUG("unable to unload library which is not loaded");
00293       return false;
00294     }
00295     else if (it-> second > 1)
00296       (it->second)--;
00297     else
00298       poco_class_loader_.unloadLibrary(library_path);
00299 
00300     return true;
00301 
00302   }
00303 
00304   template <class T>
00305   bool ClassLoader<T>::loadClassLibrary(const std::string& library_path){
00306     try
00307     {
00308       loadClassLibraryInternal(library_path);
00309     }
00310     catch (Poco::LibraryLoadException &ex)
00311     {
00312       return false;
00313     }
00314     catch (Poco::NotFoundException &ex)
00315     {
00316       return false;
00317     }
00318     return true;
00319   }
00320 
00321   template <class T>
00322   void ClassLoader<T>::loadClassLibraryInternal(const std::string& library_path, const std::string& list_name_arg) {
00323     std::string list_name = list_name_arg;
00324     boost::replace_first(list_name, "/", "__"); 
00325 
00326     poco_class_loader_.loadLibrary(library_path, list_name);
00327     LibraryCountMap::iterator it = loaded_libraries_.find(library_path);
00328     if (it == loaded_libraries_.end())
00329       loaded_libraries_[library_path] = 1;  //for correct destruction and access
00330     else
00331       loaded_libraries_[library_path] = loaded_libraries_[library_path] + 1;
00332   }
00333 
00334   template <class T>
00335   int ClassLoader<T>::unloadClassLibraryInternal(const std::string& library_path) {
00336     LibraryCountMap::iterator it = loaded_libraries_.find(library_path);
00337     if (it != loaded_libraries_.end() && loaded_libraries_[library_path] > 0)
00338     {
00339       loaded_libraries_[library_path]--;
00340       if (loaded_libraries_[library_path] == 0)
00341         poco_class_loader_.unloadLibrary(library_path);
00342       return loaded_libraries_[library_path];
00343     }
00344     else
00345     {
00346       std::string error_string = "Failed to unload library " + library_path + ". The library was not loaded before or might have already been unloaded.";
00347       throw LibraryUnloadException(error_string);
00348     }
00349   }
00350 
00351   template <class T>
00352   std::vector<std::string> ClassLoader<T>::getClassesInLibrary(const std::string & library_path)
00353   {
00354     std::vector<std::string> lookup_names;
00355 
00356 
00357     const Poco::Manifest<T> * manifest = poco_class_loader_.findManifest(library_path);
00358     if (manifest == NULL)
00359       return lookup_names;
00360 
00361     for (typename Poco::Manifest<T>::Iterator it = manifest->begin(); it != manifest->end(); ++it)
00362     {
00363       std::string name = it->name();
00364       boost::replace_first(name, "__", "/"); 
00365       lookup_names.push_back(name);
00366     }
00367     return lookup_names;
00368   }
00369 
00370   template <class T>
00371   std::vector<std::string> ClassLoader<T>::getRegisteredLibraries()
00372   {
00373     std::vector<std::string> library_names;
00374     for (ClassMapIterator it = classes_available_.begin(); it != classes_available_.end(); it++){
00375       bool duplicate = false;
00376       for (unsigned int i=0; i<library_names.size(); i++)
00377         if (it->second.library_path_ == library_names[i])
00378           duplicate = true;
00379       if (!duplicate)
00380         library_names.push_back(it->second.library_path_);
00381     }
00382     return library_names;
00383   }
00384 
00385 
00386   template <class T>
00387   std::vector<std::string> ClassLoader<T>::getLoadedLibraries()
00388   {
00389     std::vector<std::string> library_names;
00390 
00391     /*
00392        \todo find a way to get ths out of poco
00393        for (typename Poco::ClassLoader<T>::Iterator it = poco_class_loader_.begin(); it != poco_class_loader_.end(); ++it)
00394        {
00395        library_names.push_back(it->second->className());
00396        }
00397        return library_names;
00398        */
00399     LibraryCountMap::iterator it;
00400     for (it = loaded_libraries_.begin(); it != loaded_libraries_.end(); it++)
00401     {
00402       if (it->second > 0)
00403         library_names.push_back(it->first);
00404     }
00405     return library_names;
00406   }
00407 
00408   template <class T>
00409   std::map<std::string, ClassDesc> ClassLoader<T>::determineAvailableClasses()
00410   {
00411     std::map<std::string, ClassDesc> classes_available;
00412     //Pull possible files from manifests of packages which depend on this package and export class
00413     std::vector<std::string> paths;
00414     ros::package::getPlugins(package_, attrib_name_, paths);
00415     if (paths.size() == 0)
00416     {
00417       std::string error_string = "rospack could not find the " + package_ + " package containing " +  base_class_;
00418       throw LibraryLoadException(error_string);
00419     }
00420 
00421     //The poco factory for base class T
00422     for (std::vector<std::string>::iterator it = paths.begin(); it != paths.end(); ++it)
00423     {
00424       TiXmlDocument document;
00425       document.LoadFile(*it);
00426       TiXmlElement * config = document.RootElement();
00427       if (config == NULL)
00428       {
00429         ROS_ERROR("Skipping XML Document \"%s\" which had no Root Element.  This likely means the XML is malformed or missing.", it->c_str());
00430         continue;
00431       }
00432       if (config->ValueStr() != "library" &&
00433           config->ValueStr() != "class_libraries")
00434       {
00435         ROS_ERROR("The XML document \"%s\" given to add must have either \"library\" or \
00436             \"class_libraries\" as the root tag", it->c_str());
00437         continue;
00438       }
00439       //Step into the filter list if necessary
00440       if (config->ValueStr() == "class_libraries")
00441       {
00442         config = config->FirstChildElement("library");
00443       }
00444 
00445       TiXmlElement* library = config;
00446       while ( library != NULL)
00447       {
00448         std::string library_path = library->Attribute("path");
00449         if (library_path.size() == 0)
00450         {
00451           ROS_ERROR("Failed to find Path Attirbute in library element in %s", it->c_str());
00452           continue;
00453         }
00454 
00455         std::string package_name = pluginlib::getPackageFromLibraryPath(*it);
00456         if (package_name == "")
00457           ROS_ERROR("Could not find package name for class %s", it->c_str());
00458 
00459         std::string parent_dir = ros::package::getPath(package_name);
00460         std::string full_library_path = joinPaths(parent_dir , library_path);
00461 
00462         TiXmlElement* class_element = library->FirstChildElement("class");
00463         while (class_element)
00464         {
00465           std::string base_class_type = class_element->Attribute("base_class_type");
00466           std::string lookup_name = class_element->Attribute("name");
00467           std::string derived_class = class_element->Attribute("type");
00468 
00469           //make sure that this class is of the right type before registering it
00470           if(base_class_type == base_class_){
00471 
00472             // register class here
00473             TiXmlElement* description = class_element->FirstChildElement("description");
00474             std::string description_str;
00475             if (description)
00476               description_str = description->GetText() ? description->GetText() : "";
00477             else
00478               description_str = "No 'description' tag for this plugin in plugin description file.";
00479 
00480             classes_available.insert(std::pair<std::string, ClassDesc>(lookup_name, ClassDesc(lookup_name, derived_class, base_class_type, package_name, description_str, full_library_path, *it)));
00481             ROS_DEBUG("MATCHED Base type for class with name: %s type: %s base_class_type: %s Expecting base_class_type %s",
00482                       lookup_name.c_str(), derived_class.c_str(), base_class_type.c_str(), base_class_.c_str());
00483           }
00484           else
00485           {
00486             ROS_DEBUG("UNMATCHED Base type for class with name: %s type: %s base_class_type: %s Expecting base_class_type %s",
00487                       lookup_name.c_str(), derived_class.c_str(), base_class_type.c_str(), base_class_.c_str());
00488 
00489           }
00490           //step to next class_element
00491           class_element = class_element->NextSiblingElement( "class" );
00492         }
00493         library = library->NextSiblingElement( "library" );
00494       }
00495     }
00496     return classes_available;
00497   }
00498 
00499   template <class T>
00500   std::string ClassLoader<T>::getErrorStringForUnknownClass(const std::string& lookup_name)
00501   {
00502     std::string declared_types;
00503     std::vector<std::string> types = getDeclaredClasses();
00504     for ( unsigned int i = 0; i < types.size(); i ++)
00505     {
00506       declared_types = declared_types + std::string(" ") + types[i];
00507     }
00508     return "According to the loaded plugin descriptions the class " + lookup_name 
00509       + " with base class type " + base_class_ + " does not exist. Declared types are " + declared_types;
00510   }
00511 };
00512 
00513 #endif


pluginlib
Author(s): Tully Foote and Eitan Marder-Eppstein
autogenerated on Sat Dec 28 2013 17:20:19