Skip to content

Commit

Permalink
Fixed bug with redundant destructor definition being pulled into plug…
Browse files Browse the repository at this point in the history
…in library for metaobjects instead of being contained with libclass_loader.so
  • Loading branch information
Mirza Shah committed Jan 17, 2013
1 parent d16155f commit da86427
Show file tree
Hide file tree
Showing 5 changed files with 38 additions and 51 deletions.
17 changes: 6 additions & 11 deletions include/class_loader/class_loader.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@
#define CLASS_LOADER_CLASS_LOADER_H_DEFINED

#include <boost/shared_ptr.hpp>
#include <boost/thread/mutex.hpp>
#include <boost/thread/recursive_mutex.hpp>
#include <boost/bind.hpp>
#include <vector>
#include <string>
Expand Down Expand Up @@ -96,7 +96,7 @@ class ClassLoader
T* obj = createUnmanagedInstance<T>(derived_class_name);
assert(obj != NULL); //Unreachable assertion if createUnmanagedInstance() throws on failure

boost::mutex::scoped_lock lock(plugin_ref_count_mutex_);
boost::recursive_mutex::scoped_lock lock(plugin_ref_count_mutex_);
plugin_ref_count_ = plugin_ref_count_ + 1;

boost::shared_ptr<T> smart_obj(obj, boost::bind(&class_loader::ClassLoader::onPluginDeletion<T>, this, _1));
Expand All @@ -111,7 +111,7 @@ class ClassLoader
template <class Base>
Base* createUnmanagedInstance(const std::string& derived_class_name)
{
ClassLoader::hasUnmanagedInstanceBeenCreated(true);
has_unmananged_instance_been_created_ = true;
if(!isLibraryLoaded())
loadLibrary();

Expand Down Expand Up @@ -175,7 +175,7 @@ class ClassLoader
logDebug("class_loader::ClassLoader: Calling onPluginDeletion() for obj ptr = %p.\n", obj);
if(obj)
{
boost::mutex::scoped_lock lock(plugin_ref_count_mutex_);
boost::recursive_mutex::scoped_lock lock(plugin_ref_count_mutex_);
delete(obj);
plugin_ref_count_ = plugin_ref_count_ - 1;
assert(plugin_ref_count_ >= 0);
Expand All @@ -192,11 +192,6 @@ class ClassLoader
/**
* @brief Getter for if an unmanaged (i.e. unsafe) instance has been created flag
*/
static bool hasUnmanagedInstanceBeenCreated(bool has_it){has_unmananged_instance_been_created_ = has_it;}

/**
* @brief Setter for if an unmanaged (i.e. unsafe) instance has been created flag
*/
static bool hasUnmanagedInstanceBeenCreated(){return has_unmananged_instance_been_created_;}

/**
Expand All @@ -211,9 +206,9 @@ class ClassLoader
bool ondemand_load_unload_;
std::string library_path_;
int load_ref_count_;
boost::mutex load_ref_count_mutex_;
boost::recursive_mutex load_ref_count_mutex_;
int plugin_ref_count_;
boost::mutex plugin_ref_count_mutex_;
boost::recursive_mutex plugin_ref_count_mutex_;
static bool has_unmananged_instance_been_created_;
};

Expand Down
13 changes: 6 additions & 7 deletions include/class_loader/class_loader_core.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,8 @@
#define class_loader_private_H_DEFINED

#include <Poco/SharedLibrary.h>
#include <boost/thread/mutex.hpp>
#include <vector>
#include <boost/thread/recursive_mutex.hpp>
//#include <vector>
#include <map>
#include <typeinfo>
#include <string>
Expand Down Expand Up @@ -124,13 +124,13 @@ FactoryMap& getFactoryMapForBaseClass()
return(getFactoryMapForBaseClass(typeid(Base).name()));
}


/**
* @brief To provide thread safety, all exposed plugin functions can only be run serially by multiple threads. This is implemented by using critical sections enforced by a single mutex which is locked and released with the following two functions
* @return A reference to the global mutex
*/
boost::mutex& getLoadedLibraryVectorMutex();
boost::mutex& getPluginBaseToFactoryMapMapMutex();
boost::recursive_mutex& getLoadedLibraryVectorMutex();
boost::recursive_mutex& getPluginBaseToFactoryMapMapMutex();

/**
* @brief Indicates if a library containing more than just plugins has been opened by the running process
* @return True if a non-pure plugin library has been opened, otherwise false
Expand Down Expand Up @@ -159,7 +159,6 @@ void registerPlugin(const std::string& class_name, const std::string& base_class
//Note: This function will be automatically invoked when a dlopen() call
//opens a library. Normally it will happen within the scope of loadLibrary(),
//but that may not be guaranteed.

logDebug("class_loader::class_loader_private: Registering plugin factory for class = %s, ClassLoader* = %p and library name %s.", class_name.c_str(), getCurrentlyActiveClassLoader(), getCurrentlyLoadingLibraryName().c_str());

if(getCurrentlyActiveClassLoader() == NULL)
Expand Down Expand Up @@ -235,7 +234,7 @@ Base* createInstance(const std::string& derived_class_name, ClassLoader* loader)
template <typename Base>
std::vector<std::string> getAvailableClasses(ClassLoader* loader)
{
boost::mutex::scoped_lock lock(getPluginBaseToFactoryMapMapMutex());
boost::recursive_mutex::scoped_lock lock(getPluginBaseToFactoryMapMapMutex());

FactoryMap& factory_map = getFactoryMapForBaseClass<Base>();
std::vector<std::string> classes;
Expand Down
27 changes: 10 additions & 17 deletions include/class_loader/meta_object.h
Original file line number Diff line number Diff line change
Expand Up @@ -59,9 +59,11 @@ class AbstractMetaObjectBase
*/
AbstractMetaObjectBase(const std::string& class_name, const std::string& base_class_name);
/**
* @brief Destructor for the class
* @brief Destructor for the class. THIS MUST NOT BE VIRTUAL AND OVERRIDDEN BY
* TEMPLATE SUBCLASSES, OTHERWISE THEY WILL PULL IN A REDUNDANT METAOBJECT
* DESTRUCTOR OUTSIDE OF libclass_loader WITHIN THE PLUGIN LIBRARY! T
*/
virtual ~AbstractMetaObjectBase();
~AbstractMetaObjectBase();

/**
* @brief Gets the literal name of the class.
Expand Down Expand Up @@ -117,6 +119,12 @@ class AbstractMetaObjectBase
*/
ClassLoaderVector getAssociatedClassLoaders();

protected:
/**
* This is needed to make base class polymorphic (i.e. have a vtable)
*/
virtual void dummyMethod(){}

protected:
ClassLoaderVector associated_class_loaders_;
std::string associated_library_path_;
Expand Down Expand Up @@ -144,13 +152,6 @@ class AbstractMetaObject : public AbstractMetaObjectBase
AbstractMetaObjectBase::typeid_base_class_name_ = std::string(typeid(B).name());
}

/**
* @brief Desonstructor for this class
*/
virtual ~AbstractMetaObject()
{
}

/**
* @brief Defines the factory interface that the MetaObject must implement.
* @return A pointer of parametric type B to a newly created object.
Expand Down Expand Up @@ -183,14 +184,6 @@ class MetaObject: public AbstractMetaObject<B>
{
}

/**
* @brief Destructor for the class
*/
virtual ~MetaObject()
{
logDebug("class_loader::MetaObject: Destructor for factory for class type = %s.\n", (this->className().c_str()));
}

/**
* @brief The factory interface to generate an object. The object has type C in reality, though a pointer of the base class type is returned.
* @return A pointer to a newly created plugin with the base class type (type parameter B)
Expand Down
8 changes: 4 additions & 4 deletions src/class_loader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ bool ClassLoader::isLibraryLoadedByAnyClassloader()

void ClassLoader::loadLibrary()
{
boost::mutex::scoped_lock lock(load_ref_count_mutex_);
boost::recursive_mutex::scoped_lock lock(load_ref_count_mutex_);
load_ref_count_ = load_ref_count_ + 1;
class_loader::class_loader_private::loadLibrary(getLibraryPath(), this);
}
Expand All @@ -80,10 +80,10 @@ int ClassLoader::unloadLibrary()

int ClassLoader::unloadLibraryInternal(bool lock_plugin_ref_count)
{
boost::mutex::scoped_lock load_ref_lock(load_ref_count_mutex_);
boost::mutex::scoped_lock plugin_ref_lock;
boost::recursive_mutex::scoped_lock load_ref_lock(load_ref_count_mutex_);
boost::recursive_mutex::scoped_lock plugin_ref_lock;
if(lock_plugin_ref_count)
plugin_ref_lock = boost::mutex::scoped_lock(plugin_ref_count_mutex_);
plugin_ref_lock = boost::recursive_mutex::scoped_lock(plugin_ref_count_mutex_);

if(plugin_ref_count_ > 0)
logWarn("class_loader::ClassLoader: SEVERE WARNING!!! Attempting to unload library while objects created by this loader exist in the heap! You should delete your objects before attempting to unload the library or destroying the ClassLoader. The library will NOT be unloaded.");
Expand Down
24 changes: 12 additions & 12 deletions src/class_loader_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,17 +42,17 @@ namespace class_loader_private
/*****************************************************************************/
/*****************************************************************************/

boost::mutex& getLoadedLibraryVectorMutex()
boost::recursive_mutex& getLoadedLibraryVectorMutex()
/*****************************************************************************/
{
static boost::mutex m;
static boost::recursive_mutex m;
return m;
}

boost::mutex& getPluginBaseToFactoryMapMapMutex()
boost::recursive_mutex& getPluginBaseToFactoryMapMapMutex()
/*****************************************************************************/
{
static boost::mutex m;
static boost::recursive_mutex m;
return m;
}

Expand Down Expand Up @@ -165,7 +165,7 @@ MetaObjectVector allMetaObjects(const FactoryMap& factories)
MetaObjectVector allMetaObjects()
/*****************************************************************************/
{
boost::mutex::scoped_lock lock(getPluginBaseToFactoryMapMapMutex());
boost::recursive_mutex::scoped_lock lock(getPluginBaseToFactoryMapMapMutex());

MetaObjectVector all_meta_objs;
BaseToFactoryMapMap& factory_map_map = getGlobalPluginBaseToFactoryMapMap();
Expand Down Expand Up @@ -260,7 +260,7 @@ void destroyMetaObjectsForLibrary(const std::string& library_path, FactoryMap& f
void destroyMetaObjectsForLibrary(const std::string& library_path, const ClassLoader* loader)
/*****************************************************************************/
{
boost::mutex::scoped_lock lock(getPluginBaseToFactoryMapMapMutex());
boost::recursive_mutex::scoped_lock lock(getPluginBaseToFactoryMapMapMutex());

logDebug("class_loader::class_loader_private: Removing MetaObjects associated with library %s and class loader %p from global plugin-to-factorymap map.\n", library_path.c_str(), loader);

Expand Down Expand Up @@ -299,7 +299,7 @@ LibraryVector::iterator findLoadedLibrary(const std::string& library_path)
bool isLibraryLoadedByAnybody(const std::string& library_path)
/*****************************************************************************/
{
boost::mutex::scoped_lock lock(getLoadedLibraryVectorMutex());
boost::recursive_mutex::scoped_lock lock(getLoadedLibraryVectorMutex());

LibraryVector& open_libraries = getLoadedLibraryVector();
LibraryVector::iterator itr = findLoadedLibrary(library_path);
Expand Down Expand Up @@ -359,7 +359,7 @@ void addClassLoaderOwnerForAllExistingMetaObjectsForLibrary(const std::string& l
void revivePreviouslyCreateMetaobjectsFromGraveyard(const std::string& library_path, ClassLoader* loader)
/*****************************************************************************/
{
boost::mutex::scoped_lock b2fmm_lock(getPluginBaseToFactoryMapMapMutex());
boost::recursive_mutex::scoped_lock b2fmm_lock(getPluginBaseToFactoryMapMapMutex());
MetaObjectVector& graveyard = getMetaObjectGraveyard();

for(MetaObjectVector::iterator itr = graveyard.begin(); itr != graveyard.end(); itr++)
Expand All @@ -381,7 +381,7 @@ void purgeGraveyardOfMetaobjects(const std::string& library_path, ClassLoader* l
/*****************************************************************************/
{
MetaObjectVector all_meta_objs = allMetaObjects();
boost::mutex::scoped_lock b2fmm_lock(getPluginBaseToFactoryMapMapMutex()); //Note: Lock must happen after call to allMetaObjects as that will lock
boost::recursive_mutex::scoped_lock b2fmm_lock(getPluginBaseToFactoryMapMapMutex()); //Note: Lock must happen after call to allMetaObjects as that will lock

MetaObjectVector& graveyard = getMetaObjectGraveyard();
MetaObjectVector::iterator itr = graveyard.begin();
Expand Down Expand Up @@ -472,7 +472,7 @@ void loadLibrary(const std::string& library_path, ClassLoader* loader)
}

//Insert library into global loaded library vectory
boost::mutex::scoped_lock llv_lock(getLoadedLibraryVectorMutex());
boost::recursive_mutex::scoped_lock llv_lock(getLoadedLibraryVectorMutex());
LibraryVector& open_libraries = getLoadedLibraryVector();
open_libraries.push_back(LibraryPair(library_path, library_handle)); //Note: Poco::SharedLibrary automatically calls load() when library passed to constructor
}
Expand All @@ -487,7 +487,7 @@ void unloadLibrary(const std::string& library_path, ClassLoader* loader)
else
{
logDebug("class_loader::class_loader_private: Unloading library %s on behalf of ClassLoader %p...", library_path.c_str(), loader);
boost::mutex::scoped_lock lock(getLoadedLibraryVectorMutex());
boost::recursive_mutex::scoped_lock lock(getLoadedLibraryVectorMutex());
LibraryVector& open_libraries = getLoadedLibraryVector();
LibraryVector::iterator itr = findLoadedLibrary(library_path);
if(itr != open_libraries.end())
Expand Down Expand Up @@ -536,7 +536,7 @@ void printDebugInfoToScreen()

printf("OPEN LIBRARIES IN MEMORY:\n");
printf("--------------------------------------------------------------------------------\n");
boost::mutex::scoped_lock lock(getLoadedLibraryVectorMutex());
boost::recursive_mutex::scoped_lock lock(getLoadedLibraryVectorMutex());
LibraryVector libs = getLoadedLibraryVector();
for(unsigned int c = 0; c < libs.size(); c++)
printf("Open library %i = %s (Poco SharedLibrary handle = %p)\n", c, (libs.at(c)).first.c_str(), (libs.at(c)).second);
Expand Down

0 comments on commit da86427

Please sign in to comment.