Classes | Enumerations | Functions
ipa_Utils Namespace Reference

Classes

class  UniqueNumber
 

Enumerations

enum  { RET_OK = 0x00000001UL, RET_FAILED = 0x00000002UL, RET_WARNING = 0x00000004UL }
 

Functions

template<typename Distance >
void ClusteringKMeanspp (int k, cv::Mat &dataset, int *indices, int indices_length, int *centers, int &centers_length, int numLocalTries=1)
 
unsigned long ConvertToShowImage (const cv::Mat &source, cv::Mat &dest, int channel=1, double min=-1, double max=-1)
 
unsigned long EvaluatePolynomial (double x, int degree, double *coefficients, double *y)
 
unsigned long FilterByAmplitude (cv::Mat &xyzImage, const cv::Mat &greyImage, cv::Mat *mask, cv::Mat *maskColor, float minMaskThresh, float maxMaskThresh)
 
unsigned long FilterSpeckles (cv::Mat &img, int maxSpeckleSize, double _maxDiff, cv::Mat &_buf)
 Description. More...
 
unsigned long FilterTearOffEdges (cv::Mat &xyzImage, cv::Mat *mask, float piHalfFraction=6)
 
cv::Vec3b GrayColorMap (double value, double min, double max)
 
unsigned long LoadMat (cv::Mat &mat, std::string filename, int type=CV_32F)
 
unsigned long MaskImage (const cv::Mat &source, cv::Mat &dest, const cv::Mat &mask, cv::Mat &destMask, float minMaskThresh=0, float maxMaskTresh=20000, int sourceChannel=1, double sourceMin=-1, double sourceMax=-1)
 
unsigned long SaveMat (cv::Mat &mat, std::string filename, int type=CV_32F)
 
template<class T >
std::vector< T > takeRandomN (const std::vector< T > &v, int n)
 
cv::Mat vstack (const std::vector< cv::Mat > &mats)
 

Enumeration Type Documentation

anonymous enum

An enum for the return values. This enum describes possible return values that are used to return failure or success.

Enumerator
RET_OK 

Everythings OK.

RET_FAILED 

Something went dramatically wrong.

RET_WARNING 

Something went wrong.

Definition at line 25 of file GlobalDefines.h.

Function Documentation

template<typename Distance >
void ipa_Utils::ClusteringKMeanspp ( int  k,
cv::Mat &  dataset,
int *  indices,
int  indices_length,
int *  centers,
int &  centers_length,
int  numLocalTries = 1 
)

Original implementation from OpenCV, hierarchical_clustering_index.h Chooses the initial centers in the k-means using the algorithm proposed in the KMeans++ paper: Arthur, David; Vassilvitskii, Sergei - k-means++: The Advantages of Careful Seeding

Definition at line 113 of file VisionUtils.h.

unsigned long ipa_Utils::ConvertToShowImage ( const cv::Mat &  source,
cv::Mat &  dest,
int  channel = 1,
double  min = -1,
double  max = -1 
)

Function to convert a 32 bit, n channel image into a eight bit, 1 channel image.

Parameters
sourceThe 32 bit, n channel source image
destThe resulting 8 bit, 1 channel image
channelThe channel of the source image to process
minMinimal value that is converted, smaller values are clipped to min
maxMaximal value that is converted, bigger values are clipped to max
Returns
Return code

Calculate minmal and maximal value within the specified image channel

Definition at line 264 of file VisionUtils.cpp.

unsigned long ipa_Utils::EvaluatePolynomial ( double  x,
int  degree,
double *  coefficients,
double *  y 
)

Evaluates a polynomial, calculated with FitPolynomial

Parameters
xThe function value
degreeThe degree of the polynomial
coefficientsPointer to an array of the degree+1 coefficients fo the polynomial
yThe resulting function value
Returns
Return code

Definition at line 63 of file VisionUtils.cpp.

unsigned long ipa_Utils::FilterByAmplitude ( cv::Mat &  xyzImage,
const cv::Mat &  greyImage,
cv::Mat *  mask,
cv::Mat *  maskColor,
float  minMaskThresh,
float  maxMaskThresh 
)

Filters a 3D range image with help of the amplitude image

