Dev Visual Inspection Manual

General Information on the Quality Control Software

Monitoring module consists of two ROS Packages:

  • qcontrol_msgs
  • templatetester

qcontrol_msgs

This package contains custom message and service types.

  • msg/: Folder contains Message (msg) types
  • srv/: Folder contains Service (srv) types

Monitoring.msg

  • int32 detailStatus (1 OK, -1 NOK)
  • int32 operation_type
  • float32[] measurement_mm (vector with measurements)
  • float32[] angle_grad (vector with angles in degrees)
  • int32[] angle_axis (vector with info about the axis, to which the angle is computed. 0 is x, 1 is y, 2 is the axis will be defined by points in x_center, y_center).
  • int32[] x_center (vector with x axis values of some important points on the images, e.g., axis to which the angle is computed)
  • int32[] y_center (vector with y axis values of some important points on the images, e.g., axis to which the angle is computed)

ImageViewing.srv

Request:

  • string opDescr
  • string resDescr
  • bool res
  • sensor_msgs/Image overlay
  • sensor_msgs/Image roi
  • sensor_msgs/Image templ
  • float32 measurment
  • int64 x
  • int64 y
  • int64 step

QualityControl.srv

Request:

  • int64 TemplateID
  • int64 Flow
  • string FlowName Response:
  • Monitoring ResultMon

TemplateIDs (old version): For ELVEZ:

  • 1 - black ball;
  • 3 - screw;
  • 4 - lwr drive;
  • 5 - bulbholder. For LDT:
  • 1 - spindle orientation (hexagon);
  • 2 - stator orientation;
  • 3 - stator height (yellow gap);
  • 4 - spindle height (shiny part).

Flow and FlowName (new version): Flow identifies if a flow file is used:

  • 0 - no flow file is used;
  • 1 - flow file will be used for processing.

FlowName is the flow ID which corresponds to a flow file. The table of correspondence FlowName-Flow.file as well as the flow files are stored in resources/flows/flows.json.

templatetester

This package contains three nodes:

  • templatetester_node This is a GUI based node, which has four main functions:
    1. Flow scene design and saving
    2. Template selection
    3. Algorithm testing
    4. Displaying the monitoring process.

The node subscribes to the camera to grab images for template selection and algorithm testing, and provides a service to display the monitoring process.

  • monitoring_node_server Provides service for monitoring and calls the service of templatetester_node to display the results. If the monitoring has to be done real-time (mode=0), then it subscribes to the camera
  • monitoring_client Calls the service from the monitoring_node_server with templateID or Flow and FlowName and obtains the monitoring result (Monitoring.msg).

resources/ Folder in templatetester package

This folder contains

  • templates for ELVEZ and LDT (templates_elvez_ugoe/ and templates_real_ldt_ugoe/)
  • beep.wav Sound file to produce beep if there is a monitoring error
  • settings.json - settings file that contains
    1. path to templates
    2. camera name for subscription
    3. image path for testing
    4. monitoring mode: 0 - grab from camera, 1 - get images from harddrive
    5. monitoring images: path for images (if mode==1)
    6. monitoring case: 0 - ELVEZ, 1 - LDT
    7. monitoring save: path to save the original images during the processing
  • flows/ This folder contains flow files. The correspondence between the filename and its FlowName (which can be passed to the monitoring service) is saved in flows/flows.json.
  • dnn This folder contains a pretrained VGG19 network. It is used to extract features for the binary classifier (Is detail damaged or OK)
  • stylesheet.ssh defines the style of the general user interface

How to use:

  1. Correct information in the settings.json. Namely, set the path to templates, camera name, image path for testing, mode (and if needed image path), case for monitoring, path for saving the images.
  2. Compile the sources
  3. Start the camera for the real-time mode.
  4. Start templatetester: rosrun templatetester templatetester_node.
  5. Select the monitoring tab.
  6. Start monitoring server: rosrun templatetester monitoring_node_server.
  7. To imitate the call of the monitoring service: rosrun templatetester monitoring_client TemplateID or rosrun templatetester monitoring_client Flow FlowName.

Class list

Class AutoROISelectModel

class AutoROISelectModel : public NodeDataModel

The AutoROISelectModel class is a module to automatically find the region of interest based on the response of Canny edge detection filter. This class is a child of NodeDataModel (s. src/third_party/qnodeeditor). The module gets the response of the Canny edge detector and builds the convex hull and a rectangle around the returned edges. Module Inputs: 0: Source image Module Outputs: 0: A binary mask with convex hull (white) and the rest is black. 1: A binary mask with rectangle (white) and the rest is black. 2: Rectangle (x, y, width, height) of the Output1.

Class BlurringModel

class BlurringModel : public NodeDataModel

This class is designed to denoise the image. This class is a child of NodeDataModel (s. src/third_party/qnodeeditor). The module has the following parameters: 1) Algorithm: Averaging, Gaussian, Median, Bilateral Non-local Means 2) Kernel size. The bigger the kernel, the more denoising is applied to the image The module has 1 input (source image) and 1 output (denoised image).

Class BoardTiltModel

class BoardTiltModel : public NodeDataModel

The InRangeModel class is designed for color thresholding in the HSV color space. Inputs: 0: Input RGB image Outputs: 0: Output mask image Parameters: Ranges for the Hue (H): [0,179], Saturation (S): [0,255], and Value (V): [0, 255].

Class CVMatData

class CVMatData : public NodeData

The CVMatData class is a data class that holds a cv::Mat image.

Class CircleDetectModel

class CircleDetectModel : public NodeDataModel

The CircleDetectModel class is a class that wraps the Circle Hough Transform. It detects the circle in the given image using a set of provided parameters. Module Inputs: Source image Module Parameters: Voting threshold, minimum and maximum radii Module Outputs: Vector of Vec3 points (center+radius), BW mask with all circles drawn white.

Class CloneChannelModel

class CloneChannelModel : public NodeDataModel

The CloneChannelModel class implements automatic binary thresholding (Otsu’s method) of a grayscale image. Inputs: 0: Image Outputs: 0: Image.

Class ColoredBoardTiltModel

class ColoredBoardTiltModel : public NodeDataModel

The InRangeModel class is designed for color thresholding in the HSV color space. Inputs: 0: Input RGB image Outputs: 0: Output mask image Parameters: Ranges for the Hue (H): [0,179], Saturation (S): [0,255], and Value (V): [0, 255].

Class ConnectedComponentsAnalysisModel

class ConnectedComponentsAnalysisModel : public NodeDataModel

The ConnectedComponentsAnalysisModel class is a class that wraps the detection of connected components and selection of one component that corresponds to the user defined criterion. Module Inputs: Source image must be black and white (BW) Module Parameters: Criterion for component selection Module Outputs: BW image with only 1 connected component drawn on it.

Class CutRectModel

class CutRectModel : public NodeDataModel

The CutRectModel class is a class for cropping a region in the given image relative to the given rectangle. The options for cropping are: 1) Inside the given rectangle 2) Above the given rectangle (Including or excluding the rectangle itself) 3) Below the given rectangle (Including or excluding the rectangle itself) Inputs: 0: Input Image 1: Input Rectangle Outputs: 0: Cropped Image 1: Rectangle that defines the position of the cropped image in the original image.

Class Decimal2VectorAggregatorModel

class Decimal2VectorAggregatorModel : public NodeDataModel

The Decimal2VectorAggregatorModel class serves for appending numbers to a vector. The numbers can be appended to the existing vector, otherwise a new vector will be created. Inputs: 0: vector 1-4: decimal numbers Outputs: 0: vector with all input data.

Class DecimalData

class DecimalData : public NodeData

The DecimalData class is a data class that holds a double.

Class DetectAngleModel

class DetectAngleModel : public NodeDataModel

The DetectAngleModel class is designed to measure an angle in the given image. The line is built from point 0 and point 1 and according to the user selection an angle between the vector P1P0 and X, Y (in the clockwise direction) or arbitrary axis defined by Points 2 and 3 in the counterclockwise direction is computed. Inputs: 0: Point 2D 1: Point 2D 2: Point 2D 3: Point 2D 4: Input Image Outputs: 0: Angle value in grads 1: Angle axis (0 - X, 1 -Y, 2 - Arbitrary axis) 2: Image with the drawn angle.

Class DetectDetailStatusModel

class DetectDetailStatusModel : public NodeDataModel

The DetectDetailStatusModel class is design for binary predictions using a trained classifier on a given image. The user must provide a path to the trained classifier file. Inputs: 0 - Image Outputs: 0 - Decimal with the classification result. >0 - positive, otherwise - negative.

Class DetectPointMaxNonZeroNbhModel

class DetectPointMaxNonZeroNbhModel : public NodeDataModel

The DetectPointMaxNonZeroNbhModel class is designed to analyse the non-zero neighborhood around the given points. It returns the coordinates of the point, which has the minimal number of non-zero pixels in the neighborhood. Inputs: 0: is a black and white image 1: a vector of the type VecVec3Data Parameters: neighborhood radius Outputs: 0: a point of the type PointData.

Class EditorWidget

class EditorWidget : public QMainWindow

The EditorWidget class is responsible for creation of flow diagrams (algorithms for image processing pipelines) and integrating them into the monitoring routines.

Class FitRotatedShapeModel

class FitRotatedShapeModel : public NodeDataModel

This class is designed to fit a specific shape to the image. At the moment only a hexagonal shape fitting is implemented/tested. The ideal polygon is built using the center of rotation and the radius. Then the polygon is rotated around the center clock-wise to N grad (with step 0.5 grad) according its rotational symmetry. The overlap with the original image is checked. The result with the maximal overlap is returned. Inputs: 0: Source image is a black and white image with some parts of a shape present. 1: A point (type PointData) for the center of the shape Outputs: 0: An image with the final polygon drawn. 1: A point which considered as the 0 vertex of the shape Parameters: Shape radius in pixels.

Class GrayThreshModel

class GrayThreshModel : public NodeDataModel

The InRangeModel class is designed for color thresholding in the HSV color space. Inputs: 0: Input RGB image Outputs: 0: Output mask image Parameters: Ranges for the Hue (H): [0,179], Saturation (S): [0,255], and Value (V): [0, 255].

Class ImageArithmeticModel

class ImageArithmeticModel : public NodeDataModel

The ImageArithmeticModel class implements the binary image arithmetic: AND, OR, XOR, Minus. Parameters: binary operation Inputs: 0 - Image 1 - Image Outputs: 0 - Result for image arithmetic.

Class ImageCropper

class ImageCropper : public QWidget

This class implements the selection of the image part by dragging a rectangle and cropping the image.

The part that is covered by the rectangle is cropped.

Class ImageLoaderModel

class ImageLoaderModel : public NodeDataModel

This class is designed to load an image into memory and pass it further in processing pipeline. This class is a child of NodeDataModel (s. src/third_party/qnodeeditor). To load an image one needs to press a button ‘Open’ and select an image. If the module is the starting module in the monitoring pipeline, the output of the SceneIn module must be connect to the input port of this module. Inputs: 1 - Image - The output of the SceneInModule Output: 1 - Image.

Class ImageShowModel

class ImageShowModel : public NodeDataModel

The ImageShowModel class is designed to display and save the input image. A right mouse click on the image saves the image as png file. The image is also passed further on the pipeline. Inputs: 0 - Image Outputs: 0 - Image.

Class ImageTemplateMatchModel

class ImageTemplateMatchModel : public NodeDataModel

The ImageTemplateMatchModel class is designed for pattern matching based on crosscorrelation. Inputs: 0: Input image 1: Template image, which is usually smaller than the input image. 2: (optional) Search rectangle to look for the template image in the input image. Outputs: 0: The image, which is the most similar to the template image, found in the input image. 1: Rectangle, which shows the position of the found image in the input image 2: Maximal similarity value.

Class ImageViewer

class ImageViewer : public QWidget

The ImageViewer class is for showing the image in a scrollbar. Usually an instance of this class is used as the central widget of each NodeModel class.

Class ImgOverlayModel

class ImgOverlayModel : public NodeDataModel

The ImgOverlayModel class is designed to overlay one image over the other and show the results. The input images (Input0 and Input1) can be either of the same size or of the different size and then the rectangle is provided, which defines the position of the Input1 in the Input0. If no rectangle is given, the images are assumed to be of the same size. Inputs: 0: Image 1: Image 2: Rectangle Outputs: 0: The result overlay.

Class InModel

class InModel : public NodeDataModel, public BaseInNodeDataModel

The InModel class is a starting module in each scene required for integration of the flow file into the monitoring mechanism.

Class InRangeModel

class InRangeModel : public NodeDataModel

The InRangeModel class is designed for color thresholding in the HSV color space. Inputs: 0: Input RGB image Outputs: 0: Output mask image Parameters: Ranges for the Hue (H): [0,179], Saturation (S): [0,255], and Value (V): [0, 255].

Class InvertIntensityModel

class InvertIntensityModel : public NodeDataModel

The InvertIntensityModel class is designed to invert intensities of the given image. Inputs: 0: Original image Outputs: 0: Inverted image.

Class LogStackSingleton

class LogStackSingleton

This is a singleton class that collects information from all modules about failure in execution. The information is then shown in the output monitoring result.

Class MinEnclosingCircleModel

class MinEnclosingCircleModel : public NodeDataModel

The MinEnclosingCircleModel class is designed to build the minimal enclosing circle around the given points. Inputs: 0: Input image (can be color or bw) Outputs: 0: Circle radius (Decimal data) 1: Circle center (Point data)

Class MonitorElvezBlackBall

class MonitorElvezBlackBall : public MonitorBase

The MonitorElvezBlackBall class This class implements the evaluation of the black ball status.

Class MonitorElvezBulbHolder

class MonitorElvezBulbHolder : public MonitorBase

The MonitorElvezBulbHolder class This class implements the evaluation of the bulb holder status.

Class MonitorElvezLWRDrive

class MonitorElvezLWRDrive : public MonitorBase

The MonitorElvezLWRDrive class This class implements the evaluation of the lwr drive status.

Class MonitorElvezScrew

class MonitorElvezScrew : public MonitorBase

The MonitorElvezScrew class This class implements the evaluation of the screw status.

Class MonitorFlow

class MonitorFlow : public MonitorBase

The MonitorFlow class This class implements the general class for monitoring with flow diagrams.

Class MonitorHopu

class MonitorHopu : public MonitorBase

The MonitorHopu class This class implements the evaluation of the boards.

Class MonitorLDTSpindleRotation

class MonitorLDTSpindleRotation : public MonitorBase

The MonitorLDTSpindleRotation class This class implements the evaluation of the orientation of the hexagonal spindle with respect to another line on the image. This line is drawn between two upper circle centers on the drive.

Class MonitorLDTSpindleSize

class MonitorLDTSpindleSize : public MonitorBase

The MonitorLDTSpindleSize class This class implements the spindle size evaluation for LDT.

Class MonitorLDTStatorRotation

class MonitorLDTStatorRotation : public MonitorBase

The MonitorLDTStatorRotation class This class implements the evaluation of the station orientation (angle to y axis in clockwise direction)

Class MonitorLDTStatorSize

class MonitorLDTStatorSize : public MonitorBase

The MonitorLDTStatorSize class This class implements the stator size evaluation for LDT.

Class MonitoringNode

class MonitoringNode

The MonitoringNode class This class provides the monitoring service and when the request arrives, it calls the correspondent MonitorBase child routines and sends back the monitoring response. Additionally, it is also a client of the Display service (s. qdisplayservicenode.hpp). The MonitoringNode sends the request for display to the display service.

Class MonitoringWidget

class MonitoringWidget : public QWidget

This class is a widget, where the monitoring results are displayed.

Class MorphologyModel

class MorphologyModel : public NodeDataModel

The MorphologyModel class is designed to perform morphological operations accoring to the selected operation and the given kernel size. The kernel shape is morphological rect. Inputs: 0: Image Outputs: 0: Result image Parameters: Kernel width, kernel height, operation (erosion, dilation, opening, closing)

