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 #include <pluginlib/boost_fs_wrapper.h>
00045 
00046 #include <QCoreApplication>
00047 #include <QEvent>
00048 #include <QList>
00049 #include <QMap>
00050 #include <QObject>
00051 #include <QString>
00052 
00053 #include <fstream>
00054 #include <string>
00055 #include <vector>
00056 
00057 namespace qt_gui_cpp
00058 {
00059 
00060 template<typename T>
00061 class RosPluginlibPluginProvider
00062   : public QObject
00063   , public PluginProvider
00064 {
00065 
00066 public:
00067 
00068   static RosPluginlibPluginProvider<T>* create_instance(const QString& export_tag, const QString& base_class_type)
00069   {
00070     return new RosPluginlibPluginProvider<T>(export_tag, base_class_type);
00071   }
00072 
00073   RosPluginlibPluginProvider(const QString& export_tag, const QString& base_class_type)
00074     : QObject()
00075     , PluginProvider()
00076     , export_tag_(export_tag)
00077     , base_class_type_(base_class_type)
00078     , class_loader_(0)
00079   {
00080     unload_libraries_event_ = QEvent::registerEventType();
00081   }
00082 
00083   virtual ~RosPluginlibPluginProvider()
00084   {
00085     if (class_loader_)
00086     {
00087       delete class_loader_;
00088     }
00089   }
00090 
00091   virtual QMap<QString, QString> discover()
00092   {
00093     return PluginProvider::discover();
00094   }
00095 
00096   virtual QList<PluginDescriptor*> discover_descriptors()
00097   {
00098     if (class_loader_)
00099     {
00100       delete class_loader_;
00101     }
00102     class_loader_ = new pluginlib::ClassLoader<T>(export_tag_.toStdString(), base_class_type_.toStdString());
00103 
00104     QList<PluginDescriptor*> descriptors;
00105 
00106     std::vector<std::string> classes = class_loader_->getDeclaredClasses();
00107     for (std::vector<std::string>::iterator it = classes.begin(); it != classes.end(); it++)
00108     {
00109       std::string lookup_name = *it;
00110 
00111       std::string name = class_loader_->getName(lookup_name);
00112       std::string type = class_loader_->getClassType(lookup_name);
00113       std::string base_class_type = class_loader_->getBaseClassType();
00114 
00115       QMap<QString, QString> attributes;
00116       attributes["class_name"] = name.c_str();
00117       attributes["class_type"] = type.c_str();
00118       attributes["class_base_class_type"] = base_class_type.c_str();
00119 
00120       // check if plugin is available
00121       std::string library_path = class_loader_->getClassLibraryPath(lookup_name);
00122       library_path.append(Poco::SharedLibrary::suffix());
00123       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?)") : "";
00124 
00125       PluginDescriptor* plugin_descriptor = new PluginDescriptor(lookup_name.c_str(), attributes);
00126       QString label = name.c_str();
00127       QString statustip = class_loader_->getClassDescription(lookup_name).c_str();
00128       QString icon;
00129       QString icontype;
00130       std::string package_path = ros::package::getPath(class_loader_->getClassPackage(lookup_name));
00131       size_t package_path_length = package_path.length();
00132       assert(library_path.compare(0, package_path_length, package_path) == 0);
00133       std::string relative_library_path = library_path.substr(package_path_length + 1);
00134       parseManifest(lookup_name, package_path, relative_library_path, label, statustip, icon, icontype, plugin_descriptor);
00135       plugin_descriptor->setActionAttributes(label, statustip, icon, icontype);
00136 
00137       // add plugin descriptor
00138       descriptors.append(plugin_descriptor);
00139     }
00140     return descriptors;
00141   }
00142 
00143   virtual void* load(const QString& plugin_id, PluginContext* plugin_context)
00144   {
00145     return load_explicit_type(plugin_id, plugin_context);
00146   }
00147 
00148   virtual Plugin* load_plugin(const QString& plugin_id, PluginContext* plugin_context)
00149   {
00150     T* instance = load_explicit_type(plugin_id, plugin_context);
00151     if (instance == 0)
00152     {
00153       return 0;
00154     }
00155     Plugin* plugin = dynamic_cast<Plugin*>(instance);
00156     if (plugin == 0)
00157     {
00158       // TODO: garbage instance
00159       qWarning("RosPluginlibPluginProvider::load_plugin() called on non-plugin plugin provider");
00160       return 0;
00161     }
00162     return plugin;
00163   }
00164 
00165   virtual T* load_explicit_type(const QString& plugin_id, PluginContext* plugin_context)
00166   {
00167     std::string lookup_name = plugin_id.toStdString();
00168 
00169     if (!class_loader_->isClassAvailable(lookup_name))
00170     {
00171       qWarning("RosPluginlibPluginProvider::load_explicit_type(%s) class not available", lookup_name.c_str());
00172       return 0;
00173     }
00174 
00175     boost::shared_ptr<T> instance;
00176     try
00177     {
00178       instance = create_plugin(lookup_name, plugin_context);
00179     }
00180     catch (pluginlib::LibraryLoadException& e)
00181     {
00182       qWarning("RosPluginlibPluginProvider::load_explicit_type(%s) could not load library (%s)", lookup_name.c_str(), e.what());
00183       return 0;
00184     }
00185     catch (pluginlib::PluginlibException& e)
00186     {
00187       qWarning("RosPluginlibPluginProvider::load_explicit_type(%s) failed creating instance (%s)", lookup_name.c_str(), e.what());
00188       return 0;
00189     }
00190 
00191     if (!instance)
00192     {
00193       qWarning("RosPluginlibPluginProvider::load_explicit_type(%s) failed creating instance", lookup_name.c_str());
00194       return 0;
00195     }
00196 
00197     // pass context to plugin
00198     Plugin* plugin = dynamic_cast<Plugin*>(&*instance);
00199     if (plugin)
00200     {
00201       try
00202       {
00203         init_plugin(plugin_id, plugin_context, plugin);
00204       }
00205       catch (std::exception& e)
00206       {
00207         // TODO: garbage instance
00208         qWarning("RosPluginlibPluginProvider::load_explicit_type(%s) failed initializing plugin (%s)", lookup_name.c_str(), e.what());
00209         return 0;
00210       }
00211     }
00212 
00213     //qDebug("RosPluginlibPluginProvider::load_explicit_type(%s) succeeded", lookup_name.c_str());
00214     instances_[&*instance] = instance;
00215 
00216     return &*instance;
00217   }
00218 
00219   virtual void unload(void* instance)
00220   {
00221     if (!instances_.contains(instance))
00222     {
00223       qCritical("RosPluginlibPluginProvider::unload() instance not found");
00224       return;
00225     }
00226 
00227     boost::shared_ptr<T> pointer = instances_.take(instance);
00228     libraries_to_unload_.append(pointer);
00229 
00230     QCoreApplication::postEvent(this, new QEvent(static_cast<QEvent::Type>(unload_libraries_event_)));
00231   }
00232 
00233 protected:
00234 
00235   virtual boost::shared_ptr<T> create_plugin(const std::string& lookup_name, PluginContext* /*plugin_context*/ = 0)
00236   {
00237     return class_loader_->createInstance(lookup_name);
00238   }
00239 
00240   virtual void init_plugin(const QString& /*plugin_id*/, PluginContext* plugin_context, Plugin* plugin)
00241   {
00242     plugin->initPlugin(*plugin_context);
00243   }
00244 
00245 private slots:
00246 
00247   bool event(QEvent* e)
00248   {
00249     if (e->type() == unload_libraries_event_)
00250     {
00251       libraries_to_unload_.clear();
00252       return true;
00253     }
00254     return QObject::event(e);
00255   }
00256 
00257 private:
00258 
00259   bool parseManifest(const std::string& lookup_name, const std::string& package_path, const std::string& /*relative_library_path*/, QString& label, QString& statustip, QString& icon, QString& icontype, PluginDescriptor* plugin_descriptor)
00260   {
00261     //qDebug("RosPluginlibPluginProvider::parseManifest() relative_library_path \"%s\"", relative_library_path.c_str());
00262 
00263     std::string manifest_path = class_loader_->getPluginManifestPath(lookup_name);
00264     //qDebug("RosPluginlibPluginProvider::parseManifest() manifest_path \"%s\"", manifest_path.c_str());
00265     TiXmlDocument doc;
00266     bool loaded = doc.LoadFile(manifest_path);
00267     if (!loaded)
00268     {
00269       if (doc.ErrorRow() > 0)
00270       {
00271         qWarning("RosPluginlibPluginProvider::parseManifest() could not load manifest \"%s\" (%s [line %d, column %d])", manifest_path.c_str(), doc.ErrorDesc(), doc.ErrorRow(), doc.ErrorCol());
00272       }
00273       else
00274       {
00275         qWarning("RosPluginlibPluginProvider::parseManifest() could not load manifest \"%s\" (%s)", manifest_path.c_str(), doc.ErrorDesc());
00276       }
00277       return false;
00278     }
00279 
00280     // search library-tag with specific path-attribute
00281     std::string class_type = class_loader_->getClassType(lookup_name);
00282     TiXmlElement* library_element = doc.FirstChildElement("library");
00283     while (library_element)
00284     {
00285 //      if (relative_library_path.compare(library_element->Attribute("path")) == 0)
00286 //      {
00287         // search class-tag with specific type- and base_class_type-attribute
00288         TiXmlElement* class_element = library_element->FirstChildElement("class");
00289         while (class_element)
00290         {
00291           if (class_type.compare(class_element->Attribute("type")) == 0 && base_class_type_.compare(class_element->Attribute("base_class_type")) == 0)
00292           {
00293             TiXmlElement* qtgui_element = class_element->FirstChildElement("qtgui");
00294             if (qtgui_element)
00295             {
00296               // extract meta information
00297               parseActionAttributes(qtgui_element, package_path, label, statustip, icon, icontype);
00298 
00299               // extract grouping information
00300               TiXmlElement* group_element = qtgui_element->FirstChildElement("group");
00301               while (group_element)
00302               {
00303                 QString group_label;
00304                 QString group_statustip;
00305                 QString group_icon;
00306                 QString group_icontype;
00307                 parseActionAttributes(group_element, package_path, group_label, group_statustip, group_icon, group_icontype);
00308                 plugin_descriptor->addGroupAttributes(group_label, group_statustip, group_icon, group_icontype);
00309 
00310                 group_element = group_element->NextSiblingElement("group");
00311               }
00312             }
00313             return true;
00314           }
00315           class_element = class_element->NextSiblingElement("class");
00316         }
00317         break;
00318 //      }
00319 
00320       library_element = library_element->NextSiblingElement("library");
00321     }
00322 
00323     qWarning("RosPluginlibPluginProvider::parseManifest() could not handle manifest \"%s\"", manifest_path.c_str());
00324     return false;
00325   }
00326 
00327   void parseActionAttributes(TiXmlElement* element, const std::string& package_path, QString& label, QString& statustip, QString& icon, QString& icontype)
00328   {
00329     TiXmlElement* child_element;
00330     if ((child_element = element->FirstChildElement("label")) != 0)
00331     {
00332       label = child_element->GetText();
00333     }
00334     if ((child_element = element->FirstChildElement("icon")) != 0)
00335     {
00336       icontype = child_element->Attribute("type");
00337       if (icontype == "file")
00338       {
00339         // prepend base path
00340         icon = pluginlib::joinPaths(package_path, child_element->GetText()).c_str();
00341       }
00342       else
00343       {
00344         icon = child_element->GetText();
00345       }
00346     }
00347     if ((child_element = element->FirstChildElement("statustip")) != 0)
00348     {
00349       statustip = child_element->GetText();
00350     }
00351   }
00352 
00353   void unload_pending_libraries()
00354   {
00355   }
00356 
00357   QString export_tag_;
00358 
00359   QString base_class_type_;
00360 
00361   int unload_libraries_event_;
00362 
00363   pluginlib::ClassLoader<T>* class_loader_;
00364 
00365   QMap<void*, boost::shared_ptr<T> > instances_;
00366 
00367   QList<boost::shared_ptr<T> > libraries_to_unload_;
00368 
00369 };
00370 
00371 } // namespace
00372 
00373 #endif // qt_gui_cpp__RosPluginlibPluginProvider_H


qt_gui_cpp
Author(s): Dirk Thomas
autogenerated on Fri Jan 3 2014 11:44:04