Parameters
xyzImageA 3 channel, 32bit image, containing the xyz-data, filtered values are set to 0.
greyImageA 3 channel, 32bit image, containing the amplitude data
maskThe resulting mask image (32F1).
maskColorThe resulting color mask. Pixels are set to different colors if they are filtered or not.
minMaskThreshLower border for filtering.
maxMaskThreshUpper border for filtering.

build color mask from amplitude values

Definition at line 395 of file VisionUtils.cpp.

unsigned long ipa_Utils::FilterSpeckles ( cv::Mat &  img,
int  maxSpeckleSize,
double  _maxDiff,
cv::Mat &  _buf 
)

Description.

Definition at line 703 of file VisionUtils.cpp.

unsigned long ipa_Utils::FilterTearOffEdges ( cv::Mat &  xyzImage,
cv::Mat *  mask,
float  piHalfFraction = 6 
)

Filters tear-off edges from a 3D range image. All tear off edges are masked with a value of 255 in mask image. All other points are 0.

Parameters
xyzImageA 3 channel, 32bit image, containing the xyz-data, filtered values are set to 0.
maskThe resulting image mask
piHalfFractionAngles between (PI/2)/'piHalfFraction' and (2*PI)-(PI/2)/'piHalfFraction' are not discarded
Returns
Return code

Check if destination image has been initialized correctly

Extract four surrounding neighbor vectors that have a non zero mask value

x x o x x

Counte the amount of times, we satisfy the thresholds

Vector Middle (must exist)

Vector Left

Vector Right

Vector Up

Vector Down

Mask value if angle exceeded threshold too often

Definition at line 482 of file VisionUtils.cpp.

cv::Vec3b ipa_Utils::GrayColorMap ( double  value,
double  min,
double  max 
)

Returns mat as HSV or gray image

Parameters
valueValue to convert
minMinimum for scaling
maxMaximum for scaling
Returns
Vector containing RGB values

Definition at line 808 of file VisionUtils.cpp.

unsigned long ipa_Utils::LoadMat ( cv::Mat &  mat,
std::string  filename,
int  type = CV_32F 
)

Load OpenCV matrix in binary format.

Parameters
matThe OpenCV mat data structure
filenameThe filename
Returns
Return code

Definition at line 865 of file VisionUtils.cpp.

unsigned long ipa_Utils::MaskImage ( const cv::Mat &  source,
cv::Mat &  dest,
const cv::Mat &  mask,
cv::Mat &  destMask,
float  minMaskThresh = 0,
float  maxMaskTresh = 20000,
int  sourceChannel = 1,
double  sourceMin = -1,
double  sourceMax = -1 
)

Function to mask image source with image mask. All Pixels in source will be set to 0 if the corresponding pixel in mask is outside the interval [minMaskThresh, maxMaskTresh]. Additionally the source image values can be bounded to [sourceMin, sourceMax].

Parameters
sourceThe source image.
destThe destination image.
maskThe image used as mask for the source image.
destMaskThe resulting destination mask image (32F1).
minMaskThreshLower border for masking.
maxMaskThreshUpper border for masking.
sourceChannelChannel to be bounded in source image.
sourceMinLower border for bounding source image.
sourceMaxUpper border for bounding source image.

Check if destination image has been initialized correctly

Check if mask image has been initialized correctly

Calculate minmal and maximal value within the specified image sourceChannel Channel must be within [1, source->nChannels]

Definition at line 75 of file VisionUtils.cpp.

unsigned long ipa_Utils::SaveMat ( cv::Mat &  mat,
std::string  filename,
int  type = CV_32F 
)

Save OpenCV matrix in binary format.

Parameters
matThe OpenCV mat data structure
filenameThe filename
Returns
Return code

Definition at line 817 of file VisionUtils.cpp.

template<class T >
std::vector<T> ipa_Utils::takeRandomN ( const std::vector< T > &  v,
int  n 
)

Definition at line 196 of file VisionUtils.h.

cv::Mat ipa_Utils::vstack ( const std::vector< cv::Mat > &  mats)

Combines different matrices row wise, so that the number of columns remains the same and the number of rows increases.

Returns
The stacked matrix

Definition at line 26 of file VisionUtils.cpp.



cob_vision_utils
Author(s): Jan Fischer
autogenerated on Sun Oct 18 2020 13:13:20