Class NumberDisplayDataModel

class NumberDisplayDataModel : public NodeDataModel

The NumberDisplayDataModel class is designed to display the input decimal number. Inputs: 0: Decimal number Outputs: None.

Subclassed by RectDisplayDataModel, RectSourceDataModel

Class NumberSourceDataModel

class NumberSourceDataModel : public NodeDataModel

The NumberSourceDataModel class is designed to input a decimal number and pass it further to the scene as decimal data. Inputs: None Outputs: 0: Decimal data Parameters: Text field to enter the number.

Class OtsuThresholdModel

class OtsuThresholdModel : public NodeDataModel

The OtsuThresholdModel class implements automatic binary thresholding (Otsu’s method) of a grayscale image. Inputs: 0: Image Outputs: 0: Image.

Class OutModel

class OutModel : public NodeDataModel, public BaseOutNodeDataModel

The OutModel class is the ending module for each scene required for integration of the flow file into the monitoring mechanism. Inputs: 0: Image - Template image 1: Image - ROI image 2: Image - Overlayed result image 3: Rectangle - Rectangle of the roi location 4: Vector of decimal values - vector of measurements 5: Vector of decimal values - vector of angles 6: Vector of decimal values - vector of angle axes Outputs: None Parameter: Measurement type:

  • Distance
  • Angle
  • Status Pixel to MM factor is active only when the distance measurement is selected.

Class PointData

class PointData : public NodeData

The PointData class is a data class that holds a cv::Point.

Class PointFromVectorModel

class PointFromVectorModel : public NodeDataModel

The PointFromVectorModel class is designed to extract a point from the vector of points by its index. The selected point is then drawn on the image and shown in the central widget. Usage: Enter a point index, press the button. If the index is out of range, nothing will be extracted. Inputs: 0: Input image 1: vector of points (VecVec3 Data) Outputs: 0: Point Data Parameters: Point index.

Class PointInROIToPointInImageModel

class PointInROIToPointInImageModel : public NodeDataModel

The PointInROIToPointInImageModel class converts the coordinates of the given 2D point in the subimage to the coordinates of the complete image. The subimage is given as a rectangel from the complete image. The point is drawn in the central widget on the complete image. Inputs: 0: Input image 1: Point in the subimage coordinates. P_ROI(x,y) 2: Rectange which defines the location of the subimage in the complete image. Rect (x_r,y_r,w_r,h_r) Outputs: 0: Point in the image coordinates. P_Image(x+x_r,y+y_r)

Class PolynomialRegression

template <class TYPE>
class PolynomialRegression

Polynomial Regression class It aims to fit a non-linear relationship to a set of points. It approximates this by solving a series of linear equations using a least-squares approach.

We can model the expected value y as an nth degree polynomial, yielding the general polynomial regression model:

y = a0 + a1 * x + a2 * x^2 + … + an * x^n

Class QCameraSubscriberNode

class QCameraSubscriberNode : public QThread

The QCameraSubscriberNode class is a separate thread which subscribes to the camera and obtains an image from it.

Class QDisplayServiceNode

class QDisplayServiceNode : public QThread

The QDisplayServiceNode class is a separate thread that advertizes the display service, which is called during the execution of the monitoring.

Class RectData

class RectData : public NodeData

The RectData class is the data class that holds a cv::Rect.

Class RectDisplayDataModel

class RectDisplayDataModel : public NumberDisplayDataModel

The RectDisplayDataModel class is designed to show the rectangle data as text and also split the rectangle data into 4 decimal numbers: x,y, width, height. Inputs: 0: Rectangle data Outputs: 0: x 1: y 2: width 3: height.

Class RectSourceDataModel

class RectSourceDataModel : public NumberDisplayDataModel

The RectSourceDataModel class is designed to create rectangle data from four input decimal fields Inputs: 0: x 1: y 2: width 3: height Outputs: 0: rect data.

Class SelectROIModel

class SelectROIModel : public NodeDataModel

The SelectROIModel class is designed to select a region of interest (ROI) from the input image. To pass the selected ROI to the output, the image must be double clicked. Inputs: 0: Image Outputs: 0: Image.

Class TemplateWidget

class TemplateWidget : public QWidget

This class is for selection and saving template images.

In this widget the selection of template images is done.

Class TesterWidget

class TesterWidget : public QWidget

This class is for testing the algorithms offline.

This widget is designed for testing hardcoded functions and flow diagrams on images. The images can be either taken from hard-drive or grabbed from the camera

Class ToGrayscaleModel

class ToGrayscaleModel : public NodeDataModel

The OtsuThresholdModel class implements automatic binary thresholding (Otsu’s method) of a grayscale image. Inputs: 0: Image Outputs: 0: Image.

Class TrainBinaryClassifierModel

class TrainBinaryClassifierModel : public NodeDataModel

This class is designed for training a binary classifier (support vector machine) on VGG f8 features. The user must provide positive and negative examples. Then the classifier is trained and saves in the resources file. Later the trained classifier can be used for detection of damaged parts. By itself this module has no input or output ports.

Class VecVec3Data

class VecVec3Data : public NodeData

The VecVec3Data class is a data class that holds a vector of cv::Vec3f. It is used to save, for instance, the list of circles with a central point (x,y) and the radius value (z) or a list of 3D points.

Class VectorDecimalData

class VectorDecimalData : public NodeData

The VectorDecimalData class is a data class that holds a std::vector<double>

File list

File AutoROISelectModel.cpp

File AutoROISelectModel.hpp

class AutoROISelectModel : public NodeDataModel
#include <AutoROISelectModel.hpp>

The AutoROISelectModel class is a module to automatically find the region of interest based on the response of Canny edge detection filter. This class is a child of NodeDataModel (s. src/third_party/qnodeeditor). The module gets the response of the Canny edge detector and builds the convex hull and a rectangle around the returned edges. Module Inputs: 0: Source image Module Outputs: 0: A binary mask with convex hull (white) and the rest is black. 1: A binary mask with rectangle (white) and the rest is black. 2: Rectangle (x, y, width, height) of the Output1.

Public Functions

AutoROISelectModel()

Constructor.

virtual ~AutoROISelectModel()

Destructor.

QString caption() const

This function returns module caption.

Return

QString name() const

This function returns module Name.

Return

std::unique_ptr<NodeDataModel> clone() const

This function returns the unique pointer to the class.

Return

virtual QString modelName() const

This function returns the model name.

Return

unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports of this module.

Return
Parameters
  • portType: input or output

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the specific data type for input and output ports.

Return
Parameters
  • portType: input or output
  • portIndex: the correspondent port index

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data from the given port.

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when input data on the specific port of the module changes, e.g., when the port gets connected or disconnected.

Parameters
  • nodeData:
  • port:

QWidget *embeddedWidget()

This module has no embedded widget, i.e. the widget that is shown in the module itself.

Return

QWidget **toCentralViewWidget()

This function returns a pointer to the pointer to the Central Widget. It is called when the module is selected and the button “Show details” is clicked. Then the Flowscene is replaced with the Central widget.

QWidget **toSideViewWidget()

This function returns a pointer to the pointer to the Parameter widget, that is shown on the right side. It is called when the module is selected and the button “Show details” is clicked. Then the default parameter widget is replaced with this widget.

QString infoLabelText()

This function returns the info string for this module.

Protected Functions

void compute()

This function is responsible for all image processing in this module.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Members

std::shared_ptr<NodeData> _inSourceData

_inSourceData input 0

std::shared_ptr<NodeData> _outResultMaskData

_outResultMaskData output0

std::shared_ptr<NodeData> _outResultRectMaskData

_outResultRectMaskData output1

std::shared_ptr<NodeData> _outResultRectData

_outResultRectData output2

cv::Mat view_result

Resulting image that is shown in viewWidget.

QLabel *infoLabel

This is a help label that is shown in the parameter widget.

ImageViewer *viewWidget

viewWidget is the Central Widget of this module.

File BlurringModel.cpp

File BlurringModel.hpp

class BlurringModel : public NodeDataModel
#include <BlurringModel.hpp>

This class is designed to denoise the image. This class is a child of NodeDataModel (s. src/third_party/qnodeeditor). The module has the following parameters: 1) Algorithm: Averaging, Gaussian, Median, Bilateral Non-local Means 2) Kernel size. The bigger the kernel, the more denoising is applied to the image The module has 1 input (source image) and 1 output (denoised image).

Public Functions

BlurringModel()

Constructor.

virtual ~BlurringModel()

Destructor.

QString caption() const

Module Caption.

Return

QString name() const

Module Name.

Return

std::unique_ptr<NodeDataModel> clone() const

Unique pointer to the class.

Return

virtual QString modelName() const
unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports. This module has 1 input and 1 output port.

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This module returns the data type of the input and output ports. This module has CVMatData type both for input and output.

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data.

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when the status of the input data is changed.

QWidget *embeddedWidget()

This function returns a pointer to the embedded widget. This module has no embedded widget.

QWidget **toCentralViewWidget()

This function returns the pointer to the pointer to the central widget.

Return

QWidget **toSideViewWidget()

This function returns the pointer to the pointer to the parameter widget.

Return

QString infoLabelText()

This function returns the info text that is shown when the module is selected.

Public Slots

void compute()

This function performs the image denoising.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Members

QWidget *propsWidget

Parameter widget of the module.

QVBoxLayout *vblayout

Layout of the parameter widget.

QComboBox *algCombo

Combobox to select the algorithms.

QLineEdit *kernelValue

Line edit field to enter the kernel size.

QLabel *_label
QLabel *_label1
QPushButton *button
QLabel *label
ImageViewer *viewWidget

Central widget of the module.

std::shared_ptr<NodeData> _inSourceData

Input image.

std::shared_ptr<NodeData> _outResultData

Output image.

File BoardTiltModel.cpp

Functions

void covariance_matrix(Eigen::MatrixXd &mat, Eigen::MatrixXd &cov)
void eigenvalues(Eigen::MatrixXd &mat, Eigen::MatrixXd &ev)
void eigenvectors(Eigen::MatrixXd &mat, Eigen::MatrixXd &ev)
double blob_elongation(cv::Mat labels, int i)
double get_angle_of_blob(cv::Mat labels, int blob_id)

File BoardTiltModel.hpp

class BoardTiltModel : public NodeDataModel
#include <BoardTiltModel.hpp>

The InRangeModel class is designed for color thresholding in the HSV color space. Inputs: 0: Input RGB image Outputs: 0: Output mask image Parameters: Ranges for the Hue (H): [0,179], Saturation (S): [0,255], and Value (V): [0, 255].

Public Functions

BoardTiltModel()

Constructor.

virtual ~BoardTiltModel()

Destructor.

QString caption() const

This function returns the module caption.

QString name() const

This function returns the module name.

std::unique_ptr<NodeDataModel> clone() const

This function returns a unique pointer to the module.

virtual QString modelName() const

This function returns the model name.

unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports. There are 1 input and 1 output ports in this module.

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the data types of input and output ports. Input 0: Image of CVMatData type; Output 0: Image of CVMatData type;.

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data.

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when the status of the input data has changed.

QWidget *embeddedWidget()

This function returns a pointer to the embedded widget. This module has no embedded widget.

QWidget **toCentralViewWidget()

This function returns a pointer to pointer to the central widget.

QWidget **toSideViewWidget()

This function returns a pointer to pointer to the parameter widget.

QJsonObject save() const

This function saves the parameters of the module.

void restore(QJsonObject const &p)

This function restores the parameters of the module from the JsonObject.

Parameters
  • p: is the JsonObject

QString infoLabelText()

This function returns the information about on how to use the module.

Public Slots

void compute()

This function executes the thresholding.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Members

std::shared_ptr<NodeData> _inSourceData

_inSourceData is the input image

std::shared_ptr<NodeData> _outResultData

_outResultData is the output image

std::shared_ptr<RectData> _outResultRectData

Output rectangle.

cv::Mat view_result

This result image is shown in the central widget.

QWidget *propsWidget

This is parameter widget.

QFormLayout *layout

This is a parameter widget layout.

QVBoxLayout *vblayout

This is a parameter widget layout.

QSpinBox *hueMin

This field selects the minimal Hue.

QPushButton *button
QLabel *label

This is a preview label.

ImageViewer *viewWidget

This is the central widget.

File CVMatData.hpp

class CVMatData : public NodeData
#include <CVMatData.hpp>

The CVMatData class is a data class that holds a cv::Mat image.

Public Functions

CVMatData()

Default constructor.

CVMatData(cv::Mat const &_mat)

Constructor from a cv::Mat.

CVMatData(QPixmap const &pixmap)

Constructor from a pixmap.

QPixmap getPixmap() const

This function converts cv::Mat to Pixmap and returns it.

Return
QPixmap

NodeDataType type() const

This function returns the data type.

cv::Mat cvmat() const

This function returns a copy of the data field.

cv::Mat pimcvmat(QPixmap const &_pixmap) const

This function converts a pixmap to cv::Mat and returns it.

Return
Parameters
  • _pixmap:

Private Members

cv::Mat mat

This is a data field.

File CircleDetectModel.cpp

File CircleDetectModel.hpp

class CircleDetectModel : public NodeDataModel
#include <CircleDetectModel.hpp>

The CircleDetectModel class is a class that wraps the Circle Hough Transform. It detects the circle in the given image using a set of provided parameters. Module Inputs: Source image Module Parameters: Voting threshold, minimum and maximum radii Module Outputs: Vector of Vec3 points (center+radius), BW mask with all circles drawn white.

Public Functions

CircleDetectModel()

Constructor.

virtual ~CircleDetectModel()

Destructor.

QString caption() const

This function returns the module caption.

QString name() const

This function returns the module name.

std::unique_ptr<NodeDataModel> clone() const

This function returns a pointer to a module object.

virtual QString modelName() const
unsigned int nPorts(PortType portType) const
NodeDataType dataType(PortType portType, PortIndex portIndex) const
std::shared_ptr<NodeData> outData(PortIndex port)
void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)
QWidget *embeddedWidget()

This module has no embedded widget.

Return

QWidget **toCentralViewWidget()

This function returns a pointer to pointer to the module’s central widget.

QWidget **toSideViewWidget()

This function returns a pointer to pointer to the module’s parameter widget.

QJsonObject save() const

This function saves the parameters to the json file.

Return

void restore(QJsonObject const &p)

This function restores the parameters from the json file.

QString infoLabelText()

This function returns the information about on how to use the module.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Members

QWidget *_paramsWidget

This widget holds all parameter GUI fields: namely, 3 lines and a button.

QLineEdit *le1

Field for voting threshold.

QLineEdit *le2

Field for min radius.

QLineEdit *le3

Field for max radius.

QPushButton *computeButton

This button calls the compute function.

ImageViewer *viewWidget

This is a central widget that is shown, when the module is selected and “Show details” button is pressed.

std::shared_ptr<NodeData> _inSourceData

Pointer to the input data.

std::shared_ptr<NodeData> _outResultCircleMaskData

Pointer to the output black-and-white image with circle drawn white on the black background.

std::shared_ptr<VecVec3Data> _outCircleListData

Pointer to the output list of circles.

Private Slots

void compute()

This function take the input image and applies the Circle Hough Transform with the parameters provided in the parameter widget.

File CloneChannelModel.cpp

File CloneChannelModel.hpp

class CloneChannelModel : public NodeDataModel
#include <CloneChannelModel.hpp>

The CloneChannelModel class implements automatic binary thresholding (Otsu’s method) of a grayscale image. Inputs: 0: Image Outputs: 0: Image.

Public Functions

CloneChannelModel()

Constructor.

virtual ~CloneChannelModel()

Destructor.

QString caption() const

This function returns module caption.

Return

QString name() const

This function returns module Name.

Return

std::unique_ptr<NodeDataModel> clone() const

