ros_pluginlib_plugin_provider.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2011, Dirk Thomas, TU Darmstadt
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
00007  * are met:
00008  *
00009  *   * Redistributions of source code must retain the above copyright
00010  *     notice, this list of conditions and the following disclaimer.
00011  *   * Redistributions in binary form must reproduce the above
00012  *     copyright notice, this list of conditions and the following
00013  *     disclaimer in the documentation and/or other materials provided
00014  *     with the distribution.
00015  *   * Neither the name of the TU Darmstadt nor the names of its
00016  *     contributors may be used to endorse or promote products derived
00017  *     from this software without specific prior written permission.
00018  *
00019  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00020  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00021  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00022  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00023  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00024  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00025  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00026  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00027  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00028  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00029  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00030  * POSSIBILITY OF SUCH DAMAGE.
00031  */
00032 
00033 #ifndef qt_gui_cpp__RosPluginlibPluginProvider_H
00034 #define qt_gui_cpp__RosPluginlibPluginProvider_H
00035 
00036 #include "plugin.h"
00037 #include "plugin_context.h"
00038 #include "plugin_descriptor.h"
00039 #include "plugin_provider.h"
00040 
00041 #include <boost/shared_ptr.hpp>
00042 
00043 #include <pluginlib/class_loader.h>
00044 
00045 #include <QCoreApplication>
00046 #include <QEvent>
00047 #include <QList>
00048 #include <QMap>
00049 #include <QObject>
00050 #include <QString>
00051 
00052 #include <fstream>
00053 #include <string>
00054 #include <vector>
00055 
00056 namespace qt_gui_cpp
00057 {
00058 
00059 template<typename T>
00060 class RosPluginlibPluginProvider
00061   : public QObject
00062   , public PluginProvider
00063 {
00064 
00065 public:
00066 
00067   static RosPluginlibPluginProvider<T>* create_instance(const QString& export_tag, const QString& base_class_type)
00068   {
00069     return new RosPluginlibPluginProvider<T>(export_tag, base_class_type);
00070   }
00071 
00072   RosPluginlibPluginProvider(const QString& export_tag, const QString& base_class_type)
00073     : QObject()
00074     , PluginProvider()
00075     , export_tag_(export_tag)
00076     , base_class_type_(base_class_type)
00077     , class_loader_(0)
00078   {
00079     unload_libraries_event_ = QEvent::registerEventType();
00080   }
00081 
00082   virtual ~RosPluginlibPluginProvider()
00083   {
00084     if (class_loader_)
00085     {
00086       delete class_loader_;
00087     }
00088   }
00089 
00090   virtual QMap<QString, QString> discover(QObject* discovery_data)
00091   {
00092     return PluginProvider::discover(discovery_data);
00093   }
00094 
00095   virtual QList<PluginDescriptor*> discover_descriptors(QObject* discovery_data)
00096   {
00097     if (class_loader_)
00098     {
00099       delete class_loader_;
00100     }
00101 
00102     Settings discovery_settings(discovery_data);
00103     QString key = "qt_gui_cpp.RosPluginlibPluginProvider/" + export_tag_ + " " + base_class_type_;
00104     bool is_cached = discovery_settings.contains(key);
00105 
00106     std::vector<std::string> plugin_xml_paths;
00107     // reuse plugin paths from cache if available
00108     if (is_cached)
00109     {
00110       QStringList paths = discovery_settings.value(key).toStringList();
00111       for (QStringList::const_iterator it = paths.begin(); it != paths.end(); it++)
00112       {
00113         plugin_xml_paths.push_back(it->toStdString());
00114       }
00115     }
00116     else
00117     {
00118       qDebug("RosPluginlibPluginProvider::discover_descriptors() crawling for plugins of type '%s' and base class '%s'", export_tag_.toStdString().c_str(), base_class_type_.toStdString().c_str());
00119     }
00120     class_loader_ = new pluginlib::ClassLoader<T>(export_tag_.toStdString(), base_class_type_.toStdString(), std::string("plugin"), plugin_xml_paths);
00121 
00122     if (!is_cached)
00123     {
00124       // save discovered paths
00125       std::vector<std::string> paths = class_loader_->getPluginXmlPaths();
00126       QStringList qpaths;
00127       for (std::vector<std::string>::const_iterator it = paths.begin(); it != paths.end(); it++)
00128       {
00129         qpaths.push_back(it->c_str());
00130       }
00131       discovery_settings.setValue(key, qpaths);
00132     }
00133 
00134     QList<PluginDescriptor*> descriptors;
00135 
00136     std::vector<std::string> classes = class_loader_->getDeclaredClasses();
00137     for (std::vector<std::string>::iterator it = classes.begin(); it != classes.end(); it++)
00138     {
00139       std::string lookup_name = *it;
00140 
00141       std::string name = class_loader_->getName(lookup_name);
00142       std::string plugin_xml = class_loader_->getPluginManifestPath(lookup_name);
00143       boost::filesystem::path p(plugin_xml);
00144 #if BOOST_FILESYSTEM_VERSION >= 3
00145       std::string plugin_path = p.parent_path().string();
00146 #else
00147       std::string plugin_path = p.parent_path();
00148 #endif
00149 
00150       QMap<QString, QString> attributes;
00151       attributes["class_name"] = name.c_str();
00152       attributes["class_type"] = class_loader_->getClassType(lookup_name).c_str();
00153       attributes["class_base_class_type"] = class_loader_->getBaseClassType().c_str();
00154       attributes["package_name"] = class_loader_->getClassPackage(lookup_name).c_str();
00155       attributes["plugin_path"] = plugin_path.c_str();
00156 
00157       // check if plugin is available
00158       //std::string library_path = class_loader_->getClassLibraryPath(lookup_name);
00159       //attributes["not_available"] = !std::ifstream(library_path.c_str()) ? QString("library ").append(lookup_name.c_str()).append(" not found (may be it must be built?)") : "";
00160       attributes["not_available"] = "";
00161 
00162       PluginDescriptor* plugin_descriptor = new PluginDescriptor(lookup_name.c_str(), attributes);
00163       QString label = name.c_str();
00164       QString statustip = class_loader_->getClassDescription(lookup_name).c_str();
00165       QString icon;
00166       QString icontype;
00167       parseManifest(lookup_name, plugin_path, label, statustip, icon, icontype, plugin_descriptor);
00168       plugin_descriptor->setActionAttributes(label, statustip, icon, icontype);
00169 
00170       // add plugin descriptor
00171       descriptors.append(plugin_descriptor);
00172     }
00173     return descriptors;
00174   }
00175 
00176   virtual void* load(const QString& plugin_id, PluginContext* plugin_context)
00177   {
00178     return load_explicit_type(plugin_id, plugin_context);
00179   }
00180 
00181   virtual Plugin* load_plugin(const QString& plugin_id, PluginContext* plugin_context)
00182   {
00183     T* instance = load_explicit_type(plugin_id, plugin_context);
00184     if (instance == 0)
00185     {
00186       return 0;
00187     }
00188     Plugin* plugin = dynamic_cast<Plugin*>(instance);
00189     if (plugin == 0)
00190     {
00191       // TODO: garbage instance
00192       qWarning("RosPluginlibPluginProvider::load_plugin() called on non-plugin plugin provider");
00193       return 0;
00194     }
00195     return plugin;
00196   }
00197 
00198   virtual T* load_explicit_type(const QString& plugin_id, PluginContext* plugin_context)
00199   {
00200     std::string lookup_name = plugin_id.toStdString();
00201 
00202     if (!class_loader_->isClassAvailable(lookup_name))
00203     {
00204       qWarning("RosPluginlibPluginProvider::load_explicit_type(%s) class not available", lookup_name.c_str());
00205       return 0;
00206     }
00207 
00208     boost::shared_ptr<T> instance;
00209     try
00210     {
00211       instance = create_plugin(lookup_name, plugin_context);
00212     }
00213     catch (pluginlib::LibraryLoadException& e)
00214     {
00215       qWarning("RosPluginlibPluginProvider::load_explicit_type(%s) could not load library (%s)", lookup_name.c_str(), e.what());
00216       return 0;
00217     }
00218     catch (pluginlib::PluginlibException& e)
00219     {
00220       qWarning("RosPluginlibPluginProvider::load_explicit_type(%s) failed creating instance (%s)", lookup_name.c_str(), e.what());
00221       return 0;
00222     }
00223 
00224     if (!instance)
00225     {
00226       qWarning("RosPluginlibPluginProvider::load_explicit_type(%s) failed creating instance", lookup_name.c_str());
00227       return 0;
00228     }
00229 
00230     // pass context to plugin
00231     Plugin* plugin = dynamic_cast<Plugin*>(&*instance);
00232     if (plugin)
00233     {
00234       try
00235       {
00236         init_plugin(plugin_id, plugin_context, plugin);
00237       }
00238       catch (std::exception& e)
00239       {
00240         // TODO: garbage instance
00241         qWarning("RosPluginlibPluginProvider::load_explicit_type(%s) failed initializing plugin (%s)", lookup_name.c_str(), e.what());
00242         return 0;
00243       }
00244     }
00245 
00246     //qDebug("RosPluginlibPluginProvider::load_explicit_type(%s) succeeded", lookup_name.c_str());
00247     instances_[&*instance] = instance;
00248 
00249     return &*instance;
00250   }
00251 
00252   virtual void unload(void* instance)
00253   {
00254     if (!instances_.contains(instance))
00255     {
00256       qCritical("RosPluginlibPluginProvider::unload() instance not found");
00257       return;
00258     }
00259 
00260     boost::shared_ptr<T> pointer = instances_.take(instance);
00261     libraries_to_unload_.append(pointer);
00262 
00263     QCoreApplication::postEvent(this, new QEvent(static_cast<QEvent::Type>(unload_libraries_event_)));
00264   }
00265 
00266   bool event(QEvent* e)
00267   {
00268     if (e->type() == unload_libraries_event_)
00269     {
00270       libraries_to_unload_.clear();
00271       return true;
00272     }
00273     return QObject::event(e);
00274   }
00275 
00276 protected:
00277 
00278   virtual boost::shared_ptr<T> create_plugin(const std::string& lookup_name, PluginContext* /*plugin_context*/ = 0)
00279   {
00280     return class_loader_->createInstance(lookup_name);
00281   }
00282 
00283   virtual void init_plugin(const QString& /*plugin_id*/, PluginContext* plugin_context, Plugin* plugin)
00284   {
00285     plugin->initPlugin(*plugin_context);
00286   }
00287 
00288 private:
00289 
00290   bool parseManifest(const std::string& lookup_name, const std::string& plugin_path, QString& label, QString& statustip, QString& icon, QString& icontype, PluginDescriptor* plugin_descriptor)
00291   {
00292     //qDebug("RosPluginlibPluginProvider::parseManifest()");
00293 
00294     std::string manifest_path = class_loader_->getPluginManifestPath(lookup_name);
00295     //qDebug("RosPluginlibPluginProvider::parseManifest() manifest_path \"%s\"", manifest_path.c_str());
00296     TiXmlDocument doc;
00297     bool loaded = doc.LoadFile(manifest_path);
00298     if (!loaded)
00299     {
00300       if (doc.ErrorRow() > 0)
00301       {
00302         qWarning("RosPluginlibPluginProvider::parseManifest() could not load manifest \"%s\" (%s [line %d, column %d])", manifest_path.c_str(), doc.ErrorDesc(), doc.ErrorRow(), doc.ErrorCol());
00303       }
00304       else
00305       {
00306         qWarning("RosPluginlibPluginProvider::parseManifest() could not load manifest \"%s\" (%s)", manifest_path.c_str(), doc.ErrorDesc());
00307       }
00308       return false;
00309     }
00310 
00311     // search library-tag with specific path-attribute
00312     std::string class_type = class_loader_->getClassType(lookup_name);
00313     TiXmlElement* library_element = doc.FirstChildElement("library");
00314     while (library_element)
00315     {
00316         // search class-tag with specific type- and base_class_type-attribute
00317         TiXmlElement* class_element = library_element->FirstChildElement("class");
00318         while (class_element)
00319         {
00320           if (class_type.compare(class_element->Attribute("type")) == 0 && base_class_type_.compare(class_element->Attribute("base_class_type")) == 0)
00321           {
00322             TiXmlElement* qtgui_element = class_element->FirstChildElement("qtgui");
00323             if (qtgui_element)
00324             {
00325               // extract meta information
00326               parseActionAttributes(qtgui_element, plugin_path, label, statustip, icon, icontype);
00327 
00328               // extract grouping information
00329               TiXmlElement* group_element = qtgui_element->FirstChildElement("group");
00330               while (group_element)
00331               {
00332                 QString group_label;
00333                 QString group_statustip;
00334                 QString group_icon;
00335                 QString group_icontype;
00336                 parseActionAttributes(group_element, plugin_path, group_label, group_statustip, group_icon, group_icontype);
00337                 plugin_descriptor->addGroupAttributes(group_label, group_statustip, group_icon, group_icontype);
00338 
00339                 group_element = group_element->NextSiblingElement("group");
00340               }
00341             }
00342             return true;
00343           }
00344           class_element = class_element->NextSiblingElement("class");
00345         }
00346         break;
00347 
00348       library_element = library_element->NextSiblingElement("library");
00349     }
00350 
00351     qWarning("RosPluginlibPluginProvider::parseManifest() could not handle manifest \"%s\"", manifest_path.c_str());
00352     return false;
00353   }
00354 
00355   void parseActionAttributes(TiXmlElement* element, const std::string& plugin_path, QString& label, QString& statustip, QString& icon, QString& icontype)
00356   {
00357     TiXmlElement* child_element;
00358     if ((child_element = element->FirstChildElement("label")) != 0)
00359     {
00360       label = child_element->GetText();
00361     }
00362     if ((child_element = element->FirstChildElement("icon")) != 0)
00363     {
00364       icontype = child_element->Attribute("type");
00365       if (icontype == "file")
00366       {
00367         // prepend base path
00368         icon = plugin_path.c_str();
00369         icon += "/";
00370         icon += child_element->GetText();
00371       }
00372       else
00373       {
00374         icon = child_element->GetText();
00375       }
00376     }
00377     if ((child_element = element->FirstChildElement("statustip")) != 0)
00378     {
00379       statustip = child_element->GetText();
00380     }
00381   }
00382 
00383   void unload_pending_libraries()
00384   {
00385   }
00386 
00387   QString export_tag_;
00388 
00389   QString base_class_type_;
00390 
00391   int unload_libraries_event_;
00392 
00393   pluginlib::ClassLoader<T>* class_loader_;
00394 
00395   QMap<void*, boost::shared_ptr<T> > instances_;
00396 
00397   QList<boost::shared_ptr<T> > libraries_to_unload_;
00398 
00399 };
00400 
00401 } // namespace
00402 
00403 #endif // qt_gui_cpp__RosPluginlibPluginProvider_H


qt_gui_cpp
Author(s): Dirk Thomas
autogenerated on Mon Oct 6 2014 03:57:56