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


pluginlib
Author(s): Eitan Marder-Eppstein, Tully Foote, Dirk Thomas, Mirza Shah
autogenerated on Thu Jul 27 2017 02:19:34