Noether  0.0.0
Loading...
Searching...
No Matches
GUI Interfaces

Detailed Description

The GUI module is a Qt-based framework that allows customizable UI widgets to configure a tool path planning pipeline. At run-time, the GUI searches for plugins that provide these widgets, uses the plugins to populate the GUI, and then allows the end user to interactively create custom tool path plans. This plugin-based GUI architecture allows end-users to leverage the out-of-the-box GUI infrastructure and plugins, while still enabling private development of custom capabilities or customizations to the front-end of existing classes.

To add a custom UI element to the GUI, users need to do the following:

Widgets

At the lowest level, the widgets in the GUI are used to produce the YAML configuration needed to load tool path planning components via plugin (see Plugins for more details about the tool path planning component plugins). noether::BaseWidget is the base class for these customizable widgets used in the GUI.

Each implementation of a tool path planning component (e.g., mesh modifier, tool path planner, tool path modifier) must provide a widget that inherits noether::BaseWidget and is capable of configuring it. The widget should override the save method which translates the GUI elements (e.g., spin boxes, etc.) into the YAML configuration for the tool path planning component plugin. The widget should also override the configure method which sets the value of the GUI elements given the YAML configuration for the tool path planning component.

Widget Plugins

To allow users to develop their own private implementations of tool path planning components and have them appear in the GUI, all widgets are loaded into the GUI application at runtime via plugin. This plugin class is defined in the noether::WidgetPlugin class.

The GUI itself finds available widget plugins (via the NOETHER_PLUGIN_LIBS environment variable), loads them, and uses them to produce widgets to populate the various pages of the GUI. Just as each of the tool path planning component has a corresponding noether::BaseWidget to configure it, each noether::BaseWidget should also have a corresponding noether::WidgetPlugin that produces the noether::BaseWidget to allow it to be loaded into the GUI.

Simplified Widget Plugin Definition and Export

The example below shows the definition and export of a widget plugin for noether::BoundaryEdgePlannerWidget. This particular tool path planner widget 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>_WIDGET_PLUGIN macro. This macro takes as input the name of the tool path planning component widget 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::SimpleWidgetPlugin and exports it using the EXPORT_<COMPONENT>_WIDGET_PLUGIN macro.

// Include the plugin interface header
#include <noether_gui/plugin_interface.h>
// Include the widget header
#include <noether_gui/widgets/tool_path_planners/edge/boundary_edge_planner_widget.h>
namespace noether
{
// For tool path planning component widgets that can be fully configured by YAML serialization, invoke the
// `EXPORT_SIMPLE_<COMPONENT>_WIDGET_PLUGIN` macro. This macro instantiates the SimpleWidgetPlugin template for the
// input class name (first argument) and exports that plugin with the input alias (second argument).
// Ideally, the alias matches the alias of the corresponding tool path planning component plugin.
EXPORT_SIMPLE_TOOL_PATH_PLANNER_WIDGET_PLUGIN(BoundaryEdgePlannerWidget, Boundary)
} // namespace noether
#define EXPORT_SIMPLE_TOOL_PATH_PLANNER_WIDGET_PLUGIN(WidgetT, Alias)
Macro for defining and exporting a simple tool path planner widget plugin using the noether::SimpleWi...
Definition plugin_interface.h:209
[GUI Plugins Example Simple]
Definition plugin_interface.h:11

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

Full Widget Plugin Definition and Export

The example below shows the definition and export of noether::PlaneSlicerRasterPlannerWidget, a tool path planner widget 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>_WIDGET_PLUGIN macro:

// Include the plugin interface header
#include <noether_gui/plugin_interface.h>
// Include the widget header
#include <noether_gui/widgets/tool_path_planners/raster/plane_slicer_raster_planner_widget.h>
namespace noether
{
// For a complex plugin that cannot be configured through YAML serialization alone, implement a custom plugin class.
struct Plugin_PlaneSlicerRasterPlannerWidget : WidgetPlugin
{
BaseWidget* create(const YAML::Node& config,
std::shared_ptr<const WidgetFactory> factory,
QWidget* parent = nullptr) const override final
{
auto widget = new PlaneSlicerRasterPlannerWidget(factory, parent);
// Attempt to configure the widget
if (!config.IsNull())
widget->configure(config);
return widget;
}
};
// Export the plugin class with an alias using the `EXPORT_<COMPONENT>_WIDGET_PLUGIN` macro
// Ideally, the alias matches the alias of the corresponding tool path planning component plugin
EXPORT_TOOL_PATH_PLANNER_WIDGET_PLUGIN(Plugin_PlaneSlicerRasterPlannerWidget, PlaneSlicer)
} // namespace noether
#define EXPORT_TOOL_PATH_PLANNER_WIDGET_PLUGIN(DERIVED_CLASS, ALIAS)
Macro for exporting instances of tool path planner plugins.
Definition plugin_interface.h:171

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