This function returns the unique pointer to the class.

Return

virtual QString modelName() const

This function returns the model name.

Return

unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports of this module.

Return
Parameters
  • portType: input or output

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the specific data type for input and output ports.

Return
Parameters
  • portType: input or output
  • portIndex: the correspondent port index

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data from the given port.

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when input data on the specific port of the module changes, e.g., when the port gets connected or disconnected.

Parameters
  • nodeData:
  • port:

QWidget *embeddedWidget()

This module has no embedded widget, i.e. the widget that is shown in the module itself.

Return

QWidget **toCentralViewWidget()

This function returns a pointer to the pointer to the Central Widget. It is called when the module is selected and the button “Show details” is clicked. Then the Flowscene is replaced with the Central widget.

QWidget **toSideViewWidget()

This function returns a pointer to the pointer to the Parameter widget, that is shown on the right side. It is called when the module is selected and the button “Show details” is clicked. Then the default parameter widget is replaced with this widget.

Protected Functions

bool eventFilter(QObject *object, QEvent *event)
void compute()

This function is responsible for all image processing in this module.

QString infoLabelText()

This function returns the info string for this module.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Members

QLabel *_label

Result preview is shown in the label.

std::shared_ptr<NodeData> _inSourceData

Input image.

std::shared_ptr<NodeData> _outResultData

Output image.

ImageViewer *viewWidget

Central widget.

File ColoredBoardTiltModel.cpp

Functions

double get_angle(cv::Mat labels, int blob_id)
void covariance_matrix2(Eigen::MatrixXd &mat, Eigen::MatrixXd &cov)
void eigenvalues2(Eigen::MatrixXd &mat, Eigen::MatrixXd &ev)
double blob_elongation2(cv::Mat labels, int i)

File ColoredBoardTiltModel.hpp

class ColoredBoardTiltModel : public NodeDataModel
#include <ColoredBoardTiltModel.hpp>

The InRangeModel class is designed for color thresholding in the HSV color space. Inputs: 0: Input RGB image Outputs: 0: Output mask image Parameters: Ranges for the Hue (H): [0,179], Saturation (S): [0,255], and Value (V): [0, 255].

Public Functions

ColoredBoardTiltModel()

Constructor.

virtual ~ColoredBoardTiltModel()

Destructor.

QString caption() const

This function returns the module caption.

QString name() const

This function returns the module name.

std::unique_ptr<NodeDataModel> clone() const

This function returns a unique pointer to the module.

virtual QString modelName() const

This function returns the model name.

unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports. There are 1 input and 1 output ports in this module.

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the data types of input and output ports. Input 0: Image of CVMatData type; Output 0: Image of CVMatData type;.

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data.

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when the status of the input data has changed.

QWidget *embeddedWidget()

This function returns a pointer to the embedded widget. This module has no embedded widget.

QWidget **toCentralViewWidget()

This function returns a pointer to pointer to the central widget.

QWidget **toSideViewWidget()

This function returns a pointer to pointer to the parameter widget.

QJsonObject save() const

This function saves the parameters of the module.

void restore(QJsonObject const &p)

This function restores the parameters of the module from the JsonObject.

Parameters
  • p: is the JsonObject

QString infoLabelText()

This function returns the information about on how to use the module.

Public Slots

void compute()

This function executes the thresholding.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Members

std::shared_ptr<NodeData> _inSourceData

_inSourceData is the input image

std::shared_ptr<NodeData> _outResultData

_outResultData is the output image

std::shared_ptr<RectData> _outResultRectData

Output rectangle.

cv::Mat view_result

This result image is shown in the central widget.

QWidget *propsWidget

This is parameter widget.

QFormLayout *layout

This is a parameter widget layout.

QVBoxLayout *vblayout

This is a parameter widget layout.

QSpinBox *hueMin

This field selects the minimal Hue.

QPushButton *button
QLabel *label

This is a preview label.

ImageViewer *viewWidget

This is the central widget.

File ConnectedComponentsAnalysisModel.cpp

File ConnectedComponentsAnalysisModel.hpp

class ConnectedComponentsAnalysisModel : public NodeDataModel
#include <ConnectedComponentsAnalysisModel.hpp>

The ConnectedComponentsAnalysisModel class is a class that wraps the detection of connected components and selection of one component that corresponds to the user defined criterion. Module Inputs: Source image must be black and white (BW) Module Parameters: Criterion for component selection Module Outputs: BW image with only 1 connected component drawn on it.

Public Functions

ConnectedComponentsAnalysisModel()

Constructor.

virtual ~ConnectedComponentsAnalysisModel()

Destructor.

QString caption() const

This function returns the module caption.

QString name() const

This function returns the module name.

std::unique_ptr<NodeDataModel> clone() const
virtual QString modelName() const
unsigned int nPorts(PortType portType) const

This fucntion returns the number of input and output ports. There are 1 input and 1 output port in this module.

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the data type of the input and output ports. The input and output ports in this module are of CVMatData type.

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns the pointer to the output data.

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when the status of the input data has changed.

QWidget *embeddedWidget()

This module has no embedded widget.

QWidget **toCentralViewWidget()

This function returns the pointer to the central widget.

QWidget **toSideViewWidget()

This function returns the pointer to the parameter widget.

QString infoLabelText()

This function returns the information about on how to use the module.

QJsonObject save() const

This function saves the module parameters.

void restore(QJsonObject const &p)

This function restores the module parameters.

Public Slots

void compute()

In this function the computation of the connected components and the selection is performed.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Members

std::shared_ptr<NodeData> _inSourceData

Input image.

std::shared_ptr<NodeData> _outOnlyOneCCData

Output image.

cv::Mat view_result

Result image as cv::Mat.

QWidget *propsWidget

Parameter widget.

QVBoxLayout *vblayout
QComboBox *ccSelectionCriterion

Combobox for selection criteria.

QStringList commands

= { “Max_Area”, “Max_Height”, “Max_Width”, “Top”,

“Bottom” }


Selection commands.

QPushButton *button
QLabel *label
ImageViewer *viewWidget

Central widget.

File CutRectModel.cpp

File CutRectModel.hpp

class CutRectModel : public NodeDataModel
#include <CutRectModel.hpp>

The CutRectModel class is a class for cropping a region in the given image relative to the given rectangle. The options for cropping are: 1) Inside the given rectangle 2) Above the given rectangle (Including or excluding the rectangle itself) 3) Below the given rectangle (Including or excluding the rectangle itself) Inputs: 0: Input Image 1: Input Rectangle Outputs: 0: Cropped Image 1: Rectangle that defines the position of the cropped image in the original image.

Public Functions

CutRectModel()

Constructor.

virtual ~CutRectModel()

Destructor.

QString caption() const

This function returns the module caption.

QString name() const

This function returns the module name.

std::unique_ptr<NodeDataModel> clone() const

This function returns a unique pointer to the module.

virtual QString modelName() const

This function returns the model name.

unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports. There are 2 input and 2 output ports in this module.

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the data types of input and output ports. Input 0: Image of CVMatData type; Input 1: Rectangle of RectData Type Output 0: Image of CVMatData type; Output 1: Rectangle of RectData Type.

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data.

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when the status of the input data has changed.

QWidget *embeddedWidget()

This function returns a pointer to the embedded widget. This module has no embedded widget.

QWidget **toCentralViewWidget()

This function returns a pointer to pointer to the central widget.

QWidget **toSideViewWidget()

This function returns a pointer to pointer to the parameter widget.

QJsonObject save() const

This function saves the module parameters.

void restore(QJsonObject const &p)

This function restores the module parameters.

QString infoLabelText()

This function returns the information about on how to use the module.

Public Slots

void checkBoxesInsideChanged()

This slot is activated, when the parameter check box status is changed.

Protected Functions

void compute()

This is the function, where the actual image cropping happens.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Members

std::shared_ptr<NodeData> _inSourceData

Input image.

std::shared_ptr<RectData> _inRectData

Input rectangle.

std::shared_ptr<NodeData> _outResultData

Output image.

std::shared_ptr<RectData> _outResultRectData

Output rectangle.

cv::Mat view_result
QWidget *propsWidget

Parametere widget.

QVBoxLayout *layout

GUI elements.

QCheckBox *above

GUI elements.

QCheckBox *inside

GUI elements.

QCheckBox *wRect

GUI elements.

QLabel *rectLabel

GUI elements.

ImageViewer *viewWidget

Central widget.

File Decimal2VectorAggregatorModel.cpp

File Decimal2VectorAggregatorModel.hpp

class Decimal2VectorAggregatorModel : public NodeDataModel
#include <Decimal2VectorAggregatorModel.hpp>

The Decimal2VectorAggregatorModel class serves for appending numbers to a vector. The numbers can be appended to the existing vector, otherwise a new vector will be created. Inputs: 0: vector 1-4: decimal numbers Outputs: 0: vector with all input data.

Public Functions

Decimal2VectorAggregatorModel()

Constructor.

virtual ~Decimal2VectorAggregatorModel()

Destructor.

QString caption() const

This function returns the module caption.

QString name() const

This function returns the module name.

std::unique_ptr<NodeDataModel> clone() const

This function returns a unique pointer to the module.

virtual QString modelName() const

This function returns the model name.

unsigned int nPorts(PortType portType) const

This fucntion returns the number of input and output ports. There are 5 input and 1 output ports in this module.

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This fucntion returns the data types of input and output ports. Input 0: VectorDecimalData; Inputs 1-4: DecimalData Output 0: VectorDecimalData.

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data.

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when the status of the input data has changed.

QWidget *embeddedWidget()

This function returns a pointer to the embedded widget. This module has no embedded widget.

QWidget **toCentralViewWidget()

This function returns a pointer to pointer to the central widget.

QWidget **toSideViewWidget()

This function returns a pointer to pointer to the parameter widget.

QString infoLabelText()

This function returns the information string for this module.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Members

std::shared_ptr<VectorDecimalData> _inSourceData

Input vector.

std::shared_ptr<DecimalData> _inDecimal1

Input decimal.

std::shared_ptr<DecimalData> _inDecimal2

Input decimal.

std::shared_ptr<DecimalData> _inDecimal3

Input decimal.

std::shared_ptr<DecimalData> _inDecimal4

Input decimal.

std::shared_ptr<VectorDecimalData> _outVectorDecimalData

Output vector.

File DecimalData.hpp

class DecimalData : public NodeData
#include <DecimalData.hpp>

The DecimalData class is a data class that holds a double.

Public Functions

DecimalData()

Default constructor.

DecimalData(double const number)

Constructor with double.

Parameters
  • number:

NodeDataType type() const

This function returns the type of the data.

Return

double number() const

This function returns a copy of the data field.

Return

QString numberAsText() const

This function returns the data field as text.

Return

Private Members

double _number

_number is the double data field

File DetectAngleModel.cpp

File DetectAngleModel.hpp

class DetectAngleModel : public NodeDataModel
#include <DetectAngleModel.hpp>

The DetectAngleModel class is designed to measure an angle in the given image. The line is built from point 0 and point 1 and according to the user selection an angle between the vector P1P0 and X, Y (in the clockwise direction) or arbitrary axis defined by Points 2 and 3 in the counterclockwise direction is computed. Inputs: 0: Point 2D 1: Point 2D 2: Point 2D 3: Point 2D 4: Input Image Outputs: 0: Angle value in grads 1: Angle axis (0 - X, 1 -Y, 2 - Arbitrary axis) 2: Image with the drawn angle.

Public Functions

DetectAngleModel()

Constructor.

virtual ~DetectAngleModel()

Destructor.

QString caption() const

This function returns the module caption.

QString name() const

This function returns the module name.

std::unique_ptr<NodeDataModel> clone() const

This function returns a unique pointer to the module.

virtual QString modelName() const

This function returns the model name.

unsigned int nPorts(PortType portType) const

This fucntion returns the number of input and output ports. There are 5 input and 3 output ports in this module.

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This fucntion returns the data types of input and output ports. Inputs 0-3 PointData type, Input 4: CVMatData type Outputs 0-1 DecimalData type, Output 2: CVMatData type.

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data.

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when the status of the input data has changed.

QWidget *embeddedWidget()

This function returns a pointer to the embedded widget. This module has no embedded widget.

QWidget **toCentralViewWidget()

This function returns a pointer to pointer to the central widget.

QWidget **toSideViewWidget()

This function returns a pointer to pointer to the parameter widget.

QString infoLabelText()

This function returns an information string about the module.

QJsonObject save() const

This function saves the module parameters to JSON object.

void restore(QJsonObject const &p)

This function restores the module parameters from JSON object.

Public Slots

void compute()

This function computes the angle given the input and the user-defined axis.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Members

std::shared_ptr<PointData> _inPointData1

Input Point 0.

std::shared_ptr<PointData> _inPointData2

Input Point 1.

std::shared_ptr<PointData> _inPointData3

Input Point 2.

std::shared_ptr<PointData> _inPointData4

Input Point 3.

std::shared_ptr<CVMatData> _inSourceData

Input Image.

std::shared_ptr<CVMatData> _outResultData

Output Image.

std::shared_ptr<DecimalData> _outAngleData

Output angle value.

std::shared_ptr<DecimalData> _outAxisData

Output axis value.

cv::Mat view_result

Result image that is shown in the central widget.

QWidget *propsWidget

Central widget.

QFormLayout *layout

GUI elements.

QComboBox *combo

GUI elements.

QLabel *angleLabel

GUI elements.

ImageViewer *viewWidget

Central widget.

File DetectDetailStatusModel.cpp

File DetectDetailStatusModel.hpp

class DetectDetailStatusModel : public NodeDataModel
#include <DetectDetailStatusModel.hpp>

The DetectDetailStatusModel class is design for binary predictions using a trained classifier on a given image. The user must provide a path to the trained classifier file. Inputs: 0 - Image Outputs: 0 - Decimal with the classification result. >0 - positive, otherwise - negative.

Public Functions

DetectDetailStatusModel()

Constructor.

virtual ~DetectDetailStatusModel()

Destructor.

QString caption() const

This function returns the module caption.

QString name() const

This function returns the module name.

std::unique_ptr<NodeDataModel> clone() const

This function returns a pointer to a module object.

virtual QString modelName() const

This function returns the model name.

unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports. This module has 1 input and 1 output ports.

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This fucntion returns the data types of input and output ports. Input 0: Image of CVMatData type; Output 0: Classification result of Decimal type;.

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data.

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when the status of the input data has changed.

QWidget *embeddedWidget()

This function returns a pointer to the embedded widget. This module has no embedded widget.

QWidget **toCentralViewWidget()

This function returns a pointer to pointer to the central widget.

QWidget **toSideViewWidget()

This function returns a pointer to pointer to the parameter widget.

QString infoLabelText()

This function returns the information about on how to use the module.

QJsonObject save() const

This function saves the module parameters.

void restore(QJsonObject const &p)

This function restores the module parameters.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Members

QWidget *_paramsWidget

Parameter widget.

QPushButton *openModelButton

Button to open the model file.

QLabel *modelNameLabel

Label to show the model name.

QPushButton *computeButton

This button starts the computation.

QLabel *resultLabel

resultLabel

ImageViewer *viewWidget

Central widget.

QString modelFileName

The name of the model file.

std::shared_ptr<CVMatData> _inSourceData

Input image.

std::shared_ptr<DecimalData> _outResultData

Output decimal data.

Private Slots

void compute()

In this function the application of the predicition of the trained model on the given image is executed.

void openModel()

This function gives a path to the trained model.

File DetectPointMaxNonZeroNbhModel.cpp

File DetectPointMaxNonZeroNbhModel.hpp

class DetectPointMaxNonZeroNbhModel : public NodeDataModel
#include <DetectPointMaxNonZeroNbhModel.hpp>

