class_loader.hpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2012, Willow Garage, Inc.
00005  * All rights reserved.
00006  *
00007  * Redistribution and use in source and binary forms, with or without
00008  * modification, are permitted provided that the following conditions are met:
00009  *
00010  *     * Redistributions of source code must retain the above copyright
00011  *       notice, this list of conditions and the following disclaimer.
00012  *     * Redistributions in binary form must reproduce the above copyright
00013  *       notice, this list of conditions and the following disclaimer in the
00014  *       documentation and/or other materials provided with the distribution.
00015  *     * Neither the name of the copyright holders nor the names of its
00016  *       contributors may be used to endorse or promote products derived from
00017  *       this software without specific prior written permission.
00018  *
00019  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00020  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00021  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00022  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00023  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00024  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00025  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00026  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00027  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00028  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029  * POSSIBILITY OF SUCH DAMAGE.
00030  */
00031 
00032 #ifndef CLASS_LOADER__CLASS_LOADER_HPP_
00033 #define CLASS_LOADER__CLASS_LOADER_HPP_
00034 
00035 #include <boost/bind.hpp>
00036 #include <boost/shared_ptr.hpp>
00037 #include <boost/thread/recursive_mutex.hpp>
00038 #include <string>
00039 #include <vector>
00040 
00041 #include "console_bridge/console.h"
00042 
00043 #include "class_loader/class_loader_core.hpp"
00044 #include "class_loader/console_bridge_compatibility.hpp"
00045 #include "class_loader/register_macro.hpp"
00046 
00047 #if __cplusplus >= 201103L
00048 #include <memory>
00049 #include <functional>
00050 #endif
00051 
00052 // TODO(mikaelarguedas) : replace no lints with the explicit keyword in an ABI breaking release
00053 
00054 namespace class_loader
00055 {
00056 
00060 std::string systemLibrarySuffix();
00061 
00066 class ClassLoader
00067 {
00068 public:
00069 #if __cplusplus >= 201103L
00070   template<typename Base>
00071   using DeleterType = std::function<void(Base *)>;
00072 
00073   template<typename Base>
00074   using UniquePtr = std::unique_ptr<Base, DeleterType<Base>>;
00075 #endif
00076 
00082   ClassLoader(const std::string & library_path, bool ondemand_load_unload = false);  // NOLINT
00083 
00087   virtual ~ClassLoader();
00088 
00093   template<class Base>
00094   std::vector<std::string> getAvailableClasses()
00095   {
00096     return class_loader::class_loader_private::getAvailableClasses<Base>(this);
00097   }
00098 
00102   std::string getLibraryPath() {return library_path_;}
00103 
00113   template<class Base>
00114   boost::shared_ptr<Base> createInstance(const std::string & derived_class_name)
00115   {
00116     return boost::shared_ptr<Base>(
00117       createRawInstance<Base>(derived_class_name, true),
00118       boost::bind(&ClassLoader::onPluginDeletion<Base>, this, _1));
00119   }
00120 
00121 #if __cplusplus >= 201103L
00122 
00134   template<class Base>
00135   UniquePtr<Base> createUniqueInstance(const std::string & derived_class_name)
00136   {
00137     Base * raw = createRawInstance<Base>(derived_class_name, true);
00138     return std::unique_ptr<Base, DeleterType<Base>>(
00139       raw,
00140       boost::bind(&ClassLoader::onPluginDeletion<Base>, this, _1));
00141   }
00142 #endif
00143 
00156   template<class Base>
00157   Base * createUnmanagedInstance(const std::string & derived_class_name)
00158   {
00159     return createRawInstance<Base>(derived_class_name, false);
00160   }
00161 
00168   template<class Base>
00169   bool isClassAvailable(const std::string & class_name)
00170   {
00171     std::vector<std::string> available_classes = getAvailableClasses<Base>();
00172     return std::find(
00173       available_classes.begin(), available_classes.end(), class_name) != available_classes.end();
00174   }
00175 
00181   bool isLibraryLoaded();
00182 
00187   bool isLibraryLoadedByAnyClassloader();
00188 
00192   bool isOnDemandLoadUnloadEnabled() {return ondemand_load_unload_;}
00193 
00198   void loadLibrary();
00199 
00204   int unloadLibrary();
00205 
00206 private:
00211   template<class Base>
00212   void onPluginDeletion(Base * obj)
00213   {
00214     CONSOLE_BRIDGE_logDebug(
00215       "class_loader::ClassLoader: Calling onPluginDeletion() for obj ptr = %p.\n", obj);
00216     if (obj) {
00217       boost::recursive_mutex::scoped_lock lock(plugin_ref_count_mutex_);
00218       delete (obj);
00219       plugin_ref_count_ = plugin_ref_count_ - 1;
00220       assert(plugin_ref_count_ >= 0);
00221       if (0 == plugin_ref_count_ && isOnDemandLoadUnloadEnabled()) {
00222         if (!ClassLoader::hasUnmanagedInstanceBeenCreated()) {
00223           unloadLibraryInternal(false);
00224         } else {
00225           CONSOLE_BRIDGE_logWarn(
00226             "class_loader::ClassLoader: "
00227             "Cannot unload library %s even though last shared pointer went out of scope. "
00228             "This is because createUnmanagedInstance was used within the scope of this process,"
00229             " perhaps by a different ClassLoader. Library will NOT be closed.",
00230             getLibraryPath().c_str());
00231         }
00232       }
00233     }
00234   }
00235 
00246   template<class Base>
00247   Base * createRawInstance(const std::string & derived_class_name, bool managed)
00248   {
00249     if (!managed) {
00250       has_unmananged_instance_been_created_ = true;
00251     }
00252 
00253     if (
00254       managed &&
00255       ClassLoader::hasUnmanagedInstanceBeenCreated() &&
00256       isOnDemandLoadUnloadEnabled())
00257     {
00258       CONSOLE_BRIDGE_logInform("%s",
00259         "class_loader::ClassLoader: "
00260         "An attempt is being made to create a managed plugin instance (i.e. boost::shared_ptr), "
00261         "however an unmanaged instance was created within this process address space. "
00262         "This means libraries for the managed instances will not be shutdown automatically on "
00263         "final plugin destruction if on demand (lazy) loading/unloading mode is used."
00264       );
00265     }
00266     if (!isLibraryLoaded()) {
00267       loadLibrary();
00268     }
00269 
00270     Base * obj =
00271       class_loader::class_loader_private::createInstance<Base>(derived_class_name, this);
00272     assert(obj != NULL);  // Unreachable assertion if createInstance() throws on failure
00273 
00274     if (managed) {
00275       boost::recursive_mutex::scoped_lock lock(plugin_ref_count_mutex_);
00276       plugin_ref_count_ = plugin_ref_count_ + 1;
00277     }
00278 
00279     return obj;
00280   }
00281 
00285   static bool hasUnmanagedInstanceBeenCreated();
00286 
00292   int unloadLibraryInternal(bool lock_plugin_ref_count);
00293 
00294 private:
00295   bool ondemand_load_unload_;
00296   std::string library_path_;
00297   int load_ref_count_;
00298   boost::recursive_mutex load_ref_count_mutex_;
00299   int plugin_ref_count_;
00300   boost::recursive_mutex plugin_ref_count_mutex_;
00301   static bool has_unmananged_instance_been_created_;
00302 };
00303 
00304 }  // namespace class_loader
00305 
00306 
00307 #endif  // CLASS_LOADER__CLASS_LOADER_HPP_


class_loader
Author(s): Mirza Shah
autogenerated on Thu Jun 6 2019 20:43:27