Shared YAML Configuration File

The same YAML configuration file can and should be used to load both tool path planning component plugins and GUI widget plugins. In order to accomplish this, the alias of the widget plugin should be the same as the alias for the tool path planning component plugin that it configures.

For example, the noether::PlaneProjectionMeshModifier and the noether::PlaneProjectionMeshModifierWidget plugin classes are exported with the same alias: PlaneProjection.

EXPORT_SIMPLE_MESH_MODIFIER_PLUGIN(PlaneProjectionMeshModifier, PlaneProjection)
#define EXPORT_SIMPLE_MESH_MODIFIER_PLUGIN(ComponentT, Alias)
Macro for defining and exporting a simple mesh modifier plugin using the noether::SimplePlugin class.
Definition plugin_interface.h:182
EXPORT_SIMPLE_MESH_MODIFIER_WIDGET_PLUGIN(PlaneProjectionMeshModifierWidget, PlaneProjection)
#define EXPORT_SIMPLE_MESH_MODIFIER_WIDGET_PLUGIN(WidgetT, Alias)
Macro for defining and exporting a simple mesh modifier widget plugin using the noether::SimpleWidget...
Definition plugin_interface.h:200

However, in some cases there is not a direct correspondence between a widget and the tool path planning component(s) it configures. For cases like this, the plugins can have different aliases, and a separate entry in the YAML configuration (gui_plugin_name) is used to specify the GUI plugin name.

For example, noether::CrossHatchPlaneSlicerRasterPlannerWidget is a widget that configures a noether::MultiToolPathPlanner in a specific way to produce a cross-hatch tool path planner. In this case, the plugin for noether::CrossHatchPlaneSlicerRasterPlannerWidget has the alias CrossHatchPlaneSlicer, and the plugin for noether::MultiToolPathPlanner has the alias Multi. The corresponding YAML configuration for this cross-hatch tool path planner is shown below:

tool_path_planner:
name: Multi # Name of the tool path planning component plugin
gui_plugin_name: CrossHatchPlaneSlicer # Name of the widget plugin
planners: # Remainder of the configuration
- ...
- ...

Widget Plugin Factory

The noether::WidgetFactory class is intended to be used to load plugins for tool path planning component widgets. 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::WidgetFactory is configured to know about widget 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.

Architecture

The image below shows the architecture of the GUI components described in the previous sections.

Classes

class  noether::WidgetPlugin
 Base class for a plugin that can generate a BaseWidget<T> for configuring a tool path planning component (e.g., mesh modifier, tool path planner, tool path modifier). More...
 
class  noether::MeshModifierWidgetPlugin
 WidgetPlugin implementation specifically for BaseWidget instances that configure mesh modifiers. More...
 
class  noether::ToolPathPlannerWidgetPlugin
 WidgetPlugin implementation specifically for BaseWidget instances that configure tool path planners. More...
 
class  noether::DirectionGeneratorWidgetPlugin
 WidgetPlugin implementation specifically for BaseWidget instances that configure direction generators. More...
 
class  noether::OriginGeneratorWidgetPlugin
 WidgetPlugin implementation specifically for BaseWidget instances that configure origin generators. More...
 
class  noether::ToolPathModifierWidgetPlugin
 WidgetPlugin implementation specifically for BaseWidget instances that configure tool path modifiers. More...
 
struct  noether::SimpleWidgetPlugin< WidgetT, WidgetPluginT >
 Template for a simple implementation of WidgetPlugin. More...
 
class  noether::WidgetFactory
 Extends the Factory class to be able to load widget plugins for the GUI. More...
 

Macros

#define EXPORT_MESH_MODIFIER_WIDGET_PLUGIN(DERIVED_CLASS, ALIAS)    EXPORT_CLASS_SECTIONED(DERIVED_CLASS, ALIAS, NOETHER_GUI_MESH_MODIFIER_SECTION)
 Macro for exporting instances of mesh modifier plugins.
 
#define EXPORT_TOOL_PATH_PLANNER_WIDGET_PLUGIN(DERIVED_CLASS, ALIAS)    EXPORT_CLASS_SECTIONED(DERIVED_CLASS, ALIAS, NOETHER_GUI_TPP_SECTION)
 Macro for exporting instances of tool path planner plugins.
 
#define EXPORT_DIRECTION_GENERATOR_WIDGET_PLUGIN(DERIVED_CLASS, ALIAS)    EXPORT_CLASS_SECTIONED(DERIVED_CLASS, ALIAS, NOETHER_GUI_DIRECTION_GENERATOR_SECTION)
 Macro for exporting instances of direction generator plugins.
 
