Noether  0.0.0
Loading...
Searching...
No Matches
Plugins

Detailed Description

Noether provides a plugin interface (noether::Plugin) for users to provide custom implementations of the tool path planning and GUI interfaces.

To create a plugin, users need to do the following:

Plugin Interface

noether::Plugin is the plugin class that gets loaded at run-time and is responsible for generating instances of a specific tool path planning component. This class needs to be overridden and its create method implemented for each custom tool path planning component. In this interface, the user is given configuration data (in the form of a YAML::Node) and an instance of the noether::Factory (e.g., for loading nested plugins). The user is expected to use this information to produce a configured instance of their custom tool path planning component.

Simplified Plugin Definition and Export

The example below shows the definition and export of a plugin for noether::BoundaryEdgePlanner. This particular tool path planner can be fully configured using just the YAML::Node input, so we can create and export a plugin for it using the simplified EXPORT_SIMPLE_<COMPONENT>_PLUGIN macro. This macro takes as input the name of the tool path planning component class and an arbitrary alias by which we wish to refer to it (e.g., for loading from YAML files, etc.). Under the hood, this macro defines a plugin class using noether::SimplePlugin and exports it using the EXPORT_<COMPONENT>_PLUGIN macro.

// Include the plugin interface headers
#include <noether_tpp/plugin_interface.h>
#include <noether_tpp/serialization.h>
// Include the header for the custom tool path planning component
#include <noether_tpp/tool_path_planners/edge/boundary_edge_planner.h>
namespace noether
{
// For tool path planning components that can be fully configured by YAML serialization, invoke the
// `EXPORT_SIMPLE_<COMPONENT>_PLUGIN` macro. This macro instantiates the PluginImpl template for the input class name
// (first argument) and exports that plugin with the input arbitrary alias (second argument).
EXPORT_SIMPLE_TOOL_PATH_PLANNER_PLUGIN(BoundaryEdgePlanner, Boundary);
} // namespace noether
#define EXPORT_SIMPLE_TOOL_PATH_PLANNER_PLUGIN(ComponentT, Alias)
Macro for defining and exporting a simple tool path planner plugin using the noether::SimplePlugin cl...
Definition plugin_interface.h:190
[Plugins Example Simple]
Definition plugin_interface.h:20

The following macros can be used to define and export simple plugins for tool path planning components:

Full Plugin Definition and Export

The example below shows the definition and export of noether::CompoundModifier, a tool path modifier which requires more information than just the YAML::Node to be configured. In this case, we must fully define the plugin class and export it with the appropriate EXPORT_<COMPONENT>_PLUGIN macro:

// Include the plugin interface headers
#include <noether_tpp/plugin_interface.h>
#include <noether_tpp/serialization.h>
// Include the header for the custom tool path planning component
namespace noether
{
// For a complex plugin that cannot be configured through YAML serialization alone, implement a custom plugin class.
struct Plugin_CompoundToolPathModifier : public Plugin<ToolPathModifier>
{
std::unique_ptr<ToolPathModifier> create(const YAML::Node& config,
std::shared_ptr<const Factory> factory) const override final
{
std::vector<ToolPathModifier::ConstPtr> modifiers;
modifiers.reserve(config.size());
auto modifiers_config = YAML::getMember<YAML::Node>(config, "modifiers");
for (const YAML::Node& entry : modifiers_config)
{
auto entry_name = YAML::getMember<std::string>(entry, "name");
modifiers.push_back(factory->createToolPathModifier(entry));
}
return std::make_unique<CompoundModifier>(std::move(modifiers));
}
};
// Export the plugin class with an arbitrary alias using the `EXPORT_<COMPONENT>_PLUGIN` macro
EXPORT_TOOL_PATH_MODIFIER_PLUGIN(Plugin_CompoundToolPathModifier, CompoundToolPathModifier);
} // namespace noether
#define EXPORT_TOOL_PATH_MODIFIER_PLUGIN(DERIVED_CLASS, ALIAS)
Macro for exporting instances of ToolPathModifierPlugin.
Definition plugin_interface.h:175

The following macros can be used to export tool path planning component plugins:

Plugin Factory

The noether::Factory class is intended to be used to load plugins for tool path planning components. This class wraps the underlying plugin loader class and ensures that loaded plugin libraries stay in scope as long as the plugins (and objects create from them) are used. By default, noether::Factory is configured to know about plugin libraries from this repository, to look for plugin library names in the NOETHER_PLUGIN_LIBS environment variable, and to look for install paths of plugin libraries in the NOETHER_PLUGIN_PATHS envrionment variable.

Note
If the install path of the plugin library can be found in LD_LIBRARY_PATH, there is no need to set the NOETHER_PLUGIN_PATHS environment variable. For example, if this project is built in a ROS/ROS2 workspace, sourcing the workspace automatically adds its library paths to LD_LIBRARY_PATH.

Typedefs

using noether::ToolPathPlannerPlugin = Plugin< ToolPathPlanner >
 Plugin interface for creating a ToolPathPlanner.
 
using noether::DirectionGeneratorPlugin = Plugin< DirectionGenerator >
 Plugin interface for creating a DirectionGenerator.
 
using noether::OriginGeneratorPlugin = Plugin< OriginGenerator >
 Plugin interface for creating an OriginGenerator.
 
using noether::ToolPathModifierPlugin = Plugin< ToolPathModifier >
 Plugin interface for creating a ToolPathModifier.
 