The DetectPointMaxNonZeroNbhModel class is designed to analyse the non-zero neighborhood around the given points. It returns the coordinates of the point, which has the minimal number of non-zero pixels in the neighborhood. Inputs: 0: is a black and white image 1: a vector of the type VecVec3Data Parameters: neighborhood radius Outputs: 0: a point of the type PointData.

Public Functions

DetectPointMaxNonZeroNbhModel()

Constructor.

virtual ~DetectPointMaxNonZeroNbhModel()

Destructor.

QString caption() const

This function returns the module’s caption.

QString name() const

This function returns the module’s name.

std::unique_ptr<NodeDataModel> clone() const

This function returns a unique pointer to the class.

virtual QString modelName() const

This function returns the model’s name.

unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports of this module.

Return
Parameters
  • portType: input or output

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the specific data type for input and output ports.

Return
Parameters
  • portType: input or output
  • portIndex: the correspondent port index

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns the pointer to the output data to the specific port.

Parameters
  • port: is the output port index

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when input data on the specific port of the module changes, e.g., when the port gets connected or disconnected.

Parameters
  • nodeData:
  • port:

QWidget *embeddedWidget()

This module has no embedded widget, i.e. the widget that is shown in the module itself.

Return

QWidget **toCentralViewWidget()

This function returns a pointer to the pointer to the Central Widget. It is called when the module is selected and the button “Show details” is clicked. Then the Flowscene is replaced with the Central widget.

QWidget **toSideViewWidget()

This function returns a pointer to the pointer to the Parameter widget, that is shown on the right side. It is called when the module is selected and the button “Show details” is clicked. Then the default parameter widget is replaced with this widget.

QString infoLabelText()

This function returns the info string for this module.

QJsonObject save() const

This function saves the parameters to the json object that will be saved to the json file.

void restore(QJsonObject const &p)

This function restores the parameters from the file.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Members

QWidget *_paramsWidget

This is a parameter widget.

QLineEdit *le1

This is a field where the neighborhood radius parameter is enetered by the user.

QPushButton *computeButton

This button starts the computation.

ImageViewer *viewWidget

This is a viewer widget, where the results are shown.

std::shared_ptr<CVMatData> _inSourceData

This is an input black and white image.

std::shared_ptr<VecVec3Data> _inCircleListData

This is list of points of the type VecVec3Data.

std::shared_ptr<PointData> _outPointData

This is the output point, which has the minimal non-zero neighborhood.

Private Slots

void compute()

This function does the processing of the points.

File Editor_tab.md

File FitRotatedShapeModel.cpp

File FitRotatedShapeModel.hpp

class FitRotatedShapeModel : public NodeDataModel
#include <FitRotatedShapeModel.hpp>

This class is designed to fit a specific shape to the image. At the moment only a hexagonal shape fitting is implemented/tested. The ideal polygon is built using the center of rotation and the radius. Then the polygon is rotated around the center clock-wise to N grad (with step 0.5 grad) according its rotational symmetry. The overlap with the original image is checked. The result with the maximal overlap is returned. Inputs: 0: Source image is a black and white image with some parts of a shape present. 1: A point (type PointData) for the center of the shape Outputs: 0: An image with the final polygon drawn. 1: A point which considered as the 0 vertex of the shape Parameters: Shape radius in pixels.

Public Functions

FitRotatedShapeModel()

Constructor.

virtual ~FitRotatedShapeModel()

Destructor.

QString caption() const

This function returns the module’s caption.

QString name() const

This function returns the module’s name.

std::unique_ptr<NodeDataModel> clone() const

This function returns a unique pointer to the class.

virtual QString modelName() const

This function returns the model’s name.

unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports of this module.

Return
Parameters
  • portType: input or output

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the specific data type for input and output ports.

Return
Parameters
  • portType: input or output
  • portIndex: the correspondent port index

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns the pointer to the output data to the specific port.

Parameters
  • port: is the output port index

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when input data on the specific port of the module changes, e.g., when the port gets connected or disconnected.

Parameters
  • nodeData:
  • port:

QWidget *embeddedWidget()

This module has no embedded widget, i.e. the widget that is shown in the module itself.

Return

QWidget **toCentralViewWidget()

This function returns a pointer to the pointer to the Central Widget. It is called when the module is selected and the button “Show details” is clicked. Then the Flowscene is replaced with the Central widget.

QString infoLabelText()

This function returns the info string for this module.

QWidget **toSideViewWidget()

This function returns a pointer to the pointer to the Parameter widget, that is shown on the right side. It is called when the module is selected and the button “Show details” is clicked. Then the default parameter widget is replaced with this widget.

QJsonObject save() const

This function saves the parameters to the json object that will be saved to the json file.

void restore(QJsonObject const &p)

This function restores the parameters from the file.

Public Slots

void compute()

In this function the computations are executed.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Functions

void fitShape(int numVert, cv::Point center, int radius, Mat &finalShape, cv::Point &p)

fitShape this function rotates the given shape with the step of N grad and checks the overlap with the original image

Parameters
  • numVert: is the number of vertices in the ideal polygon
  • center: is the center of of the ideal polygon
  • radius: is the radius of the ideal polygon in pixels
  • finalShape: is the image with the final shape drawn. It will be returned as OutData
  • p: is the first vertex of the polygon, which lies on the x axis Point(detailCenter.x+detailRadius*cos(0), detailCenter.y+detailRadius*sin(0));

Private Members

QWidget *propsWidget

propsWidget is the parameter widget

QVBoxLayout *vblayout

vblayout is the layout in the parameter widget

QComboBox *shapeCombo

shapeCombo is the combobox to choose the shape. Now only hexagon is implemented.

QLineEdit *radiusValue

radiusValue is the field for the radius value

QPushButton *button

button is the button to start the fitting

QLabel *label

label is the shape radius label

ImageViewer *viewWidget

viewWidget shows the result

std::shared_ptr<NodeData> _inSourceData

_inSourceData is the source black and white image

std::shared_ptr<NodeData> _inCenterPointData

_inCenterPointData is the center of the ideal polygon in the image

std::shared_ptr<NodeData> _outResultData

_outResultData is the result shown in the image

std::shared_ptr<NodeData> _outResultVertex1Data

_outResultVertex1Data is the first vertex of the final polygon

File GUI1.md

File General.md

File GrayThreshModel.cpp

File GrayThreshModel.hpp

class GrayThreshModel : public NodeDataModel
#include <GrayThreshModel.hpp>

The InRangeModel class is designed for color thresholding in the HSV color space. Inputs: 0: Input RGB image Outputs: 0: Output mask image Parameters: Ranges for the Hue (H): [0,179], Saturation (S): [0,255], and Value (V): [0, 255].

Public Functions

GrayThreshModel()

Constructor.

virtual ~GrayThreshModel()

Destructor.

QString caption() const

This function returns the module caption.

QString name() const

This function returns the module name.

std::unique_ptr<NodeDataModel> clone() const

This function returns a unique pointer to the module.

virtual QString modelName() const

This function returns the model name.

unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports. There are 1 input and 1 output ports in this module.

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the data types of input and output ports. Input 0: Image of CVMatData type; Output 0: Image of CVMatData type;.

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data.

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when the status of the input data has changed.

QWidget *embeddedWidget()

This function returns a pointer to the embedded widget. This module has no embedded widget.

QWidget **toCentralViewWidget()

This function returns a pointer to pointer to the central widget.

QWidget **toSideViewWidget()

This function returns a pointer to pointer to the parameter widget.

QJsonObject save() const

This function saves the parameters of the module.

void restore(QJsonObject const &p)

This function restores the parameters of the module from the JsonObject.

Parameters
  • p: is the JsonObject

QString infoLabelText()

This function returns the information about on how to use the module.

Public Slots

void compute()

This function executes the thresholding.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Members

std::shared_ptr<NodeData> _inSourceData

_inSourceData is the input image

std::shared_ptr<NodeData> _outResultData

_outResultData is the output image

cv::Mat view_result

This result image is shown in the central widget.

QWidget *propsWidget

This is parameter widget.

QFormLayout *layout

This is a parameter widget layout.

QVBoxLayout *vblayout

This is a parameter widget layout.

QSpinBox *hueMin

This field selects the minimal Hue.

QPushButton *button
QLabel *label

This is a preview label.

ImageViewer *viewWidget

This is the central widget.

File ImageArithmeticModel.cpp

File ImageArithmeticModel.hpp

class ImageArithmeticModel : public NodeDataModel
#include <ImageArithmeticModel.hpp>

The ImageArithmeticModel class implements the binary image arithmetic: AND, OR, XOR, Minus. Parameters: binary operation Inputs: 0 - Image 1 - Image Outputs: 0 - Result for image arithmetic.

Public Functions

ImageArithmeticModel()

Constructor.

virtual ~ImageArithmeticModel()

Destructor.

QString caption() const

This function returns the module caption.

QString name() const

This function returns the module name.

std::unique_ptr<NodeDataModel> clone() const

This function returns a unique pointer to the module.

virtual QString modelName() const

This function returns the model name.

unsigned int nPorts(PortType portType) const

This fucntion returns the number of input and output ports. There are 2 input and 1 output ports in this module.

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This fucntion returns the data types of input and output ports. Input 0: Image of CVMatData type; Input 1: Image of CVMatData type; Output 0: Image of CVMatData type;.

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data.

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when the status of the input data has changed.

QWidget *embeddedWidget()

This function returns a pointer to the embedded widget. This module has no embedded widget.

QWidget **toCentralViewWidget()

This function returns a pointer to pointer to the central widget.

QWidget **toSideViewWidget()

This function returns a pointer to pointer to the parameter widget.

QJsonObject save() const

This function saves the module parameters.

void restore(QJsonObject const &p)

This function restores the module parameters.

QString infoLabelText()

This function returns the information about on how to use the module.

Public Slots

void compute()

This function is called for binary arithmetic operation on two input images.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Members

std::shared_ptr<NodeData> _inSourceData1

Input image.

std::shared_ptr<NodeData> _inSourceData2

Input image.

std::shared_ptr<NodeData> _outResultData

Output image.

cv::Mat view_result
QWidget *propsWidget

Parameter widget.

QFormLayout *layout

GUI elements.

QComboBox *combo

Combo box for arithmetic operations.

ImageViewer *viewWidget

Central widget.

File ImageLoaderModel.cpp

File ImageLoaderModel.hpp

class ImageLoaderModel : public NodeDataModel
#include <ImageLoaderModel.hpp>

This class is designed to load an image into memory and pass it further in processing pipeline. This class is a child of NodeDataModel (s. src/third_party/qnodeeditor). To load an image one needs to press a button ‘Open’ and select an image. If the module is the starting module in the monitoring pipeline, the output of the SceneIn module must be connect to the input port of this module. Inputs: 1 - Image - The output of the SceneInModule Output: 1 - Image.

Public Functions

ImageLoaderModel()

Constructor.

virtual ~ImageLoaderModel()

Destructor.

QString caption() const

This function returns the module caption.

QString name() const

This function returns the module name.

std::unique_ptr<NodeDataModel> clone() const

This function creates a clone of the module with unique pointer.

QJsonObject save() const

This function saves the module’s parameters, namely, the path to the opened image.

void restore(QJsonObject const &p)

This function restores the module’s parameters, namaly, the path to the image to be opened.

virtual QString modelName() const

This function returns the model’s name. It’s the same as caption.

unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports of the module.

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the data type of the input and output ports.

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data.

void setInData(std::shared_ptr<NodeData>, int)

This function is called when the status of the input port is changed.

QWidget *embeddedWidget()

This modul has no embedded widget.

QWidget **toCentralViewWidget()

This function returns a pointer to a pointer to the central widget. In the central widget the opened image is shown.

QWidget **toSideViewWidget()

This function returns a pointer to a pointer to the parameter widget. In the parameter widget the path to the image can be selected.

QString infoLabelText()

This function returns a help label of the module.

Public Slots

void openClicked()

This slot is called when the ‘Open’ button is clicked.

Private Members

QLabel *infoLabel

This is a help label that is shown in the parameter widget.

QLabel *_label

This label contains the filename.

QLabel *_lab1

This label contains the image preview.

ImageViewer *viewWidget

This is a central widget.

QWidget *propsWidget

This is parameters widget.

QPushButton *pushButton

This is the open button.

QVBoxLayout *layout
QString fileName

This is a filename of the image to be opened.

QPixmap _pixmap

This is input image in the pixmap format.

cv::Mat _mat

This is input image in the OpenCV::Mat format.

QString infoText

This is a info string of the module.

File ImageShowModel.cpp

File ImageShowModel.hpp

class ImageShowModel : public NodeDataModel
#include <ImageShowModel.hpp>

The ImageShowModel class is designed to display and save the input image. A right mouse click on the image saves the image as png file. The image is also passed further on the pipeline. Inputs: 0 - Image Outputs: 0 - Image.

Public Functions

ImageShowModel()

Constructor.

virtual ~ImageShowModel()

Destructor.

QString caption() const

This function returns the module caption.

QString name() const

This function returns the module name.

std::unique_ptr<NodeDataModel> clone() const

This function returns a unique pointer to the module.

virtual QString modelName() const

This function returns the model name.

unsigned int nPorts(PortType portType) const

This fucntion returns the number of input and output ports. There are 1 input and 1 output ports in this module.

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This fucntion returns the data types of input and output ports. Input 0: Image of CVMatData type; Output 0: Image of CVMatData type;.

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data.

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when the status of the input data has changed.

QWidget *embeddedWidget()

This function returns a pointer to the embedded widget. This module has no embedded widget.

QWidget **toCentralViewWidget()

This function returns a pointer to pointer to the central widget.

QWidget **toSideViewWidget()

On the parameter panel only the input image is shown.

QString infoLabelText()

This function returns the information about on how to use the module.

Protected Functions

bool eventFilter(QObject *object, QEvent *event)

eventFilter reacts on the right mouse click event

Private Members

QLabel *_label

This label contains the image preview.

std::shared_ptr<NodeData> _nodeData

Input image.

File ImageTemplateMatchModel.cpp

File ImageTemplateMatchModel.hpp

class ImageTemplateMatchModel : public NodeDataModel
#include <ImageTemplateMatchModel.hpp>

The ImageTemplateMatchModel class is designed for pattern matching based on crosscorrelation. Inputs: 0: Input image 1: Template image, which is usually smaller than the input image. 2: (optional) Search rectangle to look for the template image in the input image. Outputs: 0: The image, which is the most similar to the template image, found in the input image. 1: Rectangle, which shows the position of the found image in the input image 2: Maximal similarity value.

Public Functions

ImageTemplateMatchModel()

Constructor.

virtual ~ImageTemplateMatchModel()

Destructor.

QString caption() const

This function returns the module caption.

QString name() const

This function returns the module name.

std::unique_ptr<NodeDataModel> clone() const

This function returns a unique pointer to the module.

virtual QString modelName() const

This function returns the model name.

unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports. There are 3 input and 3 output ports in this module.

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the data types of input and output ports. Input 0: Image of CVMatData type; Input 1: Image of CVMatData type; 2: Rectangle Output 0: Image of CVMatData type; Output 1: Rectangle of RectData Type Output 2: Decimal values of DecimalData type.

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data.

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when the status of the input data has changed.

QWidget *embeddedWidget()

This function returns a pointer to the embedded widget. This module has no embedded widget.

QWidget **toCentralViewWidget()

This function returns a pointer to pointer to the central widget.

QWidget **toSideViewWidget()

This function returns a pointer to pointer to the parameter widget.

QString infoLabelText()

This function returns the information about on how to use the module.

Protected Functions

void compute()

This function calls the template matching and forms the output.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Members

std::shared_ptr<NodeData> _inSourceData

Input image.

std::shared_ptr<NodeData> _inTemplateData

Input template.

std::shared_ptr<NodeData> _inSearchRectData

Search rectangle.

std::shared_ptr<DecimalData> _outSimilarityValue

Maximal similarity value.

std::shared_ptr<NodeData> _outResultData