#define EXPORT_ORIGIN_GENERATOR_WIDGET_PLUGIN(DERIVED_CLASS, ALIAS)    EXPORT_CLASS_SECTIONED(DERIVED_CLASS, ALIAS, NOETHER_GUI_ORIGIN_GENERATOR_SECTION)
 Macro for exporting instances of origni generator plugins.
 
#define EXPORT_TOOL_PATH_MODIFIER_WIDGET_PLUGIN(DERIVED_CLASS, ALIAS)    EXPORT_CLASS_SECTIONED(DERIVED_CLASS, ALIAS, NOETHER_GUI_TOOL_PATH_MODIFIER_SECTION)
 Macro for exporting instances of tool path modifier plugins.
 
#define EXPORT_SIMPLE_MESH_MODIFIER_WIDGET_PLUGIN(WidgetT, Alias)
 Macro for defining and exporting a simple mesh modifier widget plugin using the noether::SimpleWidgetPlugin class.
 
#define EXPORT_SIMPLE_TOOL_PATH_PLANNER_WIDGET_PLUGIN(WidgetT, Alias)
 Macro for defining and exporting a simple tool path planner widget plugin using the noether::SimpleWidgetPlugin class.
 
#define EXPORT_SIMPLE_DIRECTION_GENERATOR_WIDGET_PLUGIN(WidgetT, Alias)
 Macro for defining and exporting a simple direction generator widget plugin using the noether::SimpleWidgetPlugin class.
 
#define EXPORT_SIMPLE_ORIGIN_GENERATOR_WIDGET_PLUGIN(WidgetT, Alias)
 Macro for defining and exporting a simple origin generator widget plugin using the noether::SimpleWidgetPlugin class.
 
#define EXPORT_SIMPLE_TOOL_PATH_MODIFIER_WIDGET_PLUGIN(WidgetT, Alias)
 Macro for defining and exporting a simple tool path modifier widget plugin using the noether::SimpleWidgetPlugin class.
 

Macro Definition Documentation

◆ EXPORT_SIMPLE_MESH_MODIFIER_WIDGET_PLUGIN

#define EXPORT_SIMPLE_MESH_MODIFIER_WIDGET_PLUGIN (   WidgetT,
  Alias 
)
Value:
using Plugin_##WidgetT = SimpleWidgetPlugin<WidgetT, MeshModifierWidgetPlugin>; \
EXPORT_MESH_MODIFIER_WIDGET_PLUGIN(Plugin_##WidgetT, Alias)

◆ EXPORT_SIMPLE_TOOL_PATH_PLANNER_WIDGET_PLUGIN

#define EXPORT_SIMPLE_TOOL_PATH_PLANNER_WIDGET_PLUGIN (   WidgetT,
  Alias 
)
Value:
using Plugin_##WidgetT = SimpleWidgetPlugin<WidgetT, ToolPathPlannerWidgetPlugin>; \
EXPORT_TOOL_PATH_PLANNER_WIDGET_PLUGIN(Plugin_##WidgetT, Alias)

◆ EXPORT_SIMPLE_DIRECTION_GENERATOR_WIDGET_PLUGIN

#define EXPORT_SIMPLE_DIRECTION_GENERATOR_WIDGET_PLUGIN (   WidgetT,
  Alias 
)
Value:
using Plugin_##WidgetT = SimpleWidgetPlugin<WidgetT, DirectionGeneratorWidgetPlugin>; \
EXPORT_DIRECTION_GENERATOR_WIDGET_PLUGIN(Plugin_##WidgetT, Alias)

◆ EXPORT_SIMPLE_ORIGIN_GENERATOR_WIDGET_PLUGIN

#define EXPORT_SIMPLE_ORIGIN_GENERATOR_WIDGET_PLUGIN (   WidgetT,
  Alias 
)
Value:
using Plugin_##WidgetT = SimpleWidgetPlugin<WidgetT, OriginGeneratorWidgetPlugin>; \
EXPORT_ORIGIN_GENERATOR_WIDGET_PLUGIN(Plugin_##WidgetT, Alias)

◆ EXPORT_SIMPLE_TOOL_PATH_MODIFIER_WIDGET_PLUGIN

#define EXPORT_SIMPLE_TOOL_PATH_MODIFIER_WIDGET_PLUGIN (   WidgetT,
  Alias 
)
Value:
using Plugin_##WidgetT = SimpleWidgetPlugin<WidgetT, ToolPathModifierWidgetPlugin>; \
EXPORT_TOOL_PATH_MODIFIER_WIDGET_PLUGIN(Plugin_##WidgetT, Alias)