48 #ifndef _IMAGE_PROCESSOR_H_ 49 #define _IMAGE_PROCESSOR_H_ 957 bool ApplyHomography(
const CByteImage *pInputImage,
CByteImage *pOutputImage,
float a1,
float a2,
float a3,
float a4,
float a5,
float a6,
float a7,
float a8,
bool bInterpolation =
true);
986 bool Rotate(
const CByteImage *pInputImage,
CByteImage *pOutputImage,
float mx,
float my,
float theta,
bool bInterpolation =
true);
994 bool DetermineHomography(
const Vec2d *pSourcePoints,
const Vec2d *pTargetPoints,
int nPoints,
float &a1,
float &a2,
float &a3,
float &a4,
float &a5,
float &a6,
float &a7,
float &a8);
1072 bool FilterHSV(
const CByteImage *pInputImage,
CByteImage *pOutputImage,
unsigned char hue,
unsigned char tol_hue,
unsigned char min_sat,
unsigned char max_sat,
unsigned char min_v,
unsigned char max_v,
const MyRegion *pROI = 0);
1092 bool FilterHSV2(
const CByteImage *pInputImage,
CByteImage *pOutputImage,
unsigned char min_hue,
unsigned char max_hue,
unsigned char min_sat,
unsigned char max_sat,
unsigned char min_v,
unsigned char max_v,
const MyRegion *pROI = 0);
1452 int RegionGrowing(
const CByteImage *pInputImage,
MyRegion &resultRegion,
int x,
int y,
int nMinimumPointsPerRegion = 0,
int nMaximumPointsPerRegion = 0,
bool bCalculateBoundingBox =
true,
bool bStorePixels =
false);
1472 bool FindRegions(
const CByteImage *pImage,
RegionList ®ionList,
int nMinimumPointsPerRegion = 0,
int nMaximumPointsPerRegion = 0,
bool bCalculateBoundingBox =
true,
bool bStorePixels =
false);
1489 bool FindRegions(
const CByteImage *pImage,
CRegionArray ®ionList,
int nMinimumPointsPerRegion = 0,
int nMaximumPointsPerRegion = 0,
bool bCalculateBoundingBox =
true,
bool bStorePixels =
false);
1609 bool HoughTransformCircles(
const CVec2dArray &edgePoints,
const CVec2dArray &edgeDirections,
int width,
int height,
int rmin,
int rmax,
int nCirclesToExtract,
int nMinHits,
CVec3dArray &resultCircles,
CIntArray &resultHits,
CByteImage *pVisualizationImage = 0);
1635 bool HoughTransformCircles(
const CVec2dArray &edgePoints,
const CVec2dArray &edgeDirections,
int width,
int height,
int rmin,
int rmax,
int nCirclesToExtract,
int nMinHits,
CCircle2dArray &resultCircles,
CIntArray &resultHits,
CByteImage *pVisualizationImage = 0);
1697 int GetAreaSum(
const CIntImage *pIntegralImage,
int min_x,
int min_y,
int max_x,
int max_y);
bool HighPassX3(const CFloatMatrix *pInputImage, CFloatMatrix *pOutputImage)
Applies a 1x3 highpass filter to a CFloatMatrix and write the result to a CFloatMatrix.
unsigned int PixelSum(const CByteImage *pImage)
Returns the sum of all pixel values of a grayscale CByteImage.
unsigned char MaxValue(const CByteImage *pImage)
Returns the maximum value within a grayscale CByteImage.
bool AddWithSaturation(const CByteImage *pInputImage1, const CByteImage *pInputImage2, CByteImage *pOutputImage)
Sets each pixel in a CByteImage to the sum of the corresponding pixels in two instances of CByteImage...
bool DetermineAffineTransformation(const Vec2d *pSourcePoints, const Vec2d *pTargetPoints, int nPoints, float &a1, float &a2, float &a3, float &a4, float &a5, float &a6)
Deprecated.
BayerPatternType
The four possible variants for Bayer pattern conversion.
bool MinMaxValue(const CByteImage *pImage, unsigned char &min, unsigned char &max)
Computes the minimum and maximum value within a grayscale CByteImage.
bool ApplyAffinePointOperation(const CByteImage *pInputImage, CByteImage *pOutputImage, float a, float b)
Applies an affine point operation to a CByteImage and writes the result to a CByteImage.
bool ApplyHomography(const CByteImage *pInputImage, CByteImage *pOutputImage, const Mat3d &A, bool bInterpolation=true)
Applies a homography to a CByteImage and writes the result to a CByteImage.
bool CopyFrame(const CByteImage *pInputImage, CByteImage *pOutputImage)
Copies all pixels on a one pixel wide frame from one CByteImage to CByteImage.
bool HoughTransformLines(const CByteImage *pImage, CByteImage *pVisualizationImage, Vec2dList &resultLines, int nLinesToExtract, int nMinHits=1)
Performs the Hough transform for straight lines on a CByteImage.
bool CalculateGradientImageSobel(const CByteImage *pInputImage, CByteImage *pOutputImage)
Applies a combined Sobel filter for both x- and y-direction to a CByteImage and stores the result in ...
bool Laplace2(const CByteImage *pInputImage, CShortImage *pOutputImage, bool bAbsoluteValue=true)
Filters a CByteImage with the Laplace2 operator and writes the result to a CShortImage.
bool FilterColor(const CByteImage *pInputImage, CByteImage *pOutputImage, ObjectColor cColor, CColorParameterSet *pColorParameterSet, bool bImageIsHSV=true)
Performs color filtering with binarization for a CByteImage and writes the result to a grayscale CByt...
bool FindRegions(const CByteImage *pImage, RegionList ®ionList, int nMinimumPointsPerRegion=0, int nMaximumPointsPerRegion=0, bool bCalculateBoundingBox=true, bool bStorePixels=false)
Performs region growing on a binary CByteImage, segmenting all regions in the image.
bool Max(const CByteImage *pInputImage1, const CByteImage *pInputImage2, CByteImage *pOutputImage)
Sets each pixel in a CByteImage to the maximum of the corresponding pixels in two instances of CByteI...
bool CalculateSaturationImage(const CByteImage *pInputImage, CByteImage *pOutputImage)
Calculates the saturation image for an RGB CByteImage and writes the result to a CByteImage.
bool NormalizeColor(const CByteImage *pInputImage, CByteImage *pOutputImage)
Applies histogram equalization to all channels of a color CByteImage.
bool ThresholdFilterInverse(const CByteImage *pInputImage, CByteImage *pOutputImage, unsigned char nThreshold)
Performs inverse threhold filtering to a CByteImage and writes the result to a CByteImage.
bool Dilate(const CByteImage *pInputImage, CByteImage *pOutputImage, int nMaskSize=3, const MyRegion *pROI=0)
Applies a morphological dilate operation to a binary CByteImage and writes the result to a binary CBy...
bool ThresholdFilter(const CByteImage *pInputImage, CByteImage *pOutputImage, unsigned char nThreshold)
Performs threhold filtering to a CByteImage and writes the result to a CByteImage.
std::vector< Vec2d > Vec2dList
bool DetermineHomography(const Vec2d *pSourcePoints, const Vec2d *pTargetPoints, int nPoints, float &a1, float &a2, float &a3, float &a4, float &a5, float &a6, float &a7, float &a8)
Deprecated.
bool SobelX(const CByteImage *pInputImage, CShortImage *pOutputImage, bool bAbsoluteValue=true)
Filters a CByteImage with the SobelX operator and writes the result to a CShortImage.
bool FilterRGB(const CByteImage *pInputImage, CByteImage *pOutputImage, CRGBColorModel *pColorModel, float fThreshold)
Performs color filtering with binarization for an RGB CByteImage, given a CRGBColorModel, and writes the result to a grayscale CByteImage.
bool PrewittX(const CByteImage *pInputImage, CShortImage *pOutputImage, bool bAbsoluteValue=true)
Filters a CByteImage with the PrewittX operator and writes the result to a CShortImage.
unsigned char MinValue(const CByteImage *pImage)
Returns the minimum value within a grayscale CByteImage.
bool CalculateBinarizedSummedAreaTable(const CByteImage *pInputImage, CIntImage *pSummedAreaTable)
Calculates the binarized summed area table of a grayscale CByteImage and writes the result to a CIntI...
bool Invert(const CByteImage *pInputImage, CByteImage *pOutputImage)
Calculates the inverted image of a CByteImage and writes the result to a CByteImage.
bool ConvertBayerPattern(const CByteImage *pInputImage, CByteImage *pOutputImage, BayerPatternType type)
Converts an 8 bit Bayer pattern CByteImage to an RGB24 color CByteImage.
bool SobelY(const CByteImage *pInputImage, CShortImage *pOutputImage, bool bAbsoluteValue=true)
Filters a CByteImage with the SobelY operator and writes the result to a CShortImage.
Data structure for the representation of 8-bit grayscale images and 24-bit RGB (or HSV) color images ...
bool GeneralFilter(const CByteImage *pInputImage, CByteImage *pOutputImage, const int *pKernel, int nMaskSize, int nDivider=1, bool bAbsoluteValue=false)
Applies a user defined filter to a CByteImage and writes the result to a CByteImage.
bool CalculateHSVImage(const CByteImage *pInputImage, CByteImage *pOutputImage, const MyRegion *pROI=0)
Computes the HSV image for a RGB CByteImage and writes the result to a CByteImage.
int GetAreaSumNoChecks(const CIntImage *pIntegralImage, int min_x, int min_y, int max_x, int max_y)
Efficiently computes the sum of all pixel values in a rectangular area using integral image lookups...
bool HighPassY3(const CFloatMatrix *pInputImage, CFloatMatrix *pOutputImage)
Applies a 3x1 highpass filter to a CFloatMatrix and writes the result to a CFloatMatrix.
bool CalculateGradientImage(const CByteImage *pInputImage, CByteImage *pOutputImage)
Applies a combined simple gradient filter for both x- and y-direction to a CByteImage and stores the ...
bool Xor(const CByteImage *pInputImage1, const CByteImage *pInputImage2, CByteImage *pOutputImage)
Applies the bitwise operator XOR to two instance of CByteImage and writes the result to a CByteImage...
bool CalculateHarrisMap(const CByteImage *pInputImage, CIntImage *pOutputImage)
Calculates the Harris cornerness measure for every pixel in a CByteImage and writes the results to a ...
GLuint GLuint GLsizei GLenum type
bool CalculateReverseSummedAreaTable(const CIntImage *pSummedAreaTable, CByteImage *pOutputImage)
Reconstructs the original image, given a summed area table, and writes the result to a grayscale CByt...
bool ConvertImage(const CByteImage *pInputImage, CByteImage *pOutputImage, bool bFast=false, const MyRegion *pROI=0)
Converts a grayscale CByteImage to an RGB CByteImage image and vice versa.
bool ThresholdBinarizeInverse(const CByteImage *pInputImage, CByteImage *pOutputImage, unsigned char nThreshold)
Performs inverse threshold binarization to a CByteImage and writes the result to a CByteImage...
std::vector< Vec3d > Vec3dList
bool FlipY(const CByteImage *pInputImage, CByteImage *pOutputImage)
Flips the rows in a CByteImage vertically and writes the result to a CByteImage.
bool SubtractWithSaturation(const CByteImage *pInputImage1, const CByteImage *pInputImage2, CByteImage *pOutputImage)
Sets each pixel in a CByteImage to the difference between the corresponding pixels in two instances o...
int RegionGrowing(const CByteImage *pInputImage, MyRegion &resultRegion, int x, int y, int nMinimumPointsPerRegion=0, int nMaximumPointsPerRegion=0, bool bCalculateBoundingBox=true, bool bStorePixels=false)
Performs a region growing on a binary CByteImage on the basis of one seed point and stores the comput...
bool GaussianSmooth(const CByteImage *pInputImage, CFloatMatrix *pOutputImage, float fVariance, int nKernelSize)
Applies a Gaussian filter to a CByteImage and writes the result to a CFloatMatrix.
bool Average(const CByteImage *pInputImage1, const CByteImage *pInputImage2, CByteImage *pOutputImage)
Sets each pixel in a CByteImage to the average of the corresponding pixels in two instances of CByteI...
std::vector< MyRegion > RegionList
bool AverageFilter(const CByteImage *pInputImage, CByteImage *pOutputImage, int nMaskSize=3)
Applies an average filter to a CByteImage and writes the result to a CByteImage.
bool CopyMatrix(const CFloatMatrix *pInputImage, CFloatMatrix *pOutputImage)
Copies one CFloatMatrix to another.
Data structure for the representation of a matrix of values of the data type float.
bool AbsoluteDifference(const CByteImage *pInputImage1, const CByteImage *pInputImage2, CByteImage *pOutputImage)
Sets each pixel in a CByteImage to the absolute value of the difference between the corresponding pix...
bool Canny(const CByteImage *pInputImage, CByteImage *pOutputImage, int nLowThreshold, int nHighThreshold)
Applies the Canny edge detector to a CByteImage and writes the result to a CByteImage.
bool CopyImage(const CByteImage *pInputImage, CByteImage *pOutputImage, const MyRegion *pROI=0, bool bUseSameSize=false)
Copies one CByteImage to another.
Central namespace offering various image processing routines and functions.
void ZeroFrame(CByteImage *pImage)
Sets all pixels on a one pixel wide frame of a CByteImage to zero.
bool Min(const CByteImage *pInputImage1, const CByteImage *pInputImage2, CByteImage *pOutputImage)
Sets each pixel in a CByteImage to the minimum of the corresponding pixels in two instances of CByteI...
Data structure for the representation of single channel images of the data type signed short...
GLubyte GLubyte GLubyte a
bool Subtract(const CByteImage *pInputImage1, const CByteImage *pInputImage2, CByteImage *pOutputImage)
Sets each pixel in a CByteImage to the difference between the corresponding pixels in two instances o...
bool Amplify(const CByteImage *pInputImage, CByteImage *pOutputImage, float fFactor)
Multiplies each byte value of a CByteImage with a floating point factor and writes the result to a CB...
bool PrewittY(const CByteImage *pInputImage, CShortImage *pOutputImage, bool bAbsoluteValue=true)
Filters a CByteImage with the PrewittY operator and writes the result to a CShortImage.
bool ThresholdBinarize(const CByteImage *pInputImage, CByteImage *pOutputImage, unsigned char nThreshold)
Performs threshold binarization to a CByteImage and writes the result to a CByteImage.
GLenum GLsizei GLsizei height
bool CalculateGradientImageBinary(const CByteImage *pInputImage, CByteImage *pOutputImage)
Calculates a gradient image for a CByteImage and writes the result to a CByteImage, for the special case of binary images.
bool Rotate(const CByteImage *pInputImage, CByteImage *pOutputImage, float mx, float my, float theta, bool bInterpolation=true)
Rotates pInputImage to the dimensions specified by pOutputImage and stores the result in pOutputImage...
bool FilterHSV2(const CByteImage *pInputImage, CByteImage *pOutputImage, unsigned char min_hue, unsigned char max_hue, unsigned char min_sat, unsigned char max_sat, unsigned char min_v, unsigned char max_v, const MyRegion *pROI=0)
Performs color filtering with binarization for an HSV CByteImage and writes the result to a grayscale...
bool Spread(const CByteImage *pInputImage, CByteImage *pOutputImage)
Performs a spread operation on pInputImage and stores the result in pOutputImage. ...
bool Rotate180Degrees(const CByteImage *pInputImage, CByteImage *pOutputImage)
Rotates a CByteImage by 180 degrees and writes the result to a CByteImage.
bool Add(const CByteImage *pInputImage1, const CByteImage *pInputImage2, CByteImage *pOutputImage)
Sets each pixel in a CByteImage to the sum of the corresponding pixels in two instances of CByteImage...
bool Laplace1(const CByteImage *pInputImage, CShortImage *pOutputImage, bool bAbsoluteValue=true)
Filters a CByteImage with the Laplace1 operator and writes the result to a CShortImage.
bool GaussianSmooth5x5(const CFloatMatrix *pInputImage, CFloatMatrix *pOutputImage, float fVariance)
Applies a 5x5 Gaussian filter to a CFloatMatrix and writes the result to a CFloatMatrix.
bool AdaptFrame(const CByteImage *pInputImage, CByteImage *pOutputImage)
Sets all pixels on a one pixel wide outer frame in a CByteImage to the pixel values of the inner fram...
int CalculateHarrisInterestPoints(const CByteImage *pInputImage, Vec2d *pInterestPoints, int nMaxPoints, float fQualityLevel=0.01f, float fMinDistance=5.0f)
Computes interest points within a CByteImage by applying the Harris corner detector.
int GetAreaSum(const CIntImage *pIntegralImage, int min_x, int min_y, int max_x, int max_y)
Efficiently computes the sum of all pixel values in a rectangular area using integral image lookups...
Data structure for the representation of a 2D vector.
bool Erode(const CByteImage *pInputImage, CByteImage *pOutputImage, int nMaskSize=3, const MyRegion *pROI=0)
Applies a morphological erode operation to a binary CByteImage and writes the result to a binary CByt...
bool HoughTransformCircles(const CByteImage *pImage, CByteImage *pVisualizationImage, Vec3dList &resultCircles, int rmin, int rmax, int nCirclesToExtract, int nMinHits=1)
Performs the Hough transform for circles on a CByteImage.
bool Or(const CByteImage *pInputImage1, const CByteImage *pInputImage2, CByteImage *pOutputImage)
Applies the bitwise operator OR to two instance of CByteImage and writes the result to a CByteImage...
bool HistogramStretching(const CByteImage *pInputImage, CByteImage *pOutputImage, float p1=0.1f, float p2=0.9f)
Performs histogram stretching on pInputImage and stores the result in pOutputImage.
Data structure for the representation of single channel images of the data type signed int...
Data structure for the representation of a matrix of values of the data type double.
bool HistogramEqualization(const CByteImage *pInputImage, CByteImage *pOutputImage)
Performs histogram equalization for a CByteImage and writes the result to a CByteImage.
bool And(const CByteImage *pInputImage1, const CByteImage *pInputImage2, CByteImage *pOutputImage)
Applies the bitwise operator AND to two instance of CByteImage and writes the result to a CByteImage...
bool CalculateSummedAreaTable(const CByteImage *pInputImage, CIntImage *pSummedAreaTable)
Calculates the summed area table of a grayscale CByteImage and writes the result to a CIntImage...
bool GaussianSmooth3x3(const CByteImage *pInputImage, CByteImage *pOutputImage)
Applies a 3x3 Gaussian filter to a CByteImage and writes the result to a CByteImage.
void Zero(CByteImage *pImage, const MyRegion *pROI=0)
Sets all values in a CByteImage to zero.
bool ConvertMatrix(const CFloatMatrix *pInputImage, CDoubleMatrix *pOutputImage)
Converts a CFloatMatrix to a CDoubleMatrix.
bool CalculateGradientImagePrewitt(const CByteImage *pInputImage, CByteImage *pOutputImage)
Applies a combined Prewitt filter for both x- and y-direction to a CByteImage and stores the result i...
Data structure for the representation of a 3x3 matrix.
Data structure for the representation of any image type (arbitrary number of channels) using the data...
Training and application of an RGB color model on the basis of the Mahalanobis distance.
bool Resize(const CByteImage *pInputImage, CByteImage *pOutputImage, const MyRegion *pROI=0, bool bInterpolation=true)
Resizes a CByteImage and writes the result to a CByteImage.
bool FilterHSV(const CByteImage *pInputImage, CByteImage *pOutputImage, unsigned char hue, unsigned char tol_hue, unsigned char min_sat, unsigned char max_sat, unsigned char min_v, unsigned char max_v, const MyRegion *pROI=0)
Performs color filtering with binarization for an HSV CByteImage and writes the result to a grayscale...
bool CalculateIntegralImage(const CByteImage *pInputImage, CIntImage *pIntegralImage)
Calculates the integral image of a grayscale CByteImage and writes the result to a CIntImage...