Public Member Functions | List of all members
gpp_plugin::ArrayPluginManager< _Plugin > Struct Template Reference

Loads an array of plugins. More...

#include <gpp_plugin.hpp>

Inheritance diagram for gpp_plugin::ArrayPluginManager< _Plugin >:
Inheritance graph
[legend]

Public Member Functions

void load (const std::string &_resource, ros::NodeHandle &_nh)
 
- Public Member Functions inherited from gpp_plugin::PluginManager< _Plugin >
virtual pluginlib::UniquePtr< _Plugin > createCustomInstance (const std::string &_type)
 
 PluginManager ()
 
- Public Member Functions inherited from pluginlib::ClassLoader< _Plugin >
 ClassLoader (std::string package, std::string base_class, std::string attrib_name=std::string("plugin"), std::vector< std::string > plugin_xml_paths=std::vector< std::string >())
 
T * createClassInstance (const std::string &lookup_name, bool auto_load=true)
 
boost::shared_ptr< T > createInstance (const std::string &lookup_name)
 
T * createUnmanagedInstance (const std::string &lookup_name)
 
virtual std::string getBaseClassType () const
 
virtual std::string getClassDescription (const std::string &lookup_name)
 
virtual std::string getClassLibraryPath (const std::string &lookup_name)
 
virtual std::string getClassPackage (const std::string &lookup_name)
 
virtual std::string getClassType (const std::string &lookup_name)
 
std::vector< std::string > getDeclaredClasses ()
 
virtual std::string getName (const std::string &lookup_name)
 
virtual std::string getPluginManifestPath (const std::string &lookup_name)
 
std::vector< std::string > getPluginXmlPaths ()
 
virtual std::vector< std::string > getRegisteredLibraries ()
 
virtual bool isClassAvailable (const std::string &lookup_name)
 
bool isClassLoaded (const std::string &lookup_name)
 
virtual void loadLibraryForClass (const std::string &lookup_name)
 
virtual void refreshDeclaredClasses ()
 
virtual int unloadLibraryForClass (const std::string &lookup_name)
 
 ~ClassLoader ()
 
- Public Member Functions inherited from pluginlib::ClassLoaderBase
virtual std::string getBaseClassType () const=0
 
virtual ~ClassLoaderBase ()
 
- Public Member Functions inherited from gpp_plugin::PluginGroup< _Plugin >
const bool & getDefaultValue () const noexcept
 
const std::string & getName () const noexcept
 
const PluginMapgetPlugins () const noexcept
 

Additional Inherited Members

- Public Types inherited from gpp_plugin::PluginManager< _Plugin >
using Base = pluginlib::ClassLoader< _Plugin >
 
using Definition = PluginDefinition< _Plugin >
 
- Public Types inherited from pluginlib::ClassLoader< _Plugin >
typedef std::map< std::string, ClassDesc >::iterator ClassMapIterator
 
- Public Types inherited from gpp_plugin::PluginGroup< _Plugin >
using NamedPlugin = std::pair< PluginParameter, PluginPtr >
 
using PluginMap = std::vector< NamedPlugin >
 
using PluginPtr = typename pluginlib::UniquePtr< _Plugin >
 
- Protected Attributes inherited from gpp_plugin::PluginGroup< _Plugin >
bool default_value_
 
std::string name_ = "undefined"
 
PluginMap plugins_
 

Detailed Description

template<typename _Plugin>
struct gpp_plugin::ArrayPluginManager< _Plugin >

Loads an array of plugins.

Usage

The class offers two methods:

Both methods are not thread-safe. The concurrency management must be done by the user.

Code example:

// you will need a note-handle
// create the manager
ArrayPluginManager<MyPlugin> manager;
// load the plugins
try{
// will throw if "my_resource_tag" does not specify an array
manager.load("my_resource_tag", nh);
}
catch(std::invalid_argument& ex){
std::cerr << "failed to load " << ex.what() << std::endl;
return;
}
// get the plugins and init them as you like
const auto& plugins = manager.getPlugins();
...

Parameters

The ros-parameter resource defined under the _resource argument (see load-method) must be an array. The array resquires two tags - 'name' and 'type'. 'name' defines a unique descriptor which will be passed to a plugin. 'type' defines the type of the plugin. Both tags must have literal values. Additionally it may contain boolean 'on_failure_break' (defaults to true) and 'on_success_break' (defaults to false) tags. See PluginParameter for details.

Code example:

my_resource_tag:
- {name: foo, type: a_valid_type}
- {name: baz, type: another_type, on_failure_break: false, on_success_break:
true}

Remarks

We don't need an explicit destructor here, since the destructors are called in reverse order of the construction: so the ManagerInterface is always destructed first.

https://stackoverflow.com/questions/31518581/order-of-destruction-in-the-case-of-multiple-inheritance

Template Parameters
_Pluginas in PluginManager<_Plugin>

Definition at line 297 of file gpp_plugin.hpp.

Member Function Documentation

◆ load()

template<typename _Plugin >
void gpp_plugin::ArrayPluginManager< _Plugin >::load ( const std::string &  _resource,
ros::NodeHandle _nh 
)

Definition at line 84 of file gpp_plugin.cpp.


The documentation for this struct was generated from the following files:
ros::NodeHandle


gpp_plugin
Author(s):
autogenerated on Wed Mar 2 2022 00:21:23