Output image.

std::shared_ptr<RectData> _outResultRectData

Output rectangle.

cv::Mat view_result

This result image is shown in the central wiget.

QWidget *propsWidget

Parameter widget.

QFormLayout *layout

Parameter widget layout.

QLabel *templImgLabel

Template image is shown in this label.

QLabel *simValLabel

The maximal similarity value is shown in this label.

QLabel *rectLabel

The rectangle of the template location in the input image is shown in this label.

ImageViewer *viewWidget

This is the central widget.

File ImgOverlayModel.cpp

File ImgOverlayModel.hpp

class ImgOverlayModel : public NodeDataModel
#include <ImgOverlayModel.hpp>

The ImgOverlayModel class is designed to overlay one image over the other and show the results. The input images (Input0 and Input1) can be either of the same size or of the different size and then the rectangle is provided, which defines the position of the Input1 in the Input0. If no rectangle is given, the images are assumed to be of the same size. Inputs: 0: Image 1: Image 2: Rectangle Outputs: 0: The result overlay.

Public Functions

ImgOverlayModel()

Constructor.

virtual ~ImgOverlayModel()

Destructor.

QString caption() const

This function returns the module caption.

QString name() const

This function returns the module name.

std::unique_ptr<NodeDataModel> clone() const

This function returns a unique pointer to the module.

virtual QString modelName() const

This function returns the model name.

unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports. There are 3 input and 1 output ports in this module.

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the data types of input and output ports. Input 0: Image of CVMatData type; Input 1: Image of CVMatData type; 2: Rectangle Output 0: Image of CVMatData type;.

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data.

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when the status of the input data has changed.

QWidget *embeddedWidget()

This function returns a pointer to the embedded widget. This module has no embedded widget.

QWidget **toCentralViewWidget()

This function returns a pointer to pointer to the central widget.

QWidget **toSideViewWidget()

This function returns a pointer to pointer to the parameter widget. This module has no parameter widget.

QString infoLabelText()

This function returns the information about on how to use the module.

Public Slots

void compute()

This function executes the overlay of input images and forms the output.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Members

ImageViewer *viewWidget

Viewer widget.

std::shared_ptr<NodeData> _inSource1Data

Input Image 0.

std::shared_ptr<NodeData> _inSource2Data

Input Image 1.

std::shared_ptr<NodeData> _inRectData

Input Rectangle.

std::shared_ptr<NodeData> _outResultData

Output overlay image.

File InModel.cpp

File InModel.hpp

class InModel : public NodeDataModel, public BaseInNodeDataModel
#include <InModel.hpp>

The InModel class is a starting module in each scene required for integration of the flow file into the monitoring mechanism.

Public Functions

InModel()

Constructor.

virtual ~InModel()

Desctructor.

QString caption() const

This function returns module caption.

Return

QString name() const

This function returns module name.

Return

std::unique_ptr<NodeDataModel> clone() const

This function returns a unique pointer to the module.

Return

void execute(cv::Mat &im)

This function executes the scene for the given image.

Parameters
  • im: is a cv::Mat image which is passed through the scene.

virtual QString modelName() const

This function returns the model name.

Return

unsigned int nPorts(PortType portType) const

This function returns the number of input or output ports of the current module.

Return
Parameters
  • portType: is input or output.

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the data type of input and output ports.

Return
Parameters
  • portType:
  • portIndex:

std::shared_ptr<NodeData> outData(PortIndex port)

This functions returns a pointer to the output data of the module.

Return
Parameters
  • port:

void setInData(std::shared_ptr<NodeData>, int)

This function is called when the input data is changed. This module has no input ports.

QWidget *embeddedWidget()

This module has no embedded widget.

Return

QWidget **toCentralViewWidget()

This module has no central widget.

Return

QWidget **toSideViewWidget()

This module has no parameter widget.

Return

QString infoLabelText()

Private Members

QPixmap _pixmap

Input image as pixmap.

cv::Mat _mat

Input image as cv::Mat.

File InRangeModel.cpp

File InRangeModel.hpp

class InRangeModel : public NodeDataModel
#include <InRangeModel.hpp>

The InRangeModel class is designed for color thresholding in the HSV color space. Inputs: 0: Input RGB image Outputs: 0: Output mask image Parameters: Ranges for the Hue (H): [0,179], Saturation (S): [0,255], and Value (V): [0, 255].

Public Functions

InRangeModel()

Constructor.

virtual ~InRangeModel()

Destructor.

QString caption() const

This function returns the module caption.

QString name() const

This function returns the module name.

std::unique_ptr<NodeDataModel> clone() const

This function returns a unique pointer to the module.

virtual QString modelName() const

This function returns the model name.

unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports. There are 1 input and 1 output ports in this module.

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the data types of input and output ports. Input 0: Image of CVMatData type; Output 0: Image of CVMatData type;.

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data.

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when the status of the input data has changed.

QWidget *embeddedWidget()

This function returns a pointer to the embedded widget. This module has no embedded widget.

QWidget **toCentralViewWidget()

This function returns a pointer to pointer to the central widget.

QWidget **toSideViewWidget()

This function returns a pointer to pointer to the parameter widget.

QJsonObject save() const

This function saves the parameters of the module.

void restore(QJsonObject const &p)

This function restores the parameters of the module from the JsonObject.

Parameters
  • p: is the JsonObject

QString infoLabelText()

This function returns the information about on how to use the module.

Public Slots

void compute()

This function executes the thresholding.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Members

std::shared_ptr<NodeData> _inSourceData

_inSourceData is the input image

std::shared_ptr<NodeData> _outResultData

_outResultData is the output image

cv::Mat view_result

This result image is shown in the central widget.

QWidget *propsWidget

This is parameter widget.

QFormLayout *layout

This is a parameter widget layout.

QVBoxLayout *vblayout

This is a parameter widget layout.

QSpinBox *hueMin

This field selects the minimal Hue.

QSpinBox *saturationMin

This field selects the minimal Saturation.

QSpinBox *valueMin

This field selects the minimal Value.

QSpinBox *hueMax

This field selects the maximal Hue.

QSpinBox *saturationMax

This field selects the maximal Saturation.

QSpinBox *valueMax

This field selects the maximal value.

QPushButton *button

This button starts the computation.

QLabel *label

This is a preview label.

ImageViewer *viewWidget

This is the central widget.

File InvertIntensityModel.cpp

File InvertIntensityModel.hpp

class InvertIntensityModel : public NodeDataModel
#include <InvertIntensityModel.hpp>

The InvertIntensityModel class is designed to invert intensities of the given image. Inputs: 0: Original image Outputs: 0: Inverted image.

Public Functions

InvertIntensityModel()

Constructor.

virtual ~InvertIntensityModel()

Destructor.

QString caption() const

This function returns module caption.

Return

QString name() const

This function returns Module Name.

Return

std::unique_ptr<NodeDataModel> clone() const

This function returns the unique pointer to the class.

Return

virtual QString modelName() const

This function returns the model name.

Return

unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports of this module.

Return
Parameters
  • portType: input or output

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the specific data type for input and output ports.

Return
Parameters
  • portType: input or output
  • portIndex: the correspondent port index

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data from the given port.

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when input data on the specific port of the module changes, e.g., when the port gets connected or disconnected.

Parameters
  • nodeData:
  • port:

QWidget *embeddedWidget()

This module has no embedded widget, i.e. the widget that is shown in the module itself.

Return

QWidget **toCentralViewWidget()

This function returns a pointer to the pointer to the Central Widget.

QWidget **toSideViewWidget()

This function returns a pointer to the pointer to the Parameter widget, that is shown on the right side. It is called when the module is selected and the button “Show details” is clicked. Then the default parameter widget is replaced with this widget.

QString infoLabelText()

This function returns the info string for this module.

Private Members

ImageViewer *viewWidget

This is the central widget.

std::shared_ptr<NodeData> _inSourceData

This is the input data.

std::shared_ptr<NodeData> _outResultData

This is the output data.

File LogStackSingleton.cpp

File LogStackSingleton.hpp

class LogStackSingleton
#include <LogStackSingleton.hpp>

This is a singleton class that collects information from all modules about failure in execution. The information is then shown in the output monitoring result.

Public Functions

virtual ~LogStackSingleton()

Public Members

std::deque<std::pair<std::string, std::string>> messages

This is the message deque, it contains the module name and the failure information.

Public Static Functions

LogStackSingleton &getInstance()

This function returns the instance of the singleton.

Private Functions

LogStackSingleton()
LogStackSingleton(const LogStackSingleton &src)
LogStackSingleton &operator=(const LogStackSingleton &rhs)

Private Static Attributes

std::unique_ptr<LogStackSingleton> m_instance

This is the instance of the class.

std::once_flag m_onceFlag

This flag shows if the class instance was created.

File MinEnclosingCircleModel.cpp

File MinEnclosingCircleModel.hpp

class MinEnclosingCircleModel : public NodeDataModel
#include <MinEnclosingCircleModel.hpp>

The MinEnclosingCircleModel class is designed to build the minimal enclosing circle around the given points. Inputs: 0: Input image (can be color or bw) Outputs: 0: Circle radius (Decimal data) 1: Circle center (Point data)

Public Functions

MinEnclosingCircleModel()

Constructor.

virtual ~MinEnclosingCircleModel()

Destructor.

QString caption() const

This function returns module caption.

Return

QString name() const

This function returns Module Name.

Return

std::unique_ptr<NodeDataModel> clone() const

This function returns the unique pointer to the class.

Return

virtual QString modelName() const

This function returns the model name.

Return

unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports of this module.

Return
Parameters
  • portType: input or output

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the specific data type for input and output ports.

Return
Parameters
  • portType: input or output
  • portIndex: the correspondent port index

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data from the given port.

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when input data on the specific port of the module changes, e.g., when the port gets connected or disconnected.

Parameters
  • nodeData:
  • port:

QWidget *embeddedWidget()

This module has no embedded widget, i.e. the widget that is shown in the module itself.

Return

QWidget **toCentralViewWidget()

This function returns a pointer to the pointer to the Central Widget. It is called when the module is selected and the button “Show details” is clicked. Then the Flowscene is replaced with the Central widget.

QWidget **toSideViewWidget()

This function returns a pointer to the pointer to the Parameter widget, that is shown on the right side.

QString infoLabelText()

This function returns the info string for this module.

Public Slots

void compute()

This function is responsible for all image processing in this module.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Members

std::shared_ptr<NodeData> _inSourceData

Input data.

std::shared_ptr<DecimalData> _outRadiusData

Output circle radius.

std::shared_ptr<PointData> _outCenterData

Output circle center.

cv::Mat view_result

This result image is shown in the central widget.

ImageViewer *viewWidget

Central widget.

File Monitor_tab.md

File MorphologyModel.cpp

File MorphologyModel.hpp

class MorphologyModel : public NodeDataModel
#include <MorphologyModel.hpp>

The MorphologyModel class is designed to perform morphological operations accoring to the selected operation and the given kernel size. The kernel shape is morphological rect. Inputs: 0: Image Outputs: 0: Result image Parameters: Kernel width, kernel height, operation (erosion, dilation, opening, closing)

Public Functions

MorphologyModel()

Constructor.

virtual ~MorphologyModel()

Destructor.

QString caption() const

This function returns module caption.

Return

QString name() const

This function returns Module Name.

Return

std::unique_ptr<NodeDataModel> clone() const

This function returns the unique pointer to the class.

Return

virtual QString modelName() const

This function returns the model name.

Return

unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports of this module.

Return
Parameters
  • portType: input or output

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the specific data type for input and output ports.

Return
Parameters
  • portType: input or output
  • portIndex: the correspondent port index

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data from the given port.

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when input data on the specific port of the module changes, e.g., when the port gets connected or disconnected.

Parameters
  • nodeData:
  • port:

QWidget *embeddedWidget()

This module has no embedded widget, i.e. the widget that is shown in the module itself.

Return

QWidget **toCentralViewWidget()

This function returns a pointer to the pointer to the Central Widget. It is called when the module is selected and the button “Show details” is clicked. Then the Flowscene is replaced with the Central widget.

QString infoLabelText()

This function returns the info string for this module.

QWidget **toSideViewWidget()

This function returns a pointer to the pointer to the Parameter widget, that is shown on the right side. It is called when the module is selected and the button “Show details” is clicked. Then the default parameter widget is replaced with this widget.

QJsonObject save() const

This function saves the module parameters to json object.

void restore(QJsonObject const &p)

This function restores the parameters from the json object.

Parameters
  • p: is the reference to the json object

Public Slots

void compute()

This function is responsible for all image processing in this module.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Members

QWidget *propsWidget

Parameter widget.

QVBoxLayout *vblayout

Parameter widget layout.

QFormLayout *flayout

Parameter widget layout.

QComboBox *operationCombo

Morphology operation combobox.

QSpinBox *widthValue

Kernel width value.

QSpinBox *heightValue

Kernel height value.

QPushButton *button

Update button.

ImageViewer *viewWidget

Central widget.

std::shared_ptr<NodeData> _inSourceData

Input image.

std::shared_ptr<NodeData> _outResultData

Output image.

File NumberDisplayDataModel.cpp

File NumberDisplayDataModel.hpp

class NumberDisplayDataModel : public NodeDataModel
#include <NumberDisplayDataModel.hpp>

The NumberDisplayDataModel class is designed to display the input decimal number. Inputs: 0: Decimal number Outputs: None.

Subclassed by RectDisplayDataModel, RectSourceDataModel

Public Functions

NumberDisplayDataModel()

Constructor.

virtual ~NumberDisplayDataModel()

Destructor.

QString caption() const

This function returns module caption.

Return

QString name() const

This function returns Module Name.

Return

std::unique_ptr<NodeDataModel> clone() const

This function returns the unique pointer to the class.

Return

unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports of this module.

Return
Parameters
  • portType: input or output

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the specific data type for input and output ports.

Return
Parameters
  • portType: input or output
  • portIndex: the correspondent port index

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data from the given port.

void setInData(std::shared_ptr<NodeData> data, int)

This function is called when input data on the specific port of the module changes, e.g., when the port gets connected or disconnected.

Parameters
  • nodeData:
  • port:

QWidget *embeddedWidget()

This module has no embedded widget, i.e. the widget that is shown in the module itself.

Return

QWidget **toCentralViewWidget()

This function returns a pointer to the pointer to the Central Widget. It is called when the module is selected and the button “Show details” is clicked. Then the Flowscene is replaced with the Central widget.

QWidget **toSideViewWidget()

This function returns a pointer to the pointer to the Parameter widget, that is shown on the right side. It is called when the module is selected and the button “Show details” is clicked. Then the default parameter widget is replaced with this widget.

NodeValidationState validationState() const

This function returns the validation state of the module.

QString validationMessage() const

This function returns the validation message of the module.

QString infoLabelText()

This function returns the info string for this module.

Private Members

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QStringLiteral("Missing or incorrect inputs")
QLabel *_label

This label shows the input decimal number.

File NumberSourceDataModel.cpp

File NumberSourceDataModel.hpp

class NumberSourceDataModel : public NodeDataModel
#include <NumberSourceDataModel.hpp>

The NumberSourceDataModel class is designed to input a decimal number and pass it further to the scene as decimal data. Inputs: None Outputs: 0: Decimal data Parameters: Text field to enter the number.

Public Functions

NumberSourceDataModel()

Constructor.

virtual ~NumberSourceDataModel()

Destructor.

QString caption() const

This function returns module caption.

Return

QString name() const

This function returns Module Name.

Return

std::unique_ptr<NodeDataModel> clone() const

This function returns the unique pointer to the class.

Return

QJsonObject save() const

This function saves the input number to the json object.

void restore(QJsonObject const &p)

This function restores the input number from the json object.

unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports of this module.

Return
Parameters
  • portType: input or output

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the specific data type for input and output ports.