using noether::MeshModifierPlugin = Plugin< MeshModifier >
 Plugin interface for creating a MeshModifier.
 

Classes

class  noether::Plugin< T >
 Base class for a plugin that can generate a tool path planning component (e.g., mesh modifier, tool path planner, tool path modifier). More...
 
struct  noether::SimplePlugin< DerivedT, BaseT >
 Template for a simple implementation of Plugin. More...
 
class  noether::Factory
 Factory for creating tool path planning components from plugins. More...
 

Macros

#define EXPORT_MESH_MODIFIER_PLUGIN(DERIVED_CLASS, ALIAS)    EXPORT_CLASS_SECTIONED(DERIVED_CLASS, ALIAS, NOETHER_MESH_MODIFIER_SECTION)
 Macro for exporting instances of MeshModifierPlugin.
 
#define EXPORT_TOOL_PATH_PLANNER_PLUGIN(DERIVED_CLASS, ALIAS)    EXPORT_CLASS_SECTIONED(DERIVED_CLASS, ALIAS, NOETHER_TPP_SECTION)
 Macro for exporting instances of ToolPathPlannerPlugin.
 
#define EXPORT_DIRECTION_GENERATOR_PLUGIN(DERIVED_CLASS, ALIAS)    EXPORT_CLASS_SECTIONED(DERIVED_CLASS, ALIAS, NOETHER_DIRECTION_GENERATOR_SECTION)
 Macro for exporting instances of DirectionGeneratorPlugin.
 
#define EXPORT_ORIGIN_GENERATOR_PLUGIN(DERIVED_CLASS, ALIAS)    EXPORT_CLASS_SECTIONED(DERIVED_CLASS, ALIAS, NOETHER_ORIGIN_GENERATOR_SECTION)
 Macro for exporting instances of OriginGeneratorPlugin.
 
#define EXPORT_TOOL_PATH_MODIFIER_PLUGIN(DERIVED_CLASS, ALIAS)    EXPORT_CLASS_SECTIONED(DERIVED_CLASS, ALIAS, NOETHER_TOOL_PATH_MODIFIER_SECTION)
 Macro for exporting instances of ToolPathModifierPlugin.
 
#define EXPORT_SIMPLE_MESH_MODIFIER_PLUGIN(ComponentT, Alias)
 Macro for defining and exporting a simple mesh modifier plugin using the noether::SimplePlugin class.
 
#define EXPORT_SIMPLE_TOOL_PATH_PLANNER_PLUGIN(ComponentT, Alias)
 Macro for defining and exporting a simple tool path planner plugin using the noether::SimplePlugin class.
 
#define EXPORT_SIMPLE_DIRECTION_GENERATOR_PLUGIN(ComponentT, Alias)
 Macro for defining and exporting a simple direction generator plugin using the noether::SimplePlugin class.
 
#define EXPORT_SIMPLE_ORIGIN_GENERATOR_PLUGIN(ComponentT, Alias)
 Macro for defining and exporting a simple origin generator plugin using the noether::SimplePlugin class.
 
#define EXPORT_SIMPLE_TOOL_PATH_MODIFIER_PLUGIN(ComponentT, Alias)
 Macro for defining and exporting a simple tool path modifier plugin using the noether::SimplePlugin class.
 

Macro Definition Documentation

◆ EXPORT_SIMPLE_MESH_MODIFIER_PLUGIN

#define EXPORT_SIMPLE_MESH_MODIFIER_PLUGIN (   ComponentT,
  Alias 
)
Value:
using Plugin_##ComponentT = SimplePlugin<ComponentT, MeshModifier>; \
EXPORT_MESH_MODIFIER_PLUGIN(Plugin_##ComponentT, Alias)

◆ EXPORT_SIMPLE_TOOL_PATH_PLANNER_PLUGIN

#define EXPORT_SIMPLE_TOOL_PATH_PLANNER_PLUGIN (   ComponentT,
  Alias 
)
Value:
using Plugin_##ComponentT = SimplePlugin<ComponentT, ToolPathPlanner>; \
EXPORT_TOOL_PATH_PLANNER_PLUGIN(Plugin_##ComponentT, Alias)

◆ EXPORT_SIMPLE_DIRECTION_GENERATOR_PLUGIN

#define EXPORT_SIMPLE_DIRECTION_GENERATOR_PLUGIN (   ComponentT,
  Alias 
)
Value:
using Plugin_##ComponentT = SimplePlugin<ComponentT, DirectionGenerator>; \
EXPORT_DIRECTION_GENERATOR_PLUGIN(Plugin_##ComponentT, Alias)

◆ EXPORT_SIMPLE_ORIGIN_GENERATOR_PLUGIN

#define EXPORT_SIMPLE_ORIGIN_GENERATOR_PLUGIN (   ComponentT,
  Alias 
)
Value:
using Plugin_##ComponentT = SimplePlugin<ComponentT, OriginGenerator>; \
EXPORT_ORIGIN_GENERATOR_PLUGIN(Plugin_##ComponentT, Alias)

◆ EXPORT_SIMPLE_TOOL_PATH_MODIFIER_PLUGIN

#define EXPORT_SIMPLE_TOOL_PATH_MODIFIER_PLUGIN (   ComponentT,
  Alias 
)
Value:
using Plugin_##ComponentT = SimplePlugin<ComponentT, ToolPathModifier>; \
EXPORT_TOOL_PATH_MODIFIER_PLUGIN(Plugin_##ComponentT, Alias)