class_loader.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2009, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 #ifndef PLUGINLIB_CLASS_LOADER_H
00030 #define PLUGINLIB_CLASS_LOADER_H
00031 
00032 #include "boost/algorithm/string.hpp"
00033 #include "class_loader/multi_library_class_loader.h"
00034 #include <map>
00035 #include "pluginlib/class_desc.h"
00036 #include "pluginlib/class_loader_base.h"
00037 #include "pluginlib/pluginlib_exceptions.h"
00038 #include "ros/console.h"
00039 #include "ros/package.h"
00040 #include "tinyxml.h"
00041 
00042 //Note: pluginlib has traditionally utilized a "lookup name" for classes that does not match its real C++ name. This was
00043 //done due to limitations of how pluginlib was implemented. As of version 1.9, a lookup name is no longer necessary and
00044 //an attempt to the merge two concepts is underway
00045 
00046 namespace pluginlib
00047 {
00052   template <class T>
00053     class ClassLoader: public ClassLoaderBase
00054     {
00055       public:
00056         typedef typename std::map<std::string, ClassDesc>::iterator ClassMapIterator;
00057 
00058       public:
00067         ClassLoader(std::string package, std::string base_class, std::string attrib_name = std::string("plugin"), std::vector<std::string> plugin_xml_paths = std::vector<std::string>());
00068 
00072         ~ClassLoader();
00073 
00083         __attribute__((deprecated)) T* createClassInstance(const std::string& lookup_name, bool auto_load = true);
00084 
00092         boost::shared_ptr<T> createInstance(const std::string& lookup_name);
00093 
00102         T* createUnmanagedInstance(const std::string& lookup_name);
00103 
00108         std::vector<std::string> getPluginXmlPaths();
00109 
00114         std::vector<std::string> getDeclaredClasses();
00115 
00121         virtual std::string getName(const std::string& lookup_name);
00122 
00127         virtual std::string getBaseClassType() const;
00128 
00134         virtual std::string getClassType(const std::string& lookup_name);
00135 
00141         virtual std::string getClassDescription(const std::string& lookup_name);
00142 
00148         virtual std::string getClassLibraryPath(const std::string& lookup_name);
00149 
00155         virtual std::string getClassPackage(const std::string& lookup_name);
00156 
00162         virtual std::string getPluginManifestPath(const std::string& lookup_name);
00163 
00168         virtual std::vector<std::string> getRegisteredLibraries();
00169 
00175         bool isClassLoaded(const std::string& lookup_name);
00176         
00182         virtual bool isClassAvailable(const std::string& lookup_name);
00183 
00189         virtual void loadLibraryForClass(const std::string & lookup_name);
00190 
00195         virtual void refreshDeclaredClasses();
00196 
00203         virtual int unloadLibraryForClass(const std::string& lookup_name);
00204 
00205       private:
00209         std::string callCommandLine(const char* cmd);
00210 
00216         std::vector<std::string> getPluginXmlPaths(const std::string& package, const std::string& attrib_name);
00217 
00224         std::map<std::string, ClassDesc> determineAvailableClasses(const std::vector<std::string>& plugin_xml_paths);
00225 
00229         std::string extractPackageNameFromPackageXML(const std::string& package_xml_path);
00230 
00234         std::vector<std::string> getAllLibraryPathsToTry(const std::string& library_name, const std::string& exporting_package_name);
00235 
00239         std::vector<std::string> getCatkinLibraryPaths();
00240 
00246         std::string getErrorStringForUnknownClass(const std::string& lookup_name);
00247 
00251         std::string getPathSeparator();
00252         
00256         std::string getROSBuildLibraryPath(const std::string& exporting_package_name);
00257 
00261         std::string getPackageFromPluginXMLFilePath(const std::string & path);  
00262 
00266         std::string joinPaths(const std::string& path1, const std::string& path2);       
00267 
00271         std::vector<std::string> parseToStringVector(std::string newline_delimited_str);
00272 
00276         void processSingleXMLPluginFile(const std::string& xml_file, std::map<std::string, ClassDesc>& class_available);
00277 
00281         std::string stripAllButFileFromPath(const std::string& path);
00282 
00283 
00289         int unloadClassLibraryInternal(const std::string& library_path);        
00290 
00291      private:
00292         std::vector<std::string> plugin_xml_paths_;
00293         std::map<std::string, ClassDesc> classes_available_; //Map from library to class's descriptions described in XML
00294         std::string package_;
00295         std::string base_class_;
00296         std::string attrib_name_;
00297         class_loader::MultiLibraryClassLoader lowlevel_class_loader_; //The underlying classloader
00298     };
00299 };
00300 
00301 #include "class_loader_imp.h" //Note: The implementation of the methods is in a separate file for clarity
00302 
00303 #endif //PLUGINLIB_CLASS_LOADER_H
00304 


pluginlib
Author(s): Eitan Marder-Eppstein, Tully Foote, Dirk Thomas, Mirza Shah
autogenerated on Wed Aug 26 2015 15:28:48