Return
Parameters
  • portType: input or output
  • portIndex: the correspondent port index

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data from the given port.

void setInData(std::shared_ptr<NodeData>, int)

This function is called when input data on the specific port of the module changes, e.g., when the port gets connected or disconnected.

Parameters
  • nodeData:
  • port:

QWidget *embeddedWidget()

This module has no embedded widget, i.e. the widget that is shown in the module itself.

Return

QWidget **toCentralViewWidget()

This function returns a pointer to the pointer to the Central Widget. It is called when the module is selected and the button “Show details” is clicked. Then the Flowscene is replaced with the Central widget.

QWidget **toSideViewWidget()

This function returns a pointer to the pointer to the Parameter widget, that is shown on the right side. It is called when the module is selected and the button “Show details” is clicked. Then the default parameter widget is replaced with this widget.

QString infoLabelText()

This function returns the info string for this module.

Private Members

std::shared_ptr<DecimalData> _number

This is the output decimal number.

QLineEdit *_lineEdit

This is the text field to enter the number.

Private Slots

void onTextEdited(QString const &string)

This slot reacts on the edited text in the text field.

File OtsuThresholdModel.cpp

File OtsuThresholdModel.hpp

class OtsuThresholdModel : public NodeDataModel
#include <OtsuThresholdModel.hpp>

The OtsuThresholdModel class implements automatic binary thresholding (Otsu’s method) of a grayscale image. Inputs: 0: Image Outputs: 0: Image.

Public Functions

OtsuThresholdModel()

Constructor.

virtual ~OtsuThresholdModel()

Destructor.

QString caption() const

This function returns module caption.

Return

QString name() const

This function returns module Name.

Return

std::unique_ptr<NodeDataModel> clone() const

This function returns the unique pointer to the class.

Return

virtual QString modelName() const

This function returns the model name.

Return

unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports of this module.

Return
Parameters
  • portType: input or output

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the specific data type for input and output ports.

Return
Parameters
  • portType: input or output
  • portIndex: the correspondent port index

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data from the given port.

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when input data on the specific port of the module changes, e.g., when the port gets connected or disconnected.

Parameters
  • nodeData:
  • port:

QWidget *embeddedWidget()

This module has no embedded widget, i.e. the widget that is shown in the module itself.

Return

QWidget **toCentralViewWidget()

This function returns a pointer to the pointer to the Central Widget. It is called when the module is selected and the button “Show details” is clicked. Then the Flowscene is replaced with the Central widget.

QWidget **toSideViewWidget()

This function returns a pointer to the pointer to the Parameter widget, that is shown on the right side. It is called when the module is selected and the button “Show details” is clicked. Then the default parameter widget is replaced with this widget.

Protected Functions

bool eventFilter(QObject *object, QEvent *event)
void compute()

This function is responsible for all image processing in this module.

QString infoLabelText()

This function returns the info string for this module.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Members

QLabel *_label

Result preview is shown in the label.

std::shared_ptr<NodeData> _inSourceData

Input image.

std::shared_ptr<NodeData> _outResultData

Output image.

ImageViewer *viewWidget

Central widget.

File OutModel.cpp

File OutModel.hpp

class OutModel : public NodeDataModel, public BaseOutNodeDataModel
#include <OutModel.hpp>

The OutModel class is the ending module for each scene required for integration of the flow file into the monitoring mechanism. Inputs: 0: Image - Template image 1: Image - ROI image 2: Image - Overlayed result image 3: Rectangle - Rectangle of the roi location 4: Vector of decimal values - vector of measurements 5: Vector of decimal values - vector of angles 6: Vector of decimal values - vector of angle axes Outputs: None Parameter: Measurement type:

  • Distance
  • Angle
  • Status Pixel to MM factor is active only when the distance measurement is selected.

Public Functions

OutModel()

Constructor.

virtual ~OutModel()

Desctructor.

QString caption() const

This function returns module caption.

Return

QString name() const

This function returns module name.

Return

std::unique_ptr<NodeDataModel> clone() const

This function returns a unique pointer to the module.

Return

QJsonObject save() const

This function saves the parameters to the json object.

Return

void restore(QJsonObject const &p)

This function restores the parameters from the json object.

Parameters
  • p: is the json object

boost::any getResult()

This function returns the result to the monitoring routine.

Return

virtual QString modelName() const

This function returns the model name.

Return

unsigned int nPorts(PortType portType) const

This function returns the number of input or output ports of the current module.

Return
Parameters
  • portType: is input or output.

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the data type of input and output ports.

Return
Parameters
  • portType:
  • portIndex:

std::shared_ptr<NodeData> outData(PortIndex port)

This functions returns a pointer to the output data of the module.

Return
Parameters
  • port: is the port index

void setInData(std::shared_ptr<NodeData>, int)

This function is called when the input data is changed.

QWidget *embeddedWidget()

This module has no embedded widget.

Return

QWidget **toCentralViewWidget()

This module has no central widget.

Return

QWidget **toSideViewWidget()

This function returns a pointer to the pointer to the parameter widget.

QString infoLabelText()

Public Slots

void lineEdit1Changed()

slot to activate the factor field

void comboChanged()

combo slot

Private Members

SceneResult sceneResult

Here the scene results are collected from the inputs.

QWidget *propsWidget

Parameter widget.

QFormLayout *layout

GUI elements.

QLineEdit *line1

GUI elements.

QLineEdit *line2

GUI elements.

QComboBox *combo1

GUI elements.

File PointData.hpp

class PointData : public NodeData
#include <PointData.hpp>

The PointData class is a data class that holds a cv::Point.

Public Functions

PointData()

Default constructor.

PointData(float const _x, float const _y)

Constructor from two coordinates.

Parameters
  • _x:
  • _y:

PointData(const Point &_p)

Constructor from a point.

Parameters
  • _p:

NodeDataType type() const

This function returns the type definition.

Return

cv::Point pt() const

This function returns a copy of the data.

Return

Private Members

Point p

p is the data field of type cv::Point

File PointFromVectorModel.cpp

File PointFromVectorModel.hpp

class PointFromVectorModel : public NodeDataModel
#include <PointFromVectorModel.hpp>

The PointFromVectorModel class is designed to extract a point from the vector of points by its index. The selected point is then drawn on the image and shown in the central widget. Usage: Enter a point index, press the button. If the index is out of range, nothing will be extracted. Inputs: 0: Input image 1: vector of points (VecVec3 Data) Outputs: 0: Point Data Parameters: Point index.

Public Functions

PointFromVectorModel()

Constructor.

virtual ~PointFromVectorModel()

Destructor.

QString caption() const

This function returns module caption.

Return

QString name() const

This function returns module Name.

Return

std::unique_ptr<NodeDataModel> clone() const

This function returns the unique pointer to the class.

Return

virtual QString modelName() const

This function returns the model name.

Return

unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports of this module.

Return
Parameters
  • portType: input or output

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the specific data type for input and output ports.

Return
Parameters
  • portType: input or output
  • portIndex: the correspondent port index

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data from the given port.

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when input data on the specific port of the module changes, e.g., when the port gets connected or disconnected.

Parameters
  • nodeData:
  • port:

QWidget *embeddedWidget()

This module has no embedded widget, i.e. the widget that is shown in the module itself.

Return

QWidget **toCentralViewWidget()

This function returns a pointer to the pointer to the Central Widget. It is called when the module is selected and the button “Show details” is clicked. Then the Flowscene is replaced with the Central widget.

QWidget **toSideViewWidget()

This function returns a pointer to the pointer to the Parameter widget, that is shown on the right side. It is called when the module is selected and the button “Show details” is clicked. Then the default parameter widget is replaced with this widget.

QJsonObject save() const

This function saves the parameters to the json object.

void restore(QJsonObject const &p)

This function restores the parameters from the json object.

QString infoLabelText()

This function returns the info string for this module.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Members

QWidget *_paramsWidget

Parameter widget.

QLineEdit *le1

Text field to enter index.

QPushButton *computeButton

update button

ImageViewer *viewWidget

Central widget.

std::shared_ptr<CVMatData> _inSourceData

Input image.

std::shared_ptr<VecVec3Data> _inCircleListData

Vector of points.

std::shared_ptr<PointData> _outPointData

Output point.

Private Slots

void compute()

This function is responsible for all image processing in this module.

File PointInROIToPointInImageModel.cpp

File PointInROIToPointInImageModel.hpp

class PointInROIToPointInImageModel : public NodeDataModel
#include <PointInROIToPointInImageModel.hpp>

The PointInROIToPointInImageModel class converts the coordinates of the given 2D point in the subimage to the coordinates of the complete image. The subimage is given as a rectangel from the complete image. The point is drawn in the central widget on the complete image. Inputs: 0: Input image 1: Point in the subimage coordinates. P_ROI(x,y) 2: Rectange which defines the location of the subimage in the complete image. Rect (x_r,y_r,w_r,h_r) Outputs: 0: Point in the image coordinates. P_Image(x+x_r,y+y_r)

Public Functions

PointInROIToPointInImageModel()

Constructor.

virtual ~PointInROIToPointInImageModel()

Destructor.

QString caption() const

This function returns module caption.

Return

QString name() const

This function returns module Name.

Return

std::unique_ptr<NodeDataModel> clone() const

This function returns the unique pointer to the class.

Return

virtual QString modelName() const

This function returns the model name.

Return

unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports of this module.

Return
Parameters
  • portType: input or output

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the specific data type for input and output ports.

Return
Parameters
  • portType: input or output
  • portIndex: the correspondent port index

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data from the given port.

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when input data on the specific port of the module changes, e.g., when the port gets connected or disconnected.

Parameters
  • nodeData:
  • port:

QWidget *embeddedWidget()

This module has no embedded widget, i.e. the widget that is shown in the module itself.

Return

QWidget **toCentralViewWidget()

This function returns a pointer to the pointer to the Central Widget. It is called when the module is selected and the button “Show details” is clicked. Then the Flowscene is replaced with the Central widget.

QWidget **toSideViewWidget()

This function returns a pointer to the pointer to the Parameter widget, that is shown on the right side. It is called when the module is selected and the button “Show details” is clicked. Then the default parameter widget is replaced with this widget.

QString infoLabelText()

This function returns the info string for this module.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Members

ImageViewer *viewWidget

Central widget.

std::shared_ptr<CVMatData> _inSourceData

Input image.

std::shared_ptr<PointData> _inPointData

Point in subimage coordinates.

std::shared_ptr<RectData> _inRectData

Subimage location.

std::shared_ptr<PointData> _outPointData

Output point in image coordinates.

Private Slots

void compute()

This function is responsible for all image processing in this module.

File RectData.hpp

class RectData : public NodeData
#include <RectData.hpp>

The RectData class is the data class that holds a cv::Rect.

Public Functions

RectData()

Default constructor.

RectData(cv::Rect const r)

Constructor with the given rect.

Parameters
  • r:

NodeDataType type() const

This function returns the data type.

Return

cv::Rect cvrect() const

This function returns a copy of the data.

Return

QString rectAsText() const

This function returns the data as QString.

Return

Private Members

cv::Rect rect

Rectangle data.

File RectDisplayDataModel.hpp

class RectDisplayDataModel : public NumberDisplayDataModel
#include <RectDisplayDataModel.hpp>

The RectDisplayDataModel class is designed to show the rectangle data as text and also split the rectangle data into 4 decimal numbers: x,y, width, height. Inputs: 0: Rectangle data Outputs: 0: x 1: y 2: width 3: height.

Public Functions

RectDisplayDataModel()

Constructor.

virtual ~RectDisplayDataModel()

Destructor.

QString caption() const

This function returns module caption.

Return

QString name() const

This function returns Module Name.

Return

std::unique_ptr<NodeDataModel> clone() const

This function returns the unique pointer to the class.

Return

QWidget *embeddedWidget()

This module has no embedded widget, i.e. the widget that is shown in the module itself.

Return

QWidget **toCentralViewWidget()

This module has no central widget.

Return

QWidget **toSideViewWidget()

This function returns pointer to the pointer to the parameter widget.

QString infoLabelText()

This function returns the information string of the module.

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the specific data type for input and output ports.

Return
Parameters
  • portType: input or output
  • portIndex: the correspondent port index

void setInData(std::shared_ptr<NodeData> data, int)

This function is called when input data on the specific port of the module changes, e.g., when the port gets connected or disconnected.

Parameters
  • nodeData:
  • port:

std::shared_ptr<NodeData> outData(PortIndex portIndex)
unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports of this module.

Return
Parameters
  • portType: input or output

NodeValidationState validationState() const

This function returns the module validation state.

QString validationMessage() const

This function returns the module validation message.

Private Members

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QStringLiteral("Missing or incorrect inputs")
QLabel *_label

Label field to show the rectangle data as text.

std::shared_ptr<DecimalData> x_ptr

Output x data.

std::shared_ptr<DecimalData> y_ptr

Output y data.

std::shared_ptr<DecimalData> w_ptr

Output width data.

std::shared_ptr<DecimalData> h_ptr

Output height data.

File RectSourceDataModel.hpp

class RectSourceDataModel : public NumberDisplayDataModel
#include <RectSourceDataModel.hpp>

The RectSourceDataModel class is designed to create rectangle data from four input decimal fields Inputs: 0: x 1: y 2: width 3: height Outputs: 0: rect data.

Public Functions

RectSourceDataModel()

Constructor.

virtual ~RectSourceDataModel()

Destructor.

QString caption() const

This function returns module caption.

Return

QString name() const

This function returns Module Name.

Return

std::unique_ptr<NodeDataModel> clone() const

This function returns the unique pointer to the class.

Return

QWidget *embeddedWidget()

This module has no embedded widget, i.e. the widget that is shown in the module itself.

Return

QWidget **toCentralViewWidget()

This module has no central widget.

Return

QWidget **toSideViewWidget()

This function returns a pointer to the pointer to the Parameter widget, that is shown on the right side. It is called when the module is selected and the button “Show details” is clicked. Then the default parameter widget is replaced with this widget.

QString infoLabelText()

This function returns the info string for this module.

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the specific data type for input and output ports.

Return
Parameters
  • portType: input or output
  • portIndex: the correspondent port index

void setInData(std::shared_ptr<NodeData> data, PortIndex portIndex)

This function is called when input data on the specific port of the module changes, e.g., when the port gets connected or disconnected.

Parameters
  • nodeData:
  • port:

std::shared_ptr<NodeData> outData(PortIndex portIndex)

This function returns a pointer to the output data from the given port.

unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports of this module.

Return
Parameters
  • portType: input or output

NodeValidationState validationState() const

This function returns the module validation state.

QString validationMessage() const

This function returns the module validation message.

Private Members

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QStringLiteral("Missing or incorrect inputs")
QLabel *_label

The created rectangle is shown as text in this label.

std::shared_ptr<DecimalData> _inX_ptr

Input X data.

std::shared_ptr<DecimalData> _inY_ptr

Input Y data.

std::shared_ptr<DecimalData> _inW_ptr

Input Width data.

std::shared_ptr<DecimalData> _inH_ptr

Input Height data.

std::shared_ptr<RectData> _outRect_ptr

Output rectangle data.

File SceneResult.cpp

File SceneResult.hpp

struct SceneResult
#include <SceneResult.hpp>

This structure is filled by the output module in the flow diagram.

Public Functions

bool isInit()

This function shows if the scene has changed its status during the execution.

Return

void init()

This function initializes the scene result, i.e., clears the vectors and sets the flag to -99.

cv::Point getInfoPoint()

This function returns a point from resultRect. On this point the result string will be printed out.

Return
cv::Point

Public Members

float templateSimilarity = 0.0

Maximal similarity value is defined the the Template matcher.

cv::Mat templImage

Template image.

cv::Mat roiImage

Region of interest (ROI) image that is the most similar region to the templImage that is found in the currentImage.

cv::Mat finalOverlay

Final overlay image is the image that is shown after the monitoring is executed.

