plugin.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 
00030 #ifndef RVE_PLUGINLOADER_PLUGIN_H
00031 #define RVE_PLUGINLOADER_PLUGIN_H
00032 
00033 #include "class_entry.h"
00034 
00035 #include <string>
00036 #include <list>
00037 #include <stdexcept>
00038 
00039 #include <boost/shared_ptr.hpp>
00040 #include <boost/signals.hpp>
00041 
00042 #include <rve_dynlib/dynlib.h>
00043 
00044 namespace YAML
00045 {
00046 class Node;
00047 }
00048 
00049 namespace rve_pluginloader
00050 {
00051 
00052 typedef std::map<std::string, std::string> M_string;
00053 
00054 class Plugin;
00055 struct PluginStatus
00056 {
00057   PluginStatus(Plugin* p)
00058   : plugin(p)
00059   {}
00060   Plugin* plugin;
00061 };
00062 typedef boost::signal<void(const PluginStatus&)> PluginStatusSignal;
00063 
00064 class Exception : public std::runtime_error
00065 {
00066 public:
00067   Exception(const std::string& str)
00068   : std::runtime_error(str)
00069   {}
00070 };
00071 
00072 class PluginParseException : public Exception
00073 {
00074 public:
00075   PluginParseException(const std::string& file, const std::string& error)
00076   : Exception("Unable to parse plugin description file [" + file + "]: " + error)
00077   {}
00078 };
00079 
00080 class LibraryLoadException : public Exception
00081 {
00082 public:
00083   LibraryLoadException(const std::string& library_name, const std::string& error)
00084   : Exception("Unable to load library [" + library_name + "]: " + error)
00085   {}
00086 };
00087 
00088 class LibraryDoesNotExistException : public Exception
00089 {
00090 public:
00091   LibraryDoesNotExistException(const std::string& library_name)
00092   : Exception("Library [" + library_name + "] does not exist on disk")
00093   {}
00094 };
00095 
00096 class NoPluginRegisterFunctionException : public Exception
00097 {
00098 public:
00099   NoPluginRegisterFunctionException(const std::string& library_name)
00100   : Exception("Library [" + library_name + "] does not have an rvePluginRegister(rve_pluginloader::TypeRegistry*) function!")
00101   {}
00102 };
00103 
00104 class PluginDoesNotContainClassException : public Exception
00105 {
00106 public:
00107   PluginDoesNotContainClassException(const std::string& package, const std::string& derived_class)
00108   : Exception("Plugin from package [" + package + "] does not contain class [" + derived_class + "]")
00109   {}
00110 };
00111 
00112 class OutstandingAllocationException : public Exception
00113 {
00114 public:
00115   OutstandingAllocationException(const std::string& str)
00116   : Exception(str)
00117   {}
00118 };
00119 
00120 class Plugin
00121 {
00122 public:
00123   Plugin();
00124   ~Plugin();
00125 
00126   void loadDescription(const std::string& description_path);
00127   void load();
00128   void unload();
00129   bool isLoaded();
00130 
00131   const std::string& getPackageName() const { return package_name_; }
00132   const std::string& getDescriptionPath() const { return description_path_; }
00133   const std::string& getName() { return name_; }
00134 
00135   PluginStatusSignal& getLoadingSignal() { return loading_signal_; }
00136   PluginStatusSignal& getLoadedSignal() { return loaded_signal_; }
00137   PluginStatusSignal& getUnloadingSignal() { return unloading_signal_; }
00138   PluginStatusSignal& getUnloadedSignal() { return unloaded_signal_; }
00139 
00140   YAML::Node& getDescription() { return *doc_; }
00141 
00142   const V_ClassEntry* getClassEntries(const std::string& base_class) const;
00143   const ClassEntryPtr& getClassEntry(const std::string& base_class, const std::string& derived_class) const;
00144 
00145   bool hasClass(const std::string& base_class, const std::string& derived_class) const;
00146 
00147   template<typename T>
00148   T* create(const std::string& base_class, const std::string& derived_class)
00149   {
00150     T* t = static_cast<T*>(create(base_class, derived_class));
00151     return t;
00152   }
00153 
00154   void* create(const std::string& base_class, const std::string& derived_class);
00155 
00156   template<typename T>
00157   boost::shared_ptr<T> createShared(const std::string& base_class, const std::string& derived_class)
00158   {
00159     return boost::static_pointer_cast<T>(createShared(base_class, derived_class));
00160   }
00161 
00162   boost::shared_ptr<void> createShared(const std::string& base_class, const std::string& derived_class);
00163 
00164   void destroy(void* mem);
00165   bool ownsAllocation(void* mem);
00166 
00167 private:
00168   void unload(bool allow_throw);
00169 
00170   std::string description_path_;
00171   std::string package_name_;
00172   std::string package_path_;
00173   std::string library_path_;
00174   std::string name_;
00175 
00176   M_ClassEntry class_entries_;
00177 
00178   bool loaded_;
00179 
00180   rve_dynlib::Handle library_;
00181 
00182   PluginStatusSignal loading_signal_;
00183   PluginStatusSignal loaded_signal_;
00184   PluginStatusSignal unloading_signal_;
00185   PluginStatusSignal unloaded_signal_;
00186 
00187   YAML::Node* doc_;
00188 
00189   struct AllocationInfo
00190   {
00191     void* pointer;
00192     std::vector<void*> backtrace;
00193     std::string base_class;
00194     std::string derived_class;
00195   };
00196   typedef std::map<void*, AllocationInfo> M_AllocationInfo;
00197   M_AllocationInfo allocations_;
00198 };
00199 typedef boost::shared_ptr<Plugin> PluginPtr;
00200 typedef std::list<PluginPtr> L_Plugin;
00201 
00202 }
00203 
00204 #endif // RVE_PLUGINLOADER_PLUGIN_MANAGER_H
00205 


rve_pluginloader
Author(s): Josh Faust
autogenerated on Wed Dec 11 2013 14:31:46