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 ¢ers_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. | |
unsigned long | FilterTearOffEdges (cv::Mat &xyzImage, cv::Mat *mask, float piHalfFraction=6) |
cv::Mat | GetColorcoded (const cv::Mat &img_32F) |
cv::Mat | GetColorcoded (const cv::Mat &img_32F, double min, double max) |
cv::Vec3b | GrayColorMap (double value, double min, double max) |
void | InitUndistortMap (const cv::Mat &A, const cv::Mat &dist_coeffs, cv::Mat &mapxarr, cv::Mat &mapyarr) |
Function to replace the buggy OpenCV 1.1 function. | |
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) |
anonymous enum |
An enum for the return values. This enum describes possible return values that are used to return failure or success.
RET_OK |
Everythings OK. |
RET_FAILED |
Something went dramatically wrong. |
RET_WARNING |
Something went wrong. |
Definition at line 70 of file GlobalDefines.h.
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 174 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.
source | The 32 bit, n channel source image |
dest | The resulting 8 bit, 1 channel image |
channel | The channel of the source image to process |
min | Minimal value that is converted, smaller values are clipped to min |
max | Maximal value that is converted, bigger values are clipped to max |
Calculate minmal and maximal value within the specified image channel
Definition at line 371 of file VisionUtils.cpp.
unsigned long ipa_Utils::EvaluatePolynomial | ( | double | x, |
int | degree, | ||
double * | coefficients, | ||
double * | y | ||
) |
Evaluates a polynomial, calculated with FitPolynomial
x | The function value |
degree | The degree of the polynomial |
coefficients | Pointer to an array of the degree +1 coefficients fo the polynomial |
y | The resulting function value |
Definition at line 101 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
xyzImage | A 3 channel, 32bit image, containing the xyz-data, filtered values are set to 0. |
greyImage | A 3 channel, 32bit image, containing the amplitude data |
mask | The resulting mask image (32F1). |
maskColor | The resulting color mask. Pixels are set to different colors if they are filtered or not. |
minMaskThresh | Lower border for filtering. |
maxMaskThresh | Upper border for filtering. |
build color mask from amplitude values
Definition at line 478 of file VisionUtils.cpp.
unsigned long ipa_Utils::FilterSpeckles | ( | cv::Mat & | img, |
int | maxSpeckleSize, | ||
double | _maxDiff, | ||
cv::Mat & | _buf | ||
) |
Description.
Definition at line 786 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.
xyzImage | A 3 channel, 32bit image, containing the xyz-data, filtered values are set to 0. |
mask | The resulting image mask |
piHalfFraction | Angles between (PI/2)/'piHalfFraction' and (2*PI)-(PI/2)/'piHalfFraction' are not discarded |
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 565 of file VisionUtils.cpp.
cv::Mat ipa_Utils::GetColorcoded | ( | const cv::Mat & | img_32F | ) |
Returns mat as HSV or gray image
img_32F | Float matrix |
Definition at line 900 of file VisionUtils.cpp.
cv::Mat ipa_Utils::GetColorcoded | ( | const cv::Mat & | img_32F, |
double | min, | ||
double | max | ||
) |
Returns mat as HSV or gray image
img_32F | Float matrix |
min | Minimum for scaling |
max | Maximum for scaling |
Definition at line 910 of file VisionUtils.cpp.
cv::Vec3b ipa_Utils::GrayColorMap | ( | double | value, |
double | min, | ||
double | max | ||
) |
Returns mat as HSV or gray image
value | Value to convert |
min | Minimum for scaling |
max | Maximum for scaling |
Definition at line 891 of file VisionUtils.cpp.
void ipa_Utils::InitUndistortMap | ( | const cv::Mat & | A, |
const cv::Mat & | dist_coeffs, | ||
cv::Mat & | mapxarr, | ||
cv::Mat & | mapyarr | ||
) |
Function to replace the buggy OpenCV 1.1 function.
Definition at line 113 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.
mat | The OpenCV mat data structure |
filename | The filename |
Definition at line 1017 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]
.
source | The source image. |
dest | The destination image. |
mask | The image used as mask for the source image. |
destMask | The resulting destination mask image (32F1). |
minMaskThresh | Lower border for masking. |
maxMaskThresh | Upper border for masking. |
sourceChannel | Channel to be bounded in source image. |
sourceMin | Lower border for bounding source image. |
sourceMax | Upper 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 182 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.
mat | The OpenCV mat data structure |
filename | The filename |
Definition at line 969 of file VisionUtils.cpp.
std::vector<T> ipa_Utils::takeRandomN | ( | const std::vector< T > & | v, |
int | n | ||
) |
Definition at line 252 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.
Definition at line 64 of file VisionUtils.cpp.