roscpp_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 "roscpp_plugin_provider.h"
00034 
00035 #include "nodelet_plugin_provider.h"
00036 #include <rqt_gui_cpp/plugin.h>
00037 
00038 #include <qt_gui_cpp/plugin_provider.h>
00039 
00040 #include <nodelet/nodelet.h>
00041 #include <pluginlib/class_list_macros.h>
00042 #include <ros/ros.h>
00043 
00044 #include <stdexcept>
00045 #include <sys/types.h>
00046 #include <unistd.h>
00047 #include <iostream>
00048 
00049 namespace rqt_gui_cpp {
00050 
00051 RosCppPluginProvider::RosCppPluginProvider()
00052   : qt_gui_cpp::CompositePluginProvider()
00053   , node_initialized_(false)
00054   , wait_for_master_dialog_(0)
00055   , wait_for_master_thread_(0)
00056 {
00057   QList<PluginProvider*> plugin_providers;
00058   plugin_providers.append(new NodeletPluginProvider("rqt_gui", "rqt_gui_cpp::Plugin"));
00059   set_plugin_providers(plugin_providers);
00060 }
00061 
00062 RosCppPluginProvider::~RosCppPluginProvider()
00063 {
00064   if (ros::isStarted())
00065   {
00066     ros::shutdown();
00067   }
00068 }
00069 
00070 void* RosCppPluginProvider::load(const QString& plugin_id, qt_gui_cpp::PluginContext* plugin_context)
00071 {
00072   init_node();
00073   return qt_gui_cpp::CompositePluginProvider::load(plugin_id, plugin_context);
00074 }
00075 
00076 qt_gui_cpp::Plugin* RosCppPluginProvider::load_plugin(const QString& plugin_id, qt_gui_cpp::PluginContext* plugin_context)
00077 {
00078   init_node();
00079   return qt_gui_cpp::CompositePluginProvider::load_plugin(plugin_id, plugin_context);
00080 }
00081 
00082 void RosCppPluginProvider::wait_for_master()
00083 {
00084   // check if master is available
00085   if (ros::master::check())
00086   {
00087     return;
00088   }
00089   // spawn thread to detect when master becomes available
00090   wait_for_master_dialog_ = new QMessageBox(QMessageBox::Question, QObject::tr("Waiting for ROS master"), QObject::tr("Could not find ROS master. Either start a 'roscore' or abort loading the plugin."), QMessageBox::Abort);
00091   wait_for_master_thread_ = new WaitForMasterThread(wait_for_master_dialog_);
00092   wait_for_master_thread_->start();
00093   QObject::connect(wait_for_master_thread_, SIGNAL(master_found_signal(int)), wait_for_master_dialog_, SLOT(done(int)), Qt::QueuedConnection);
00094   int button = wait_for_master_dialog_->exec();
00095   // check if master existence was not detected by background thread
00096   bool no_master = (button != QMessageBox::Ok);
00097   if (no_master)
00098   {
00099     dynamic_cast<WaitForMasterThread*>(wait_for_master_thread_)->abort = true;
00100     wait_for_master_thread_->wait();
00101   }
00102   wait_for_master_thread_->exit();
00103   wait_for_master_thread_->deleteLater();
00104   wait_for_master_dialog_->deleteLater();
00105   wait_for_master_dialog_ = 0;
00106   if (no_master)
00107   {
00108     throw std::runtime_error("RosCppPluginProvider::init_node() could not find ROS master");
00109   }
00110 }
00111 
00112 void RosCppPluginProvider::init_node()
00113 {
00114   // initialize ROS node once
00115   if (!node_initialized_)
00116   {
00117     int argc = 0;
00118     char** argv = 0;
00119     std::stringstream name;
00120     name << "rqt_gui_cpp_node_";
00121     name << getpid();
00122     qDebug("RosCppPluginProvider::init_node() initialize ROS node '%s'", name.str().c_str());
00123     ros::init(argc, argv, name.str().c_str(), ros::init_options::NoSigintHandler);
00124     wait_for_master();
00125     ros::start();
00126     node_initialized_ = true;
00127   }
00128   else
00129   {
00130     wait_for_master();
00131   }
00132 }
00133 
00134 WaitForMasterThread::WaitForMasterThread(QObject* parent)
00135   : QThread(parent)
00136   , abort(false)
00137 {}
00138 
00139 void WaitForMasterThread::run()
00140 {
00141   while (true)
00142   {
00143     usleep(100000);
00144     if (abort)
00145     {
00146       break;
00147     }
00148     if (ros::master::check())
00149     {
00150       emit(master_found_signal(QMessageBox::Ok));
00151       break;
00152     }
00153   }
00154 }
00155 
00156 }
00157 
00158 PLUGINLIB_EXPORT_CLASS(rqt_gui_cpp::RosCppPluginProvider, qt_gui_cpp::PluginProvider)


rqt_gui_cpp
Author(s): Dirk Thomas
autogenerated on Mon Oct 6 2014 07:13:24