cv::Rect resultRect

The result measurement information text will be shown below this rectangle.

std::vector<float> measurement_mm

Vector with measurements.

std::vector<float> angle_grad

Vector with angles.

std::vector<int> angle_axis

Vector with angle axes.

std::vector<int> x_center

Vectors with x coordinates of some measurement (e.g. for angle detection 2 line segments must be provided)

std::vector<int> y_center

Vectors with y coordinates of some measurement.

std::string messageLine

Text line.

std::string messageLine2 =""

Another text line.

bool executionStatus

Execution status.

int isOK = -99

This flag is changed during the scene execution, if something went wrong.

File SelectROIModel.cpp

File SelectROIModel.hpp

class SelectROIModel : public NodeDataModel
#include <SelectROIModel.hpp>

The SelectROIModel class is designed to select a region of interest (ROI) from the input image. To pass the selected ROI to the output, the image must be double clicked. Inputs: 0: Image Outputs: 0: Image.

Public Functions

SelectROIModel()

Constructor.

virtual ~SelectROIModel()

Destructor.

QString caption() const

This function returns module caption.

Return

QString name() const

This function returns module Name.

Return

std::unique_ptr<NodeDataModel> clone() const

This function returns the unique pointer to the class.

Return

virtual QString modelName() const

This function returns the model name.

Return

unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports of this module.

Return
Parameters
  • portType: input or output

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the specific data type for input and output ports.

Return
Parameters
  • portType: input or output
  • portIndex: the correspondent port index

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data from the given port.

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when input data on the specific port of the module changes, e.g., when the port gets connected or disconnected.

Parameters
  • nodeData:
  • port:

QWidget *embeddedWidget()

This function returns the embedded widget.

QWidget **toCentralViewWidget()

This function returns a pointer to the pointer to the Central Widget. It is called when the module is selected and the button “Show details” is clicked. Then the Flowscene is replaced with the Central widget.

QWidget **toSideViewWidget()

This function returns a pointer to the pointer to the Parameter widget, that is shown on the right side. It is called when the module is selected and the button “Show details” is clicked. Then the default parameter widget is replaced with this widget.

QString infoLabelText()

This function returns the info string for this module.

Protected Functions

bool eventFilter(QObject *object, QEvent *event)

This event filter catches the double click events.

Return
Parameters
  • object:
  • event:

void compute()

The actual image cropping is done in this function.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Members

ImageCropper *cropper

Cropper class instance.

std::shared_ptr<NodeData> _inSourceImageData

Input image data.

std::shared_ptr<RectData> _outRectData

Output rectangle data.

std::shared_ptr<NodeData> _outResultImageData

Output ROI image data.

File Template_tab.md

File Tester_tab.md

File ToGrayscaleModel.cpp

File ToGrayscaleModel.hpp

class ToGrayscaleModel : public NodeDataModel
#include <ToGrayscaleModel.hpp>

The OtsuThresholdModel class implements automatic binary thresholding (Otsu’s method) of a grayscale image. Inputs: 0: Image Outputs: 0: Image.

Public Functions

ToGrayscaleModel()

Constructor.

virtual ~ToGrayscaleModel()

Destructor.

QString caption() const

This function returns module caption.

Return

QString name() const

This function returns module Name.

Return

std::unique_ptr<NodeDataModel> clone() const

This function returns the unique pointer to the class.

Return

virtual QString modelName() const

This function returns the model name.

Return

unsigned int nPorts(PortType portType) const

This function returns the number of input and output ports of this module.

Return
Parameters
  • portType: input or output

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the specific data type for input and output ports.

Return
Parameters
  • portType: input or output
  • portIndex: the correspondent port index

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data from the given port.

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when input data on the specific port of the module changes, e.g., when the port gets connected or disconnected.

Parameters
  • nodeData:
  • port:

QWidget *embeddedWidget()

This module has no embedded widget, i.e. the widget that is shown in the module itself.

Return

QWidget **toCentralViewWidget()

This function returns a pointer to the pointer to the Central Widget. It is called when the module is selected and the button “Show details” is clicked. Then the Flowscene is replaced with the Central widget.

QWidget **toSideViewWidget()

This function returns a pointer to the pointer to the Parameter widget, that is shown on the right side. It is called when the module is selected and the button “Show details” is clicked. Then the default parameter widget is replaced with this widget.

Protected Functions

bool eventFilter(QObject *object, QEvent *event)
void compute()

This function is responsible for all image processing in this module.

QString infoLabelText()

This function returns the info string for this module.

Protected Attributes

NodeValidationState modelValidationState = NodeValidationState::Warning
QString modelValidationError = QString("Missing or incorrect inputs")

Private Members

QLabel *_label

Result preview is shown in the label.

std::shared_ptr<NodeData> _inSourceData

Input image.

std::shared_ptr<NodeData> _outResultData

Output image.

ImageViewer *viewWidget

Central widget.

File TrainBinaryClassifierModel.cpp

File TrainBinaryClassifierModel.hpp

class TrainBinaryClassifierModel : public NodeDataModel
#include <TrainBinaryClassifierModel.hpp>

This class is designed for training a binary classifier (support vector machine) on VGG f8 features. The user must provide positive and negative examples. Then the classifier is trained and saves in the resources file. Later the trained classifier can be used for detection of damaged parts. By itself this module has no input or output ports.

Public Functions

TrainBinaryClassifierModel()

Constructor.

virtual ~TrainBinaryClassifierModel()

Destructor.

QString caption() const

This function returns the module caption.

Return

QString name() const

This function returns the module name.

Return

std::unique_ptr<NodeDataModel> clone() const

This function creates a pointer to a class object and returns it.

Return

virtual QString modelName() const

This function returns the model name.

Return

unsigned int nPorts(PortType portType) const

This function returns the number of input or output ports of the module.

Return
Parameters
  • portType: indicates if this is an input or output port.

NodeDataType dataType(PortType portType, PortIndex portIndex) const

This function returns the specific data type for input and output ports.

Return
Parameters
  • portType: is the type of the port (input or output)
  • portIndex: is the port index (starting from 0)

std::shared_ptr<NodeData> outData(PortIndex port)

This function returns a pointer to the output data.

Return

void setInData(std::shared_ptr<NodeData> nodeData, PortIndex port)

This function is called when the input data status changes.

QWidget *embeddedWidget()

This function returns a pointer to the embedded widget.

Return
nullptr, since this module has no embedded widget.

QWidget **toCentralViewWidget()

This function returns pointer to pointer to the central widget.

Return
nullptr, since this module has no central widget.

QWidget **toSideViewWidget()

This function returns pointer to pointer to the parameter widget.

Return

QString infoLabelText()

Public Slots

void compute()

This function does the actual training.

void providePosExamples()

This function sets the posDirName path, i.e., the path to the directrory with positive examples.

void provideNegExamples()

This function sets the negDirName path, i.e., the path to the directrory with negative examples.

Protected Functions

int getFeatureVectorsFromImages(std::string path_to_img, cv::dnn::Net &net, cv::Mat &training_data)

This helper function computes VGG f8 features from the images given in the path_to img. It uses the given network and fills in training data with features.

Return
It returns the number of processed images.

Private Members

QWidget *propsWidget

This is a parameter widget.

QGridLayout *layout

layout of the parameter widget

QPushButton *openPExampleButton

A button that opens a directory with positive examples.

QLabel *pExampleLabel

A label with the number of positive example images.

QPushButton *openNExampleButton

A button that opens a directory with negative examples.

QLabel *nExampleLabel

A label with the number of negative example images.

QPushButton *trainSaveButton

A button that calls compute function.

QLabel *trainedFileLabel

A label with the filename of the trained classifier.

QString posDirName

A string that holds that path of a directory with positive examples.

QString negDirName

A string that holds that path of a directory with negative examples.

File VecVec3Data.hpp

class VecVec3Data : public NodeData
#include <VecVec3Data.hpp>

The VecVec3Data class is a data class that holds a vector of cv::Vec3f. It is used to save, for instance, the list of circles with a central point (x,y) and the radius value (z) or a list of 3D points.

Public Functions

VecVec3Data()

Deafult constructor.

VecVec3Data(std::vector<cv::Vec3f> const _points)

Constructor that is initialized with a vector of points.

Parameters
  • _points:

NodeDataType type() const

This function returns that type of this data.

Return

std::vector<cv::Vec3f> pts() const

This function returns a copy of the vector of points.

Return

Private Members

std::vector<cv::Vec3f> points

points is the vector of cv::Vec3f

File VectorDecimalData.hpp

class VectorDecimalData : public NodeData
#include <VectorDecimalData.hpp>

The VectorDecimalData class is a data class that holds a std::vector<double>

Public Functions

VectorDecimalData()

Default constructor.

VectorDecimalData(std::vector<double> &in)

Constructor from a given vector.

Parameters
  • in: is a input vector of double

NodeDataType type() const

This function returns the data type.

Return

void addElement(float &el)

This function add an element to the vector.

std::vector<double> vector() const

This function returns a copy of the vector.

Return

void clear()

This function clears the vector.

Private Members

std::vector<double> _vector

_vector is a vector of double

File editorwidget.cpp

Functions

static void setFlowStyle()

File editorwidget.hpp

Functions

static std::shared_ptr<DataModelRegistry> registerDataModels()
class EditorWidget : public QMainWindow
#include <editorwidget.hpp>

The EditorWidget class is responsible for creation of flow diagrams (algorithms for image processing pipelines) and integrating them into the monitoring routines.

Public Functions

EditorWidget(QWidget *_parent = 0)

Constructor.

Public Slots

void selectionInSceneChanged()
void showDetailsOnClick()
void hideDetailsOnClick()
void saveforMonitoring()

Signals

void selectionRemoved()
void flowFileUpdated()

Private Members

QStackedWidget *centralWidget

This is central widget, where either the flow scene with the complete diagram or the output widget of a selected module are shown.

FlowView *view

This is flow view.

FlowScene *scene

This is Flow scene.

QWidget *paramWidget

Parameters widget.

QWidget *defaultDescriptionParamWidget

Default widget which is shown on the right when no module is selected.

QDockWidget *dock

Dock window with parameter widget.

QDockWidget *saveLoadSceneDock

Dock window, where the buttons and the scene name field are shown.

QPushButton button

Button on the default parameter widget.

QStateMachine machine

State machine to switch between the default parameter widget and the parameter widget of a selected module.

QVBoxLayout *layout

Layout of the default parameter widget.

QWidget **ppcurrentParamsWidget

Pointer to pointer to Parameter Widget, which is returned from the selected module.

QWidget **ppcurrentCentralWidget

Pointer to pointer to Central Widget, which is returned from the selected module.

QPushButton *saveScene

Button for scene saving.

QPushButton *loadScene

Button for scene loading.

QPushButton *clearScene

Button to remove all modules from the current scene.

QPushButton *saveSceneMonitoring

Button, which saves the scene for monitoring. For this, the unique scene name must be provided to sceneName.

QLineEdit *sceneName

Field for the unique scene name to be given by the user. The name must start with FLOW_.

File imagecropper.cpp

namespace

Functions

static bool anonymous_namespace{imagecropper.cpp}::isPointNearSide(const int _sideCoordinate, const int _pointCoordinate)

File imagecropper.hpp

Enums

enum CursorPosition

The CursorPosition enum In this enum the cursor positions are stored.

Values:

CursorPositionUndefined
CursorPositionMiddle
CursorPositionTop
CursorPositionBottom
CursorPositionLeft
CursorPositionRight
CursorPositionTopLeft
CursorPositionTopRight
CursorPositionBottomLeft
CursorPositionBottomRight
class ImageCropper : public QWidget
#include <imagecropper.hpp>

This class implements the selection of the image part by dragging a rectangle and cropping the image.

The part that is covered by the rectangle is cropped.

Public Functions

ImageCropper(QWidget *parent = 0)
~ImageCropper()
const QPixmap cropImage(QRectF &res)

This function crops the image.

Return
The cropped pixmap
Parameters
  • res: The real rectangle, where the image is cropped.

Public Slots

void setImage(const QPixmap &_image)

This function sets the image for cropping.

Parameters
  • _image: is a pixmap with the image

void setBackgroundColor(const QColor &_backgroundColor)

This functions sets the background color of the cropping widget.

Parameters
  • _backgroundColor: is set

void setCroppingRectBorderColor(const QColor &_borderColor)

setCroppingRectBorderColor

Parameters
  • _borderColor:

void setProportion(const QSizeF &_proportion)

This function sets the proportion for selection.

Parameters
  • _proportion:

void setProportionFixed(const bool _isFixed)

This function sets the fixed proportion for cropping.

Parameters
  • _isFixed:

Protected Functions

void paintEvent(QPaintEvent *_event)
void mousePressEvent(QMouseEvent *_event)
void mouseMoveEvent(QMouseEvent *_event)
void mouseReleaseEvent(QMouseEvent *_event)

Private Functions

CursorPosition getCursorPosition(const QRectF &_cropRect, const QPointF &_mousePosition)

getCursorPosition This function returns the cursor position

Return
Parameters
  • _cropRect:
  • _mousePosition:

void updateCursorIcon(const QPointF &_mousePosition)

updateCursorIcon This function updates the cursor icon according to the mouse position

Parameters
  • _mousePosition:

const QRectF calculateGeometry(const QRectF &_sourceGeometry, const CursorPosition _cursorPosition, const QPointF &_mouseDelta)
const QRectF calculateGeometryWithCustomProportions(const QRectF &_sourceGeometry, const CursorPosition _cursorPosition, const QPointF &_mouseDelta)
const QRectF calculateGeometryWithFixedProportions(const QRectF &_sourceGeometry, const CursorPosition _cursorPosition, const QPointF &_mouseDelta, const QSizeF &_deltas)

Private Members

QPixmap imageForCropping

Image for cropping.

QRectF croppingRect

Rectangle for cropping.

QRectF lastStaticCroppingRect

Last fixed cropping rectangle.

CursorPosition cursorPosition

The last cursor position.

bool isMousePressed

Is true when the left mouse button is pressed.

bool isProportionFixed

True if the cropping proportion fixed.

QPointF startMousePos

Starting position of mouse.

QSizeF proportion

Proportions.

QSizeF deltas

delta x and delta y

QColor backgroundColor

Background color.

QColor croppingRectBorderColor

Cropping rect grid color.

File imageviewer.cpp

File imageviewer.hpp

class ImageViewer : public QWidget
#include <imageviewer.hpp>

The ImageViewer class is for showing the image in a scrollbar. Usually an instance of this class is used as the central widget of each NodeModel class.

Public Functions

ImageViewer()

Constructor.

void setImage(const QPixmap &newImage)

This function puts the input image to the image label.

Private Members

QLabel *imageLabel

The image is shown in this label.

QScrollArea *scrollArea

This is a scroll area, where the image is placed.

QVBoxLayout *layout

This is the central layout of the widget.

double scaleFactor

File mainpage.md

File monitorbase.cpp

File monitorbase.hpp

struct MonitoringData
#include <monitorbase.hpp>

The MonitoringData struct holds all information for execution of monitoring, sending back the response, and displaying the results.

Public Members

boost::tuple<cv::Rect, float> detection_res

detection_res Rectangle of the found ROI and the similarity value

cv::Mat currImage

Current image that is processed.

cv::Mat templImage

Template image.

cv::Mat roiImage

Part of the current image that is similar to template image.

cv::Mat resImage

Result image with overlayed monitoring info.

std::string mInfo1

Message line 1.

std::string mInfo2

Message line 2.

cv::Point position

Position of the text on an image.

bool result

Monitoring result, boolean.

qcontrol_msgs::Monitoring mon_res

Message response for the monitoring request. It is filled dependent on the monitoring case.

std::string flowNameID

flowNameID ID string of the flow file

class MonitorBase
#include <monitorbase.hpp>

The MonitorBase class This is the base class for all monitoring cases.

