nodelet_plugin_provider.cpp
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 #include "nodelet_plugin_provider.h"
00034 
00035 #include "roscpp_plugin_provider.h"
00036 
00037 #include <ros/callback_queue.h>
00038 #include <ros/ros.h>
00039 
00040 #include <stdexcept>
00041 #include <boost/bind.hpp>
00042 
00043 namespace rqt_gui_cpp {
00044 
00045 NodeletPluginProvider::NodeletPluginProvider(const QString& export_tag, const QString& base_class_type)
00046   : qt_gui_cpp::RosPluginlibPluginProvider<rqt_gui_cpp::Plugin>(export_tag, base_class_type)
00047   , loader_(0)
00048   , ros_spin_thread_(0)
00049 {}
00050 
00051 NodeletPluginProvider::~NodeletPluginProvider()
00052 {
00053   if (loader_)
00054   {
00055     delete loader_;
00056   }
00057 }
00058 
00059 void NodeletPluginProvider::unload(void* instance)
00060 {
00061   qDebug("NodeletPluginProvider::unload()");
00062   if (!instances_.contains(instance))
00063   {
00064     qCritical("NodeletPluginProvider::unload() instance not found");
00065     return;
00066   }
00067 
00068   QString nodelet_name = instances_[instance];
00069   bool unloaded = loader_->unload(nodelet_name.toStdString());
00070   if (!unloaded)
00071   {
00072     qCritical("NodeletPluginProvider::unload() '%s' failed", nodelet_name.toStdString().c_str());
00073   }
00074 
00075   // stop and garbage ros spin thread if not needed anymore
00076   if (loader_->listLoadedNodelets().empty())
00077   {
00078     shutdown();
00079   }
00080 
00081   qt_gui_cpp::RosPluginlibPluginProvider<rqt_gui_cpp::Plugin>::unload(instance);
00082 }
00083 
00084 void NodeletPluginProvider::shutdown()
00085 {
00086   if (ros_spin_thread_ != 0)
00087   {
00088     ros_spin_thread_->abort = true;
00089     ros_spin_thread_->wait();
00090     ros_spin_thread_->deleteLater();
00091     ros_spin_thread_ = 0;
00092   }
00093 }
00094 
00095 void NodeletPluginProvider::init_loader()
00096 {
00097   // initialize nodelet Loader once
00098   if (loader_ == 0)
00099   {
00100     loader_ = new nodelet::Loader(boost::bind(&NodeletPluginProvider::create_instance, this, _1));
00101   }
00102 
00103   // spawn ros spin thread
00104   if (ros_spin_thread_ == 0)
00105   {
00106     ros_spin_thread_ = new RosSpinThread(this);
00107     ros_spin_thread_->start();
00108   }
00109 }
00110 
00111 boost::shared_ptr<Plugin> NodeletPluginProvider::create_plugin(const std::string& lookup_name, qt_gui_cpp::PluginContext* plugin_context)
00112 {
00113   init_loader();
00114 
00115   nodelet::M_string remappings;
00116   nodelet::V_string my_argv;
00117   std::string nodelet_name = lookup_name + "_" + QString::number(plugin_context->serialNumber()).toStdString();
00118   instance_.reset();
00119   qDebug("NodeletPluginProvider::create_plugin() load %s", lookup_name.c_str());
00120   bool loaded = loader_->load(nodelet_name, lookup_name, remappings, my_argv);
00121   if (loaded)
00122   {
00123     qDebug("NodeletPluginProvider::create_plugin() loaded");
00124     instances_[&*instance_] = nodelet_name.c_str();
00125   }
00126   boost::shared_ptr<rqt_gui_cpp::Plugin> instance = instance_;
00127   instance_.reset();
00128   return instance;
00129 }
00130 
00131 boost::shared_ptr<nodelet::Nodelet> NodeletPluginProvider::create_instance(const std::string& lookup_name)
00132 {
00133   instance_ = qt_gui_cpp::RosPluginlibPluginProvider<rqt_gui_cpp::Plugin>::create_plugin(lookup_name);
00134   return instance_;
00135 }
00136 
00137 void NodeletPluginProvider::init_plugin(const QString& plugin_id, qt_gui_cpp::PluginContext* plugin_context, qt_gui_cpp::Plugin* plugin)
00138 {
00139   qDebug("NodeletPluginProvider::init_plugin()");
00140 
00141   rqt_gui_cpp::Plugin* nodelet = dynamic_cast<rqt_gui_cpp::Plugin*>(plugin);
00142   if (!nodelet)
00143   {
00144     throw std::runtime_error("plugin is not a nodelet");
00145   }
00146 
00147   qt_gui_cpp::RosPluginlibPluginProvider<rqt_gui_cpp::Plugin>::init_plugin(plugin_id, plugin_context, plugin);
00148 }
00149 
00150 NodeletPluginProvider::RosSpinThread::RosSpinThread(QObject* parent)
00151   : QThread(parent)
00152   , abort(false)
00153 {}
00154 
00155 NodeletPluginProvider::RosSpinThread::~RosSpinThread()
00156 {}
00157 
00158 void NodeletPluginProvider::RosSpinThread::run()
00159 {
00160   while (!abort)
00161   {
00162     ros::getGlobalCallbackQueue()->callOne(ros::WallDuration(0.1));
00163   }
00164 }
00165 
00166 }


rqt_gui_cpp
Author(s): Dirk Thomas
autogenerated on Sat Jun 8 2019 20:23:30