class_loader.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2012, 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 
00030 #ifndef CLASS_LOADER_CLASS_LOADER_H_DEFINED
00031 #define CLASS_LOADER_CLASS_LOADER_H_DEFINED
00032 
00033 #include <boost/shared_ptr.hpp>
00034 #include <boost/thread/recursive_mutex.hpp>
00035 #include <boost/bind.hpp>
00036 #include <vector>
00037 #include <string>
00038 #include <console_bridge/console.h>
00039 #include "class_loader/class_loader_register_macro.h"
00040 #include "class_loader/class_loader_core.h"
00041 
00042 namespace class_loader
00043 {
00044 
00048 std::string systemLibrarySuffix();
00049 
00050 
00051 
00056 class ClassLoader
00057 {
00058   public:
00064     ClassLoader(const std::string& library_path, bool ondemand_load_unload = false);
00065 
00069     virtual ~ClassLoader();
00070 
00075     template <class Base>
00076     std::vector<std::string> getAvailableClasses()
00077     {
00078       return(class_loader::class_loader_private::getAvailableClasses<Base>(this));
00079     }
00080 
00084     std::string getLibraryPath(){return(library_path_);}
00085 
00091     template <class Base>    
00092     boost::shared_ptr<Base> createInstance(const std::string& derived_class_name)
00093     {
00094       if(ClassLoader::hasUnmanagedInstanceBeenCreated() && isOnDemandLoadUnloadEnabled())
00095         logInform("class_loader::ClassLoader: An attempt is being made to create a managed plugin instance (i.e. boost::shared_ptr), however an unmanaged instance was created within this process address space. This means libraries for the managed instances will not be shutdown automatically on final plugin destruction if on demand (lazy) loading/unloading mode is used.");
00096 
00097       if(!isLibraryLoaded())
00098         loadLibrary();
00099 
00100       Base* obj = class_loader::class_loader_private::createInstance<Base>(derived_class_name, this);
00101       assert(obj != NULL); //Unreachable assertion if createInstance() throws on failure
00102 
00103       boost::recursive_mutex::scoped_lock lock(plugin_ref_count_mutex_);
00104       plugin_ref_count_ = plugin_ref_count_ + 1;
00105 
00106       boost::shared_ptr<Base> smart_obj(obj, boost::bind(&class_loader::ClassLoader::onPluginDeletion<Base>, this, _1));
00107       return(smart_obj);
00108     }
00109 
00115     template <class Base>
00116     Base* createUnmanagedInstance(const std::string& derived_class_name)
00117     {
00118       has_unmananged_instance_been_created_ = true;
00119       if(!isLibraryLoaded())
00120         loadLibrary();
00121 
00122       Base* obj = class_loader::class_loader_private::createInstance<Base>(derived_class_name, this);
00123       assert(obj != NULL); //Unreachable assertion if createInstance() throws on failure
00124 
00125       return(obj);
00126     }
00127 
00134     template <class Base>
00135     bool isClassAvailable(const std::string& class_name)
00136     {
00137       std::vector<std::string> available_classes = getAvailableClasses<Base>();
00138       return(std::find(available_classes.begin(), available_classes.end(), class_name) != available_classes.end());
00139     }
00140 
00146     bool isLibraryLoaded();
00147 
00152     bool isLibraryLoadedByAnyClassloader();
00153 
00157     bool isOnDemandLoadUnloadEnabled(){return(ondemand_load_unload_);}
00158 
00163     void loadLibrary();
00164 
00169     int unloadLibrary();
00170 
00171   private:
00176     template <class Base>    
00177     void onPluginDeletion(Base* obj)
00178     {
00179       logDebug("class_loader::ClassLoader: Calling onPluginDeletion() for obj ptr = %p.\n", obj);
00180       if(obj)
00181       {
00182         boost::recursive_mutex::scoped_lock lock(plugin_ref_count_mutex_);
00183         delete(obj);
00184         plugin_ref_count_ = plugin_ref_count_ - 1;
00185         assert(plugin_ref_count_ >= 0);
00186         if(plugin_ref_count_ == 0 && isOnDemandLoadUnloadEnabled())
00187         {
00188           if(!ClassLoader::hasUnmanagedInstanceBeenCreated())
00189             unloadLibraryInternal(false);
00190           else
00191             logWarn("class_loader::ClassLoader: Cannot unload library %s even though last shared pointer went out of scope. This is because createUnmanagedInstance was used within the scope of this process, perhaps by a different ClassLoader. Library will NOT be closed.", getLibraryPath().c_str());
00192         }
00193       }
00194     }
00195 
00199     static bool hasUnmanagedInstanceBeenCreated();
00200 
00206     int unloadLibraryInternal(bool lock_plugin_ref_count);
00207 
00208   private:
00209 
00210     bool ondemand_load_unload_;
00211     std::string library_path_;
00212     int load_ref_count_;  
00213     boost::recursive_mutex load_ref_count_mutex_;
00214     int plugin_ref_count_;
00215     boost::recursive_mutex plugin_ref_count_mutex_;
00216     static bool has_unmananged_instance_been_created_;
00217 };
00218 
00219 }
00220 
00221 
00222 #endif


class_loader
Author(s): Mirza Shah
autogenerated on Sun Oct 5 2014 22:50:57