Subclassed by MonitorElvezBlackBall, MonitorElvezBulbHolder, MonitorElvezLWRDrive, MonitorElvezScrew, MonitorFlow, MonitorHopu, MonitorLDTSpindleRotation, MonitorLDTSpindleSize, MonitorLDTStatorRotation, MonitorLDTStatorSize

Public Functions

MonitorBase()

Constructor.

virtual ~MonitorBase()

Destructor.

virtual void executeMonitoring() = 0

pure virtual function to execute monitoring.

virtual void executeTemplateMatching() = 0

pure virtual function to execute template matching

MonitoringData const &getMonitoringData() const

Accessor for the monitoring data.

Return

void setCurrentImage(cv::Mat &m)

This function sets the current image for monitoring.

Parameters
  • m: The current image is passed by reference.

void setFlowNameID(const std::string &id)

Public Static Functions

void read_templates(std::string path_to_templates)

This function reads templates from the file and arranges them into a vector of tuples.

void read_flow_list(std::vector<std::pair<std::string, std::string>> &v)

This function reads the resources/flows/flows.json and filles the vector.

Parameters
  • v: This vector of pairs is filled.

std::unique_ptr<MonitorBase> create_monitor(QString str)

Protected Attributes

MonitoringData mon_data

Monitoring data is hidden here.

Protected Static Attributes

std::vector<boost::tuple<int, int, int, int, int, bool, cv::Mat, cv::Mat>> templates_data

templates_data: a vector with the id and location (x,y,width, height) of the template, template image, and template mask if available

File monitorelvez.hpp

class MonitorElvezBlackBall : public MonitorBase
#include <monitorelvez.hpp>

The MonitorElvezBlackBall class This class implements the evaluation of the black ball status.

Public Functions

void executeMonitoring()

pure virtual function to execute monitoring.

void executeTemplateMatching()

pure virtual function to execute template matching

class MonitorElvezLWRDrive : public MonitorBase
#include <monitorelvez.hpp>

The MonitorElvezLWRDrive class This class implements the evaluation of the lwr drive status.

Public Functions

void executeMonitoring()

pure virtual function to execute monitoring.

void executeTemplateMatching()

pure virtual function to execute template matching

class MonitorElvezScrew : public MonitorBase
#include <monitorelvez.hpp>

The MonitorElvezScrew class This class implements the evaluation of the screw status.

Public Functions

void executeMonitoring()

pure virtual function to execute monitoring.

void executeTemplateMatching()

pure virtual function to execute template matching

class MonitorElvezBulbHolder : public MonitorBase
#include <monitorelvez.hpp>

The MonitorElvezBulbHolder class This class implements the evaluation of the bulb holder status.

Public Functions

void executeMonitoring()

pure virtual function to execute monitoring.

void executeTemplateMatching()

pure virtual function to execute template matching

File monitorelvezblackball.cpp

File monitorelvezbulbholder.cpp

File monitorelvezlwrdrive.cpp

File monitorelvezscrew.cpp

File monitorflow.cpp

File monitorflow.hpp

class MonitorFlow : public MonitorBase
#include <monitorflow.hpp>

The MonitorFlow class This class implements the general class for monitoring with flow diagrams.

Public Functions

void executeMonitoring()

pure virtual function to execute monitoring.

void executeTemplateMatching()

pure virtual function to execute template matching

File monitorhopu.cpp

Functions

double get_angle_new(cv::Mat labels, int blob_id)

File monitorhopu.hpp

class MonitorHopu : public MonitorBase
#include <monitorhopu.hpp>

The MonitorHopu class This class implements the evaluation of the boards.

Public Functions

void executeMonitoring()

pure virtual function to execute monitoring.

void executeTemplateMatching()

pure virtual function to execute template matching

File monitoring_client.cpp

Functions

int main(int argc, char **argv)

File monitoring_node.cpp

Functions

int main(int argc, char **argv)
class MonitoringNode

The MonitoringNode class This class provides the monitoring service and when the request arrives, it calls the correspondent MonitorBase child routines and sends back the monitoring response. Additionally, it is also a client of the Display service (s. qdisplayservicenode.hpp). The MonitoringNode sends the request for display to the display service.

Public Functions

MonitoringNode(int mode, std::string path_camera_or_imagefolder, std::string path_templ, int mon_case, std::string path_save)
void cameraStreamCallback(const sensor_msgs::ImageConstPtr &msg)

This function is a camera stream subsriber callback.

Parameters
  • msg: contains the pointer to the image from the camera.

bool monitoringCallback(qcontrol_msgs::QualityControl::Request &req, qcontrol_msgs::QualityControl::Response &res)

This function is a monitoring callback.

Return
Parameters
  • req: Request contains the flag showing if it is a flow diagram or a preprogrammed routine, and the IDName of the routine or flow diagram
  • res: Response contains the monitoring results

Private Members

ros::NodeHandle nh_

ROS Node Handle.

image_transport::ImageTransport it_

Image Transport.

image_transport::Subscriber image_sub_

Image subscriber.

ros::ServiceServer processInputImageServer_

ROS Server for providing the monitoring.

ros::ServiceClient clientViewImages_

ROS Client to view the images.

sensor_msgs::ImageConstPtr colorImagePtr

Pointer to color image that arrives from the camera.

bool newImageArrived

Bool flag showing if a new image was obtained from the camera.

std::unique_ptr<MonitorBase> monitoringRunner

A smart pointer to a MonitorBase child.

int mode
std::string path_to_images

This is a path to the folder, where the images are read from in the monitoring emulator mode.

std::string path_to_save

This is path where to save original images.

int mon_case

This is monitoring case (0 - ELVEZ, 1 - LDT), it is needed only to keep compatibility with old format of monitoring service call.

File monitoringwidget.cpp

Functions

QImage CVImgToPixmap(cv::Mat &img)

File monitoringwidget.hpp

class MonitoringWidget : public QWidget
#include <monitoringwidget.hpp>

This class is a widget, where the monitoring results are displayed.

Public Functions

MonitoringWidget(int argc, char **argv, QWidget *_parent = 0)

MonitoringWidget Constructor.

Parameters
  • argc: command line parameters are needed to initialize the display service node
  • argv:
  • _parent: parent window

~MonitoringWidget()

Public Slots

void loadNewImage()

loadNewImage slot is called when the signal imageupdated from the display service node is emitted

Private Members

QCheckBox *noImageSaveCheckBox
QLabel *m_ImageLabel
QLabel *m_TemplateLabel
QLabel *m_RoiLabel
cv::Mat currentImage
cv::Mat templImage
cv::Mat roiImage
QLabel *infoMsgLabel
QDisplayServiceNode qnode

File monitorldt.hpp

class MonitorLDTSpindleRotation : public MonitorBase
#include <monitorldt.hpp>

The MonitorLDTSpindleRotation class This class implements the evaluation of the orientation of the hexagonal spindle with respect to another line on the image. This line is drawn between two upper circle centers on the drive.

Public Functions

void executeMonitoring()

pure virtual function to execute monitoring.

void executeTemplateMatching()

pure virtual function to execute template matching

class MonitorLDTSpindleSize : public MonitorBase
#include <monitorldt.hpp>

The MonitorLDTSpindleSize class This class implements the spindle size evaluation for LDT.

Public Functions

void executeMonitoring()

pure virtual function to execute monitoring.

void executeTemplateMatching()

pure virtual function to execute template matching

class MonitorLDTStatorSize : public MonitorBase
#include <monitorldt.hpp>

The MonitorLDTStatorSize class This class implements the stator size evaluation for LDT.

Public Functions

void executeMonitoring()

pure virtual function to execute monitoring.

void executeTemplateMatching()

pure virtual function to execute template matching

class MonitorLDTStatorRotation : public MonitorBase
#include <monitorldt.hpp>

The MonitorLDTStatorRotation class This class implements the evaluation of the station orientation (angle to y axis in clockwise direction)

Public Functions

void executeMonitoring()

pure virtual function to execute monitoring.

void executeTemplateMatching()

pure virtual function to execute template matching

File monitorldtspindlerotation.cpp

File monitorldtspindlesize.cpp

File monitorldtstatorrotation.cpp

File monitorldtstatorsize.cpp

File opencv_wrap.hpp

namespace OPCV

OPCV namespace holds some wrapper functions for opencv-based routines

Functions

static void markROIImage(cv::Mat &_img, cv::Rect &_roi_rect, cv::Scalar &_color, cv::Mat &res_)

markROIImage This function draws a roi on an image in a semi-transparent way

Parameters
  • _img:
  • _roi_rect:
  • _color:
  • res_:

static boost::tuple<cv::Rect, float> detectTemplate(cv::Mat &_img, cv::Mat &_templ, cv::Rect &searchRect)
static void CLAHE_HistEq(cv::Mat &img_, cv::Mat &out_)
static void blurring(cv::Mat &in_, cv::Mat &out_, int size, int alg)
static void thresholding(cv::Mat &img_, cv::Mat &out_, int alg)
static cv::Scalar median(cv::Mat &image)
static void conversionColor(cv::Mat &in_, cv::Mat &out_, int alg)
static void autoCanny(cv::Mat &img_, cv::Mat &out_)
static std::vector<cv::Point> contoursConvexHull(std::vector<std::vector<cv::Point>> &contours, size_t index)
static void rotate(cv::Mat &src, cv::Mat &dst, double angle)

File polynomialregression.hpp

Functions

void polynom(std::vector<float> &x, std::vector<float> &coeffs, std::vector<float> &y)
template <class TYPE>
class PolynomialRegression
#include <polynomialregression.hpp>

Polynomial Regression class It aims to fit a non-linear relationship to a set of points. It approximates this by solving a series of linear equations using a least-squares approach.

We can model the expected value y as an nth degree polynomial, yielding the general polynomial regression model:

y = a0 + a1 * x + a2 * x^2 + … + an * x^n

Public Functions

PolynomialRegression()
virtual ~PolynomialRegression()
bool fitIt(const std::vector<TYPE> &x, const std::vector<TYPE> &y, const int &order, std::vector<TYPE> &coeffs)

File qcamerasubscribernode.cpp

File qcamerasubscribernode.hpp

class QCameraSubscriberNode : public QThread
#include <qcamerasubscribernode.hpp>

The QCameraSubscriberNode class is a separate thread which subscribes to the camera and obtains an image from it.

Public Functions

QCameraSubscriberNode(int argc, char **argv, std::string camera_stream_str)

QCameraSubscriberNode constructor.

Parameters
  • argc: commandline parameters for ros::init()
  • argv: commandline parameters for ros::init()
  • camera_stream_str: path to the camera node

~QCameraSubscriberNode()
bool init()

init This function initializes the ros node and subscribes to the camera

Return

void run()

run This function make the ros node spinOnce and sleep until a new Image arrives

const std::string &nodeName()

Public Members

sensor_msgs::ImageConstPtr colorImagePtr

colorImagePtr The message with the latest image

Signals

void rosShutdown()
void imageUpdated()

Protected Functions

void streamCallback(const sensor_msgs::ImageConstPtr &msg)

Protected Attributes

int init_argc
char **init_argv
const std::string node_name

Private Members

std::string path_to_camera
cv::Mat img
bool newImageArrived

File qdisplayservicenode.cpp

File qdisplayservicenode.hpp

class QDisplayServiceNode : public QThread
#include <qdisplayservicenode.hpp>

The QDisplayServiceNode class is a separate thread that advertizes the display service, which is called during the execution of the monitoring.

Public Functions

QDisplayServiceNode(int argc, char **argv)

QDisplayServiceNode constructor.

Parameters
  • argc: command line parameters are needed for ros::init
  • argv:

~QDisplayServiceNode()
bool init()

init This function initializes the ros node and advertizes the display service

Return

void run()
const std::string &nodeName()

Public Members

cv::Mat img_templ

img_templ CV::Mat Image Template

cv::Mat img_roi

img_roi CV::Mat Image Region of interest (the part of the image which is similar to the template)

cv::Mat img_res

img_res CV::Mat Resulting image, which is shown after the monitoring is finished

bool detailIntact

detailIntact Status of the detail; true is the detail is OK

std::string infoLine

infoLine, measureLine These strings are filled and shown on the resulting image

std::string measureLine
cv::Point p

p cv::Point position of the information strings on the resulting image. Usually, the point below bounding box of the ROI is shown.

int step

step The display is done in 3 steps: 1: The acquired image is shown 2: The template and the found roi images are shown 3: The monitoring result is placed on the acquired image

std::string save

Path to save the original images.

Signals

void rosShutdown()
void imageUpdated()

Protected Functions

bool showImagesCb(qcontrol_msgs::ImageViewing::Request &req, qcontrol_msgs::ImageViewing::Response &res)

This is a display service callback function.

Return
Parameters
  • req: Request
  • res: Response

Protected Attributes

int init_argc
char **init_argv
const std::string node_name
ros::ServiceServer serv

File templatetester_node.cpp

Functions

int main(int argc, char *argv[])

File templatewidget.cpp

File templatewidget.hpp

class TemplateWidget : public QWidget
#include <templatewidget.hpp>

This class is for selection and saving template images.

In this widget the selection of template images is done.

Public Functions

TemplateWidget(QWidget *_parent = 0)

Constructor

~TemplateWidget()

Destructor

Public Members

QCameraSubscriberNode *pqn

Pointer to the camera subscriber node

Private Members

ImageCropper *m_imageCropper
QLabel *m_croppedImage
QString templDir

Private Slots

void crop()
void openDir()
void openFile()
void grabImage()

File testerwidget.cpp

File testerwidget.hpp

class TesterWidget : public QWidget
#include <testerwidget.hpp>

This class is for testing the algorithms offline.

This widget is designed for testing hardcoded functions and flow diagrams on images. The images can be either taken from hard-drive or grabbed from the camera

Public Functions

TesterWidget(QWidget *_parent = 0)

TesterWidget constructor.

Parameters
  • _parent: is a parent window

~TesterWidget()
void setTemplateDir(const std::string &templ_path)

setTemplateDir: This function sets the path to the template directory

Parameters
  • templ_path: std::string path to the template directory

void openImageFile(const std::string &im_path)

openImageFile: This function sets path to the image file, which is opened

Parameters
  • im_path: std::string path to the image file

Public Members

QCameraSubscriberNode *pqn

pqn Pointer to the Subscriber node, which listens to the camera

Public Slots

void updateFlowList()

updateFlowList: This function updates the combobox list with the function names which can be called for testing.

Private Members

QLabel *m_ImageLabel

m_ImageLabel The QLabel for showing the original image

QLabel *m_TemplateLabel

m_TemplateLabel The QLabel for showing the template

QLabel *m_RoiLabel

m_RoiLabel The Qlabel for showing the template found in the original image

QLabel *m_templDirectoryLabel
QComboBox *comboOperations
QComboBox *comboTemplates
QVBoxLayout *layout
QHBoxLayout *buttonLayout
QVBoxLayout *imgLayout
QHBoxLayout *roiLayout
QPushButton *openFileBtn
QPushButton *grabImageBtn
QPushButton *setDirectorBtn
QPushButton *doProcessingBtn
std::unique_ptr<MonitorBase> monitoringRunner

The monitoring class. Its methods are called for image processing.

cv::Mat currentImage

Current image file that will be processed.

QString templDir

Path to the directory with Template images.

QString lastFPath

Path of the last opened file. Initially, it opens the home directory.

std::vector<std::pair<std::string, std::string>> v_flows

v_flows List of pairs flow_id and flow_filename

Private Slots

void setDir()

setDir slot for selection of the directory to save the templates

void openFile()

openFile slot for opening of an image for testing. The image is saved on hard drive.

void doDetection()

doDetection slot for testing of the selected algorithm on a chosen image.

void grabImage()

grabImage slot for grabbing the image from the camera. The image is grabbed from the camera. The settings for the camera path are given the resources/settings.json file