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 *********************************************************************/
00036 
00037 //NOTE: this should really never be included on its own, but just in case someone is bad we'll guard
00038 
00039 #ifndef PLUGINLIB_CLASS_LOADER_IMP_H_
00040 #define PLUGINLIB_CLASS_LOADER_IMP_H_
00041 
00042 #include "boost/bind.hpp"
00043 #include "boost/filesystem.hpp"
00044 #include <class_loader/class_loader.h>
00045 #include <list>
00046 #include "ros/package.h"
00047 #include <sstream>
00048 #include <stdexcept>
00049 
00050 namespace pluginlib 
00051 {
00052   template <class T>
00053   ClassLoader<T>::ClassLoader(std::string package, std::string base_class, std::string attrib_name, std::vector<std::string> plugin_xml_paths) :
00054   plugin_xml_paths_(plugin_xml_paths),
00055   package_(package),
00056   base_class_(base_class),
00057   attrib_name_(attrib_name),
00058   lowlevel_class_loader_(false) //NOTE: The parameter to the class loader enables/disables on-demand class loading/unloading. Leaving it off for now...libraries will be loaded immediately and won't be unloaded until class loader is destroyed or force unload.
00059   /***************************************************************************/
00060   {
00061     ROS_DEBUG_NAMED("pluginlib.ClassLoader","Creating ClassLoader, base = %s, address = %p", base_class.c_str(), this);
00062     if (plugin_xml_paths_.size() == 0)
00063     {
00064       plugin_xml_paths_ = getPluginXmlPaths(package_, attrib_name_);
00065     }
00066     classes_available_ = determineAvailableClasses(plugin_xml_paths_);
00067     ROS_DEBUG_NAMED("pluginlib.ClassLoader","Finished constructring ClassLoader, base = %s, address = %p", base_class.c_str(), this);
00068   }
00069 
00070   template <class T>
00071   ClassLoader<T>::~ClassLoader()
00072   /***************************************************************************/
00073   {
00074     ROS_DEBUG_NAMED("pluginlib.ClassLoader","Destroying ClassLoader, base = %s, address = %p", getBaseClassType().c_str(), this);
00075   }
00076 
00077   template <class T>
00078   std::string ClassLoader<T>::callCommandLine(const char* cmd)
00079   /***************************************************************************/
00080   {
00081     FILE* pipe = popen(cmd, "r");
00082     if (!pipe)
00083       return "ERROR";
00084     char buffer[128];
00085     std::string result = "";
00086     while(!feof(pipe))
00087     {
00088       if(fgets(buffer, 128, pipe) != NULL)
00089               result += buffer;
00090     }
00091     pclose(pipe);
00092     return result;
00093   }
00094 
00095   template <class T>
00096   T* ClassLoader<T>::createClassInstance(const std::string& lookup_name, bool auto_load)
00097   /***************************************************************************/
00098   {
00099     //Note: This method is deprecated
00100     ROS_DEBUG_NAMED("pluginlib.ClassLoader","In deprecated call createClassInstance(), lookup_name = %s, auto_load = %i.", (lookup_name.c_str()), auto_load);
00101         
00102     if(auto_load && !isClassLoaded(lookup_name))
00103     {
00104       ROS_DEBUG_NAMED("pluginlib.ClassLoader","Autoloading class library before attempting to create instance.");
00105       loadLibraryForClass(lookup_name);
00106     }
00107 
00108     try
00109     {
00110       ROS_DEBUG_NAMED("pluginlib.ClassLoader","Attempting to create instance through low-level MultiLibraryClassLoader...");
00111       T* obj = lowlevel_class_loader_.createUnmanagedInstance<T>(getClassType(lookup_name));
00112       ROS_DEBUG_NAMED("pluginlib.ClassLoader","Instance created with object pointer = %p", obj);
00113       
00114       return obj;
00115     }
00116     catch(const class_loader::CreateClassException& ex)
00117     {
00118       ROS_DEBUG_NAMED("pluginlib.ClassLoader","CreateClassException about to be raised for class %s", lookup_name.c_str());
00119       throw(pluginlib::CreateClassException(ex.what()));
00120     }
00121   }
00122   
00123   template <class T>
00124   boost::shared_ptr<T> ClassLoader<T>::createInstance(const std::string& lookup_name)
00125   /***************************************************************************/
00126   {
00127     ROS_DEBUG_NAMED("pluginlib.ClassLoader","Attempting to create managed instance for class %s.", lookup_name.c_str());
00128     
00129     if(!isClassLoaded(lookup_name))
00130       loadLibraryForClass(lookup_name);
00131     
00132     try
00133     {
00134       std::string class_type = getClassType(lookup_name);
00135       ROS_DEBUG_NAMED("pluginlib.ClassLoader","%s maps to real class type %s", lookup_name.c_str(), class_type.c_str());    
00136     
00137       boost::shared_ptr<T> obj = lowlevel_class_loader_.createInstance<T>(class_type);
00138       
00139       ROS_DEBUG_NAMED("pluginlib.ClassLoader","boost::shared_ptr to object of real type %s created.", class_type.c_str());    
00140       
00141       return obj;
00142     }
00143     catch(const class_loader::CreateClassException& ex)
00144     {
00145       ROS_DEBUG_NAMED("pluginlib.ClassLoader","Exception raised by low-level multi-library class loader when attempting to create instance of class %s.", lookup_name.c_str());
00146       throw(pluginlib::CreateClassException(ex.what()));
00147     }
00148   }
00149 
00150   template <class T>
00151   T* ClassLoader<T>::createUnmanagedInstance(const std::string& lookup_name)
00152   /***************************************************************************/
00153   {
00154     ROS_DEBUG_NAMED("pluginlib.ClassLoader","Attempting to create UNMANAGED instance for class %s.", lookup_name.c_str());
00155 
00156     if(!isClassLoaded(lookup_name))
00157       loadLibraryForClass(lookup_name);
00158 
00159     T* instance = 0;
00160     try
00161     {
00162       ROS_DEBUG_NAMED("pluginlib.ClassLoader","Attempting to create instance through low level multi-library class loader.");
00163       std::string class_type = getClassType(lookup_name);
00164       ROS_DEBUG_NAMED("pluginlib.ClassLoader","%s maps to real class type %s", lookup_name.c_str(), class_type.c_str());
00165       instance = lowlevel_class_loader_.createUnmanagedInstance<T>(class_type);
00166       ROS_DEBUG_NAMED("pluginlib.ClassLoader","Instance of type %s created.", class_type.c_str());
00167     }
00168     catch(const class_loader::CreateClassException& ex) //mas - change exception type here (DONE)
00169     {
00170       ROS_DEBUG_NAMED("pluginlib.ClassLoader","Exception raised by low-level multi-library class loader when attempting to create UNMANAGED instance of class %s.", lookup_name.c_str());
00171       throw(pluginlib::CreateClassException(ex.what()));   
00172     }
00173     return instance;
00174   }
00175 
00176   template <class T>
00177   std::vector<std::string> ClassLoader<T>::getPluginXmlPaths(const std::string& package, const std::string& attrib_name)
00178   /***************************************************************************/
00179   {
00180     //Pull possible files from manifests of packages which depend on this package and export class
00181     std::vector<std::string> paths;
00182     ros::package::getPlugins(package, attrib_name, paths);
00183     return paths;
00184   }
00185 
00186   template <class T>
00187   std::map<std::string, ClassDesc> ClassLoader<T>::determineAvailableClasses(const std::vector<std::string>& plugin_xml_paths)
00188   /***************************************************************************/
00189   {
00190     //mas - This method requires major refactoring...not only is it really long and confusing but a lot of the comments do not seem to be correct. With time I keep correcting small things, but a good rewrite is needed.
00191 
00192     ROS_DEBUG_NAMED("pluginlib.ClassLoader","Entering determineAvailableClasses()...");
00193     std::map<std::string, ClassDesc> classes_available;
00194 
00195     //Walk the list of all plugin XML files (variable "paths") that are exported by the build system
00196     for (std::vector<std::string>::const_iterator it = plugin_xml_paths.begin(); it != plugin_xml_paths.end(); ++it)
00197     {
00198       processSingleXMLPluginFile(*it, classes_available);
00199     }
00200 
00201     ROS_DEBUG_NAMED("pluginlib.ClassLoader","Exiting determineAvailableClasses()...");
00202     return classes_available;
00203   }
00204 
00205   template <class T>
00206   std::string ClassLoader<T>::extractPackageNameFromPackageXML(const std::string& package_xml_path)
00207  /***************************************************************************/  
00208   {
00209       TiXmlDocument document;
00210       document.LoadFile(package_xml_path);
00211       TiXmlElement* doc_root_node = document.FirstChildElement("package");
00212       if (doc_root_node == NULL)
00213       {
00214         ROS_ERROR_NAMED("pluginlib.ClassLoader","Could not find a root element for package manifest at %s.", package_xml_path.c_str());
00215         return "";
00216       }
00217 
00218       assert(doc_root_node == document.RootElement());
00219 
00220       TiXmlElement* package_name_node = doc_root_node->FirstChildElement("name");
00221       if(package_name_node == NULL)
00222       {
00223         ROS_ERROR_NAMED("pluginlib.ClassLoader","package.xml at %s does not have a <name> tag! Cannot determine package which exports plugin.", package_xml_path.c_str());
00224         return "";
00225       }
00226 
00227       return(package_name_node->GetText());
00228   }
00229 
00230   template <class T>
00231   std::vector<std::string> ClassLoader<T>::getCatkinLibraryPaths()
00232   /***************************************************************************/
00233   {
00234     //TODO: This needs to be replaced with an api call
00235     return(parseToStringVector(callCommandLine("catkin_find --lib")));
00236   }
00237 
00238   template <class T>
00239   std::vector<std::string> ClassLoader<T>::getAllLibraryPathsToTry(const std::string& library_name, const std::string& exporting_package_name)
00240   /***************************************************************************/
00241   {
00242     //Catkin-rosbuild Backwards Compatability Rules - Note library_name may be prefixed with relative path (e.g. "/lib/libFoo")
00243     //1. Try catkin library paths (catkin_find --libs) + library_name + extension
00244     //2. Try catkin library paths (catkin_find -- libs) + stripAllButFileFromPath(library_name) + extension
00245     //3. Try export_pkg/library_name + extension
00246 
00247     std::vector<std::string> all_paths;
00248     std::vector<std::string> all_paths_without_extension = getCatkinLibraryPaths();
00249     all_paths_without_extension.push_back(getROSBuildLibraryPath(exporting_package_name));
00250     std::string library_name_with_extension = library_name + class_loader::systemLibrarySuffix();
00251     std::string stripped_library_name_with_extension = stripAllButFileFromPath(library_name) + class_loader::systemLibrarySuffix();
00252     const std::string path_separator = getPathSeparator();
00253 
00254     for(unsigned int c = 0; c < all_paths_without_extension.size(); c++)
00255     {
00256       std::string current_path = all_paths_without_extension.at(c);
00257       all_paths.push_back(current_path + path_separator + library_name_with_extension);
00258       all_paths.push_back(current_path + path_separator + stripped_library_name_with_extension);
00259     }
00260     return(all_paths);
00261   }
00262 
00263   template <class T>
00264   bool ClassLoader<T>::isClassLoaded(const std::string& lookup_name)
00265   /***************************************************************************/
00266   {
00267     return lowlevel_class_loader_.isClassAvailable<T>(getClassType(lookup_name)); //mas - (DONE)
00268   }
00269 
00270   template <class T>
00271   std::string ClassLoader<T>::getBaseClassType() const
00272   /***************************************************************************/
00273   {
00274     return base_class_;
00275   }
00276 
00277     template <class T>
00278   std::string ClassLoader<T>::getClassDescription(const std::string& lookup_name)
00279   /***************************************************************************/
00280   {
00281     ClassMapIterator it = classes_available_.find(lookup_name);
00282     if (it != classes_available_.end())
00283       return it->second.description_;
00284     return "";
00285   }
00286 
00287     template <class T>
00288   std::string ClassLoader<T>::getClassType(const std::string& lookup_name)
00289   /***************************************************************************/
00290   {
00291     ClassMapIterator it = classes_available_.find(lookup_name);
00292     if (it != classes_available_.end())
00293       return it->second.derived_class_;
00294     return "";
00295   }
00296 
00297   template <class T>
00298   std::string ClassLoader<T>::getClassLibraryPath(const std::string& lookup_name)
00299   /***************************************************************************/
00300   {
00301     if (classes_available_.find(lookup_name) == classes_available_.end())
00302     {
00303       ROS_DEBUG_NAMED("pluginlib.ClassLoader","Class %s has no mapping in classes_available_.", lookup_name.c_str());
00304       return "";
00305     }
00306     ClassMapIterator it = classes_available_.find(lookup_name);
00307     std::string library_name = it->second.library_name_;
00308     ROS_DEBUG_NAMED("pluginlib.ClassLoader","Class %s maps to library %s in classes_available_.", lookup_name.c_str(), library_name.c_str());
00309 
00310     std::vector<std::string> paths_to_try = getAllLibraryPathsToTry(library_name, it->second.package_);
00311 
00312     ROS_DEBUG_NAMED("pluginlib.ClassLoader","Iterating through all possible paths where %s could be located...", library_name.c_str());
00313     for(std::vector<std::string>::const_iterator it = paths_to_try.begin(); it != paths_to_try.end(); it++)
00314     {
00315       ROS_DEBUG_NAMED("pluginlib.ClassLoader","Checking path %s ", it->c_str());
00316       if (boost::filesystem::exists(*it))
00317       {
00318         ROS_DEBUG_NAMED("pluginlib.ClassLoader","Library %s found at explicit path %s.", library_name.c_str(), it->c_str());
00319         return *it;
00320       }
00321     }
00322     return "";
00323   }
00324 
00325   template <class T>
00326   std::string ClassLoader<T>::getClassPackage(const std::string& lookup_name)
00327   /***************************************************************************/
00328   {
00329     ClassMapIterator it = classes_available_.find(lookup_name);
00330     if (it != classes_available_.end())
00331       return it->second.package_;
00332     return "";
00333   }
00334 
00335   template <class T>
00336   std::vector<std::string> ClassLoader<T>::getPluginXmlPaths()
00337   /***************************************************************************/
00338   {
00339     return plugin_xml_paths_;
00340   }
00341 
00342   template <class T>
00343   std::vector<std::string> ClassLoader<T>::getDeclaredClasses()
00344   /***************************************************************************/
00345   {
00346     std::vector<std::string> lookup_names;
00347     for (ClassMapIterator it = classes_available_.begin(); it != classes_available_.end(); ++it)
00348       lookup_names.push_back(it->first);
00349 
00350     return lookup_names;
00351   }
00352 
00353   template <class T>
00354   std::string ClassLoader<T>::getErrorStringForUnknownClass(const std::string& lookup_name)
00355   /***************************************************************************/
00356   {
00357     std::string declared_types;
00358     std::vector<std::string> types = getDeclaredClasses();
00359     for ( unsigned int i = 0; i < types.size(); i ++)
00360     {
00361       declared_types = declared_types + std::string(" ") + types[i];
00362     }
00363     return "According to the loaded plugin descriptions the class " + lookup_name 
00364       + " with base class type " + base_class_ + " does not exist. Declared types are " + declared_types;
00365   }
00366 
00367   template <class T>
00368   std::string ClassLoader<T>::getName(const std::string& lookup_name)
00369   /***************************************************************************/
00370   {
00371     //remove the package name to get the raw plugin name
00372     std::vector<std::string> split;
00373     boost::split(split, lookup_name, boost::is_any_of("/"));
00374     return split.back();
00375   }
00376 
00377   template <class T>
00378   std::string ClassLoader<T>::getPackageFromPluginXMLFilePath(const std::string & plugin_xml_file_path)
00379  /***************************************************************************/  
00380   {
00381     //Note: This method takes an input a path to a plugin xml file and must determine which 
00382     //package the XML file came from. This is not necessariliy the same thing as the member
00383     //variable "package_". The plugin xml file can be located anywhere in the source tree for a
00384     //package
00385 
00386     //rosbuild:
00387     //1. Find nearest encasing manifest.xml
00388     //2. Once found, the name of the folder containg the manifest should be the package name we are looking for
00389     //3. Confirm package is findable with rospack
00390 
00391     //catkin:
00392     //1. Find nearest encasing package.xml
00393     //2. Extract name of package from package.xml
00394 
00395     std::string package_name;
00396     boost::filesystem::path p(plugin_xml_file_path);
00397     boost::filesystem::path parent = p.parent_path();
00398 
00399     //Figure out exactly which package the passed XML file is exported by.
00400     while (true)
00401     {
00402       if(boost::filesystem::exists(parent / "package.xml"))
00403       {
00404         std::string package_file_path = (boost::filesystem::path(parent / "package.xml")).string();
00405         return(extractPackageNameFromPackageXML(package_file_path));
00406       }
00407       else if (boost::filesystem::exists(parent / "manifest.xml"))
00408       {
00409 #if BOOST_FILESYSTEM_VERSION >= 3
00410         std::string package = parent.filename().string();
00411 #else
00412         std::string package = parent.filename();
00413 #endif
00414         std::string package_path = ros::package::getPath(package);
00415 
00416         if (plugin_xml_file_path.find(package_path) == 0) //package_path is a substr of passed plugin xml path
00417         {
00418           package_name = package;
00419           break;
00420         }       
00421       }
00422 
00423       //Recursive case - hop one folder up
00424       parent = parent.parent_path().string();
00425 
00426       //Base case - reached root and cannot find what we're looking for
00427       if (parent.string().empty())
00428         return "";
00429     }
00430 
00431     return package_name;    
00432   }
00433 
00434   template <class T>
00435   std::string ClassLoader<T>::getPathSeparator()
00436   /***************************************************************************/
00437   {
00438 #if BOOST_FILESYSTEM_VERSION >= 3
00439     return(boost::filesystem::path("/").native());
00440 #else
00441     return(boost::filesystem::path("/").external_file_string());
00442 #endif
00443   }
00444 
00445 
00446   template <class T>
00447   std::string ClassLoader<T>::getPluginManifestPath(const std::string& lookup_name)
00448   /***************************************************************************/
00449   {
00450     ClassMapIterator it = classes_available_.find(lookup_name);
00451     if (it != classes_available_.end())
00452       return it->second.plugin_manifest_path_;
00453     return "";
00454   }
00455 
00456 
00457   template <class T>
00458   std::vector<std::string> ClassLoader<T>::getRegisteredLibraries()
00459   /***************************************************************************/
00460   {
00461     return(lowlevel_class_loader_.getRegisteredLibraries());
00462   }
00463 
00464   template <class T>
00465   std::string ClassLoader<T>::getROSBuildLibraryPath(const std::string& exporting_package_name)
00466   /***************************************************************************/
00467   {
00468     return(ros::package::getPath(exporting_package_name));
00469   }
00470 
00471   template <class T>
00472   bool ClassLoader<T>::isClassAvailable(const std::string& lookup_name)
00473   /***************************************************************************/
00474   {
00475     return classes_available_.find(lookup_name) != classes_available_.end();
00476   }
00477 
00478   template <class T>
00479   std::string ClassLoader<T>::joinPaths(const std::string& path1, const std::string& path2)
00480   /***************************************************************************/
00481   {
00482     boost::filesystem::path p1(path1);
00483     return (p1 / path2).string();
00484   }
00485 
00486   template <class T>
00487   void ClassLoader<T>::loadLibraryForClass(const std::string& lookup_name)
00488   /***************************************************************************/
00489   {
00490     ClassMapIterator it = classes_available_.find(lookup_name);
00491     if (it == classes_available_.end())
00492     {
00493       ROS_DEBUG_NAMED("pluginlib.ClassLoader","Class %s has no mapping in classes_available_.", lookup_name.c_str());
00494       throw pluginlib::LibraryLoadException(getErrorStringForUnknownClass(lookup_name));
00495     }
00496 
00497     std::string library_path = getClassLibraryPath(lookup_name);
00498     if (library_path == "")
00499     {
00500       ROS_DEBUG_NAMED("pluginlib.ClassLoader","No path could be found to the library containing %s.", lookup_name.c_str());
00501       std::ostringstream error_msg;
00502       error_msg << "Could not find library corresponding to plugin " << lookup_name << ". Make sure the plugin description XML file has the correct name of the library and that the library actually exists.";
00503       throw pluginlib::LibraryLoadException(error_msg.str());
00504     }
00505 
00506     try
00507     {
00508       lowlevel_class_loader_.loadLibrary(library_path);
00509       it->second.resolved_library_path_ = library_path;
00510     }
00511     catch(const class_loader::LibraryLoadException& ex)
00512     {
00513       std::string error_string = "Failed to load library " + library_path + ". Make sure that you are calling the PLUGINLIB_EXPORT_CLASS macro in the library code, and that names are consistent between this macro and your XML. Error string: " + ex.what();
00514       throw pluginlib::LibraryLoadException(error_string);
00515     }
00516   }
00517 
00518   template <class T>
00519   std::vector<std::string> ClassLoader<T>::parseToStringVector(std::string newline_delimited_str)
00520   /***************************************************************************/
00521   {
00522     std::string next;
00523     std::vector<std::string> parse_result;
00524     for(unsigned int c = 0; c < newline_delimited_str.size(); c++)
00525     {
00526       char ch = newline_delimited_str.at(c);
00527       if(ch == '\n')
00528       {
00529         parse_result.push_back(next);
00530         next = "";
00531       }
00532       else
00533         next.push_back(ch);
00534     }
00535     return(parse_result);
00536   }
00537 
00538 
00539   template <class T>
00540   void ClassLoader<T>::processSingleXMLPluginFile(const std::string& xml_file, std::map<std::string, ClassDesc>& classes_available)
00541   /***************************************************************************/
00542   {
00543     ROS_DEBUG_NAMED("pluginlib.ClassLoader","Processing xml file %s...", xml_file.c_str());
00544     TiXmlDocument document;
00545     document.LoadFile(xml_file);
00546     TiXmlElement * config = document.RootElement();
00547     if (config == NULL)
00548     {
00549       ROS_ERROR_NAMED("pluginlib.ClassLoader","Skipping XML Document \"%s\" which had no Root Element.  This likely means the XML is malformed or missing.", xml_file.c_str());
00550       return;
00551     }
00552     if (config->ValueStr() != "library" &&
00553         config->ValueStr() != "class_libraries")
00554     {
00555       ROS_ERROR_NAMED("pluginlib.ClassLoader","The XML document \"%s\" given to add must have either \"library\" or \
00556           \"class_libraries\" as the root tag", xml_file.c_str());
00557       return;
00558     }
00559     //Step into the filter list if necessary
00560     if (config->ValueStr() == "class_libraries")
00561     {
00562       config = config->FirstChildElement("library");
00563     }
00564 
00565     TiXmlElement* library = config;
00566     while ( library != NULL)
00567     {
00568       std::string library_path = library->Attribute("path");
00569       if (library_path.size() == 0)
00570       {
00571         ROS_ERROR_NAMED("pluginlib.ClassLoader","Failed to find Path Attirbute in library element in %s", xml_file.c_str());
00572         continue;
00573       }
00574 
00575       std::string package_name = getPackageFromPluginXMLFilePath(xml_file);
00576       if (package_name == "")
00577         ROS_ERROR_NAMED("pluginlib.ClassLoader","Could not find package manifest (neither package.xml or deprecated manifest.xml) at same directory level as the plugin XML file %s. Plugins will likely not be exported properly.\n)", xml_file.c_str());
00578 
00579       TiXmlElement* class_element = library->FirstChildElement("class");
00580       while (class_element)
00581       {
00582         std::string base_class_type = class_element->Attribute("base_class_type");
00583         std::string derived_class = class_element->Attribute("type");
00584 
00585         std::string lookup_name;
00586         if(class_element->Attribute("name") != NULL)
00587         {
00588           lookup_name = class_element->Attribute("name");
00589           ROS_DEBUG_NAMED("pluginlib.ClassLoader","XML file specifies lookup name (i.e. magic name) = %s.", lookup_name.c_str());          
00590         }
00591         else
00592         {
00593           ROS_DEBUG_NAMED("pluginlib.ClassLoader","XML file has no lookup name (i.e. magic name) for class %s, assuming lookup_name == real class name.", derived_class.c_str());
00594           lookup_name = derived_class;
00595         }
00596 
00597         //make sure that this class is of the right type before registering it
00598         if(base_class_type == base_class_){
00599 
00600           // register class here
00601           TiXmlElement* description = class_element->FirstChildElement("description");
00602           std::string description_str;
00603           if (description)
00604             description_str = description->GetText() ? description->GetText() : "";
00605           else
00606             description_str = "No 'description' tag for this plugin in plugin description file.";
00607 
00608           classes_available.insert(std::pair<std::string, ClassDesc>(lookup_name, ClassDesc(lookup_name, derived_class, base_class_type, package_name, description_str, library_path, xml_file)));
00609         }
00610 
00611         //step to next class_element
00612         class_element = class_element->NextSiblingElement( "class" );
00613       }
00614       library = library->NextSiblingElement( "library" );
00615     }
00616   }
00617 
00618   template <class T>
00619   void ClassLoader<T>::refreshDeclaredClasses()
00620   /***************************************************************************/
00621   {
00622     ROS_DEBUG_NAMED("pluginlib.ClassLoader","Refreshing declared classes.");
00623     // determine classes not currently loaded for removal
00624     std::list<std::string> remove_classes;
00625     for (std::map<std::string, ClassDesc>::const_iterator it = classes_available_.begin(); it != classes_available_.end(); it++)
00626     {
00627 
00628       std::string resolved_library_path = it->second.resolved_library_path_;
00629       std::vector<std::string> open_libs = lowlevel_class_loader_.getRegisteredLibraries();
00630       if(std::find(open_libs.begin(), open_libs.end(), resolved_library_path) != open_libs.end())
00631         remove_classes.push_back(it->first);
00632     }
00633 
00634     while (!remove_classes.empty())
00635     {
00636       classes_available_.erase(remove_classes.front());
00637       remove_classes.pop_front();
00638     }
00639 
00640     // add new classes
00641     plugin_xml_paths_ = getPluginXmlPaths(package_, attrib_name_);
00642     std::map<std::string, ClassDesc> updated_classes = determineAvailableClasses(plugin_xml_paths_);
00643     for (std::map<std::string, ClassDesc>::const_iterator it = updated_classes.begin(); it != updated_classes.end(); it++)
00644     {
00645       if (classes_available_.find(it->first) == classes_available_.end())
00646         classes_available_.insert(std::pair<std::string, ClassDesc>(it->first, it->second));
00647     }
00648   }
00649 
00650   template <class T>
00651   std::string ClassLoader<T>::stripAllButFileFromPath(const std::string& path)
00652   /***************************************************************************/
00653   {
00654     std::string only_file;
00655     size_t c = path.find_last_of(getPathSeparator());
00656     if(c == std::string::npos)
00657       return(path);
00658     else
00659       return(path.substr(c, path.size()));
00660   }
00661 
00662   template <class T>
00663   int ClassLoader<T>::unloadLibraryForClass(const std::string& lookup_name)
00664   /***************************************************************************/
00665   {
00666     ClassMapIterator it = classes_available_.find(lookup_name);
00667     if (it != classes_available_.end() && it->second.resolved_library_path_ != "UNRESOLVED")
00668     {
00669       std::string library_path = it->second.resolved_library_path_;
00670       ROS_DEBUG_NAMED("pluginlib.ClassLoader","Attempting to unload library %s for class %s", library_path.c_str(), lookup_name.c_str());
00671       return unloadClassLibraryInternal(library_path);
00672     }
00673     else
00674     {
00675       throw pluginlib::LibraryUnloadException(getErrorStringForUnknownClass(lookup_name));
00676     }
00677   }
00678 
00679   template <class T>
00680   int ClassLoader<T>::unloadClassLibraryInternal(const std::string& library_path)
00681   /***************************************************************************/
00682   {
00683     return(lowlevel_class_loader_.unloadLibrary(library_path));
00684   }
00685 
00686 }
00687 
00688   
00689 
00690 
00691 #endif


pluginlib
Author(s): Eitan Marder-Eppstein, Tully Foote, Dirk Thomas, Mirza Shah
autogenerated on Mon Oct 6 2014 03:26:36