class_loader.hpp
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_HPP_
00030 #define PLUGINLIB__CLASS_LOADER_HPP_
00031 
00032 #include "boost/algorithm/string.hpp"
00033 #include "class_loader/multi_library_class_loader.h"
00034 #include <map>
00035 #include "pluginlib/class_desc.hpp"
00036 #include "pluginlib/class_loader_base.hpp"
00037 #include "pluginlib/exceptions.hpp"
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 {
00048 
00049 #if __cplusplus >= 201103L
00050   template<typename T>
00051   using UniquePtr = class_loader::ClassLoader::UniquePtr<T>;
00052 #endif
00053 
00057   template <class T>
00058     class ClassLoader: public ClassLoaderBase
00059     {
00060       public:
00061         typedef typename std::map<std::string, ClassDesc>::iterator ClassMapIterator;
00062 
00063       public:
00072         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>());
00073 
00077         ~ClassLoader();
00078 
00088         __attribute__((deprecated)) T* createClassInstance(const std::string& lookup_name, bool auto_load = true);
00089 
00098         boost::shared_ptr<T> createInstance(const std::string& lookup_name);
00099 
00100 #if __cplusplus >= 201103L
00101 
00112         UniquePtr<T> createUniqueInstance(const std::string& lookup_name);
00113 #endif
00114 
00124         T* createUnmanagedInstance(const std::string& lookup_name);
00125 
00130         std::vector<std::string> getPluginXmlPaths();
00131 
00136         std::vector<std::string> getDeclaredClasses();
00137 
00143         virtual std::string getName(const std::string& lookup_name);
00144 
00149         virtual std::string getBaseClassType() const;
00150 
00156         virtual std::string getClassType(const std::string& lookup_name);
00157 
00163         virtual std::string getClassDescription(const std::string& lookup_name);
00164 
00170         virtual std::string getClassLibraryPath(const std::string& lookup_name);
00171 
00177         virtual std::string getClassPackage(const std::string& lookup_name);
00178 
00184         virtual std::string getPluginManifestPath(const std::string& lookup_name);
00185 
00190         virtual std::vector<std::string> getRegisteredLibraries();
00191 
00197         bool isClassLoaded(const std::string& lookup_name);
00198 
00204         virtual bool isClassAvailable(const std::string& lookup_name);
00205 
00211         virtual void loadLibraryForClass(const std::string & lookup_name);
00212 
00217         virtual void refreshDeclaredClasses();
00218 
00225         virtual int unloadLibraryForClass(const std::string& lookup_name);
00226 
00227       private:
00228 
00234         std::vector<std::string> getPluginXmlPaths(const std::string& package, const std::string& attrib_name, bool force_recrawl=false);
00235 
00242         std::map<std::string, ClassDesc> determineAvailableClasses(const std::vector<std::string>& plugin_xml_paths);
00243 
00247         std::string extractPackageNameFromPackageXML(const std::string& package_xml_path);
00248 
00252         std::vector<std::string> getAllLibraryPathsToTry(const std::string& library_name, const std::string& exporting_package_name);
00253 
00257         std::vector<std::string> getCatkinLibraryPaths();
00258 
00264         std::string getErrorStringForUnknownClass(const std::string& lookup_name);
00265 
00269         std::string getPathSeparator();
00270 
00274         std::string getROSBuildLibraryPath(const std::string& exporting_package_name);
00275 
00279         std::string getPackageFromPluginXMLFilePath(const std::string & path);
00280 
00284         std::string joinPaths(const std::string& path1, const std::string& path2);
00285 
00289         void processSingleXMLPluginFile(const std::string& xml_file, std::map<std::string, ClassDesc>& class_available);
00290 
00294         std::string stripAllButFileFromPath(const std::string& path);
00295 
00296 
00302         int unloadClassLibraryInternal(const std::string& library_path);
00303 
00304      private:
00305         std::vector<std::string> plugin_xml_paths_;
00306         std::map<std::string, ClassDesc> classes_available_; //Map from library to class's descriptions described in XML
00307         std::string package_;
00308         std::string base_class_;
00309         std::string attrib_name_;
00310         class_loader::MultiLibraryClassLoader lowlevel_class_loader_; //The underlying classloader
00311     };
00312 };
00313 
00314 #include "class_loader_imp.hpp" //Note: The implementation of the methods is in a separate file for clarity
00315 
00316 #endif  // PLUGINLIB__CLASS_LOADER_HPP_


pluginlib
Author(s): Eitan Marder-Eppstein, Tully Foote, Dirk Thomas, Mirza Shah
autogenerated on Sat Jun 8 2019 19:57:35