41 #include <boost/bind.hpp> 61 qDebug(
"NodeletPluginProvider::unload()");
64 qCritical(
"NodeletPluginProvider::unload() instance not found");
72 qCritical(
"NodeletPluginProvider::unload() '%s' failed", nodelet_name.toStdString().c_str());
117 std::string nodelet_name = lookup_name +
"_" + QString::number(plugin_context->
serialNumber()).toStdString();
119 qDebug(
"NodeletPluginProvider::create_plugin() load %s", lookup_name.c_str());
120 bool loaded =
loader_->
load(nodelet_name, lookup_name, remappings, my_argv);
123 qDebug(
"NodeletPluginProvider::create_plugin() loaded");
139 qDebug(
"NodeletPluginProvider::init_plugin()");
144 throw std::runtime_error(
"plugin is not a nodelet");
bool load(const std::string &name, const std::string &type, const M_string &remappings, const V_string &my_argv)
std::vector< std::string > listLoadedNodelets()
RosSpinThread(QObject *parent=0)
virtual boost::shared_ptr< T > create_plugin(const std::string &lookup_name, PluginContext *=0)
bool unload(const std::string &name)
virtual void init_plugin(const QString &, PluginContext *plugin_context, Plugin *plugin)
boost::shared_ptr< nodelet::Nodelet > create_instance(const std::string &lookup_name)
NodeletPluginProvider(const QString &export_tag, const QString &base_class_type)
ROSCPP_DECL CallbackQueue * getGlobalCallbackQueue()
QMap< void *, QString > instances_
boost::shared_ptr< rqt_gui_cpp::Plugin > instance_
virtual void unload(void *instance)
virtual boost::shared_ptr< Plugin > create_plugin(const std::string &lookup_name, qt_gui_cpp::PluginContext *plugin_context)
virtual ~NodeletPluginProvider()
RosSpinThread * ros_spin_thread_
nodelet::Loader * loader_
virtual void init_plugin(const QString &plugin_id, qt_gui_cpp::PluginContext *plugin_context, qt_gui_cpp::Plugin *plugin)
virtual void unload(void *instance)
std::vector< std::string > V_string
std::map< std::string, std::string > M_string