Class to link detected images edges a typical source can be a cvCanny image. More...
#include <contour.h>
Public Member Functions | |
Contour () | |
void | Draw (unsigned char *pImgRGB) |
Draws the detected contours in a RGB image with radom colours. | |
void | GetAbnormitiesInEdgesImage (IplImage *ptImgEdge, std::vector< CvPoint > *pAbnormities, uchar iEdgeStrength=0) |
Find egde contour Abnormities in edge image. | |
int | getContours (std::vector< std::vector< cv::Point > > &contours, unsigned min_length=0) |
Returns the contour as vector of vector points. | |
int | GetEdgeListSplittedXY (std::vector< cv::Point_< int > > &rEdges, std::vector< unsigned char > **ppAngle8Bit=NULL) |
Returns number of edges and edges in the arguments. | |
unsigned int | GetNrOfEdges () |
Returns a number of edges used to linke edges to semgents. | |
std::vector< cv::Range > | getSegmentIndexes () |
the indexes of the contour segments | |
void | Init (unsigned int iImgWidth, unsigned int iImgHeight, bool bAllowToModifyTheSources=false, unsigned char iEdgeToProcess=0xFF, unsigned char iEdgeInProcess=0xFF-1, unsigned char iEdgeProcessed=0xFF-2, unsigned char iEdgeStrengthRemoved=0) |
Inititalized the class and reserves the momory needed. | |
void | Perform (unsigned char *pImgEdgeStrength, int defEdgeLinkMode=MODE_CONTOUR, void *pImgEdgeDirection=NULL, int defImgEdgeDirectionType=ANGLE_8U) |
Starts the edge linking with a certain mode. | |
~Contour () | |
Static Public Attributes | |
static const int | ANGLE_32F = 32 |
Static const variable used to define the source format of a gradient image as atan2(dy, dx) of the edge The format ANGLE_32F means values from -PI to +PI. | |
static const int | ANGLE_64F = 64 |
Static const variable used to define the source format of a gradient image as atan2(dy, dx) of the edge The format ANGLE_64F means values from -PI to +PI. | |
static const int | ANGLE_8U = 8 |
Static const variable used to define the source format of a gradient image as atan2(dy, dx) of the edge The format ANGLE_8U means zero rad are 0, +PI and -PI are 0x7F. | |
static const int | MODE_COMPLEX = 4 |
Static const variable used to define the methode used to find the contour (linked edges) | |
static const int | MODE_CONTOUR = 2 |
Static const variable used to define the methode used to find the contour (linked edges) | |
static const int | MODE_GRAIDENT = 3 |
Static const variable used to define the methode used to find the contour (linked edges) | |
static const int | MODE_SIMPLE = 1 |
Static const variable used to define the methode used to find the contour (linked edges) | |
Private Member Functions | |
void | AllocateMemory () |
int | GetImgDirectionIndex (CvPoint tPoint) |
unsigned char * | getImgEdge (CvPoint tPoint) |
bool | isInImage (const CvPoint &p) |
void | Linking_Complex () |
void | Linking_Contour () |
void | Linking_Gradient () |
void | Linking_Simple () |
void | markNeighborEdgesAsProcessed (unsigned char *pPix) |
void | RelaseMemory () |
void | SumArrayMatrix (int *pMatrixA, int *pMatrixB, int *pSum, const int iSize) |
void | Trace_Complex (CvPoint tPoint, int *pEnd, unsigned int iCommingFromEdge) |
void | Trace_Contour (CvPoint tPoint, int *pEnd, unsigned int iCommingFromEdge) |
void | Trace_Gradient (CvPoint tPoint, int *pEnd) |
void | Trace_Simple (CvPoint tPoint, int *pEnd) |
Static Private Member Functions | |
static const CvPoint | GetNeighborPoint (CvPoint pPtrCenter, int iNeighborIndex) |
static const void | SortArrayIndexes (int *pArray, int *pIndexes, const int iSize) |
Private Attributes | |
std::vector< unsigned char > | mAngle8Bit |
bool | mbAllowToModifyTheSources |
int | mdefEdgeLinkMode |
int | mdImgEdgeDirectionType |
unsigned char | mEdgeInProcess |
unsigned char | mEdgeProcessed |
std::vector< CvPoint > | mEdges |
unsigned char | mEdgeToProcess |
int | mImgHeight |
int | mImgWidth |
unsigned int | mNrOfEdges |
unsigned char * | mpImgEdge |
void * | mpImgEdgeDirection |
std::vector< cv::Range > | mSegments |
Static Private Attributes | |
static const double | dPi = 3.1415926535897932384626433832795 |
static const float | fPi = 3.1415926535897932384626433832795 |
static const int | ppContourWeightsField [9][9] |
static const int | ppGradientWeightsField [4][9] |
static const int | pppCommingFromEdgeWeightsField [9][3][3] |
static const int | pppDirectionWeightsField [4][3][3] |
Class to link detected images edges a typical source can be a cvCanny image.
Definition at line 108 of file contour.cpp.
Definition at line 119 of file contour.cpp.
void V4R::Contour::AllocateMemory | ( | ) | [private] |
Definition at line 123 of file contour.cpp.
void V4R::Contour::Draw | ( | unsigned char * | pImgRGB | ) |
Draws the detected contours in a RGB image with radom colours.
pImgRGB | target image |
Definition at line 164 of file contour.cpp.
void V4R::Contour::GetAbnormitiesInEdgesImage | ( | IplImage * | ptImgEdge, |
std::vector< CvPoint > * | pAbnormities, | ||
uchar | iEdgeStrength = 0 |
||
) |
Find egde contour Abnormities in edge image.
Definition at line 681 of file contour.cpp.
int V4R::Contour::getContours | ( | std::vector< std::vector< cv::Point > > & | contours, |
unsigned | min_length = 0 |
||
) |
Returns the contour as vector of vector points.
contours | |
min_length | on zero all controus are returned |
Definition at line 148 of file contour.cpp.
int V4R::Contour::GetEdgeListSplittedXY | ( | std::vector< cv::Point_< int > > & | rEdges, |
std::vector< unsigned char > ** | ppAngle8Bit = NULL |
||
) |
Returns number of edges and edges in the arguments.
listX | |
listY |
Definition at line 649 of file contour.cpp.
int V4R::Contour::GetImgDirectionIndex | ( | CvPoint | tPoint | ) | [private] |
Definition at line 194 of file contour.cpp.
unsigned char* V4R::Contour::getImgEdge | ( | CvPoint | tPoint | ) | [inline, private] |
const CvPoint V4R::Contour::GetNeighborPoint | ( | CvPoint | pPtrCenter, |
int | iNeighborIndex | ||
) | [static, private] |
Definition at line 608 of file contour.cpp.
unsigned int V4R::Contour::GetNrOfEdges | ( | ) | [inline] |
std::vector< cv::Range > V4R::Contour::getSegmentIndexes | ( | ) |
void V4R::Contour::Init | ( | unsigned int | iImgWidth, |
unsigned int | iImgHeight, | ||
bool | bAllowToModifyTheSources = false , |
||
unsigned char | iEdgeToProcess = 0xFF , |
||
unsigned char | iEdgeInProcess = 0xFF-1 , |
||
unsigned char | iEdgeProcessed = 0xFF-2 , |
||
unsigned char | iEdgeStrengthRemoved = 0 |
||
) |
Inititalized the class and reserves the momory needed.
iImgWidth | image width |
iImgHeight | image hight |
bAllowToModifyTheSources | if it is true it will write into your source image based on the parameters iEdgeStrengthSrc and iEdgeStrengthDes, it it it false it will make a copy of the image first (solwer) |
iEdgeToProcess | the strength of an edge in the source image, only of interrest if bAllowToModifyTheSources = true |
iEdgeInProcess | the strength of an edge in process, only of interrest if bAllowToModifyTheSources = true |
iEdgeProcessed | the strength of an edge after it was processed, only of interrest if bAllowToModifyTheSources = true |
iEdgeStrengthRemoved | the strength of an edge whenn it was removed, only of interrest if bAllowToModifyTheSources = true |
Definition at line 179 of file contour.cpp.
bool V4R::Contour::isInImage | ( | const CvPoint & | p | ) | [inline, private] |
void V4R::Contour::Linking_Complex | ( | ) | [private] |
Definition at line 545 of file contour.cpp.
void V4R::Contour::Linking_Contour | ( | ) | [private] |
Definition at line 402 of file contour.cpp.
void V4R::Contour::Linking_Gradient | ( | ) | [private] |
Definition at line 488 of file contour.cpp.
void V4R::Contour::Linking_Simple | ( | ) | [private] |
Definition at line 272 of file contour.cpp.
void V4R::Contour::markNeighborEdgesAsProcessed | ( | unsigned char * | pPix | ) | [inline, private] |
void V4R::Contour::Perform | ( | unsigned char * | pImgEdgeStrength, |
int | defEdgeLinkMode = MODE_CONTOUR , |
||
void * | pImgEdgeDirection = NULL , |
||
int | defImgEdgeDirectionType = ANGLE_8U |
||
) |
Starts the edge linking with a certain mode.
pImgEdgeStrength | edge image, where the edge must be at least of the iEdgeStrengthSrc defined in Contour::Init |
defEdgeLinkMode | defines the used mode to link the edges the default is MODE_CONTOUR MODE_SIMPLE the linker follows the first detected neighbor and removes the others. It checks first the top left and goes than to the right and then the next row (pImgEdgeDirection and defImgEdgeDirectionType are not needed) MODE_CONTOUR the linker follows the first detected neighbor detected on the obosite site from which it steped to the current edge and removes the others. (pImgEdgeDirection and defImgEdgeDirectionType are not needed) MODE_GRAIDENT the linker follows the first detected neighbor detected given by the edge direction in the pImgEdgeDirection image. (pImgEdgeDirection is needed and defImgEdgeDirectionType only if the format of pImgEdgeDirection is unlike ANGLE_8U) MODE_COMPLEX mixes the modes MODE_GRAIDENT and MODE_CONTOUR |
pImgEdgeDirection | pointer to the edge direction image with the angle information of every edge in the pImgEdgeStrength |
defImgEdgeDirectionType | type of the pImgEdgeDirection default is ANGLE_8U. ANGLE_8U the angle values in pImgEdgeDirection are encoded as 8 bit values where zero rad are 0, +PI and -PI are 0x7F. "unsigned char i8BitAngle = (unsigned char) (dRad * 255.0 / (2 * CV_PI) + 128.5);" is a way to generate such information. ANGLE_32F the angle values in pImgEdgeDirection are encoded 32 float value where the ange is defined as atan2(dy, dx) of the related edge in pImgEdgeStrength ANGLE_64F the angle values in pImgEdgeDirection are encoded 32 float value where the ange is defined as atan2(dy, dx) of the related edge in pImgEdgeStrength |
Definition at line 236 of file contour.cpp.
void V4R::Contour::RelaseMemory | ( | ) | [private] |
Definition at line 133 of file contour.cpp.
const void V4R::Contour::SortArrayIndexes | ( | int * | pArray, |
int * | pIndexes, | ||
const int | iSize | ||
) | [static, private] |
Definition at line 661 of file contour.cpp.
void V4R::Contour::SumArrayMatrix | ( | int * | pMatrixA, |
int * | pMatrixB, | ||
int * | pSum, | ||
const int | iSize | ||
) | [inline, private] |
void V4R::Contour::Trace_Complex | ( | CvPoint | tPoint, |
int * | pEnd, | ||
unsigned int | iCommingFromEdge | ||
) | [private] |
Definition at line 563 of file contour.cpp.
void V4R::Contour::Trace_Contour | ( | CvPoint | tPoint, |
int * | pEnd, | ||
unsigned int | iCommingFromEdge | ||
) | [private] |
Definition at line 420 of file contour.cpp.
void V4R::Contour::Trace_Gradient | ( | CvPoint | tPoint, |
int * | pEnd | ||
) | [private] |
Definition at line 506 of file contour.cpp.
void V4R::Contour::Trace_Simple | ( | CvPoint | tPoint, |
int * | pEnd | ||
) | [private] |
Definition at line 324 of file contour.cpp.
const int V4R::Contour::ANGLE_32F = 32 [static] |
const int V4R::Contour::ANGLE_64F = 64 [static] |
const int V4R::Contour::ANGLE_8U = 8 [static] |
const double V4R::Contour::dPi = 3.1415926535897932384626433832795 [static, private] |
const float V4R::Contour::fPi = 3.1415926535897932384626433832795 [static, private] |
std::vector<unsigned char> V4R::Contour::mAngle8Bit [private] |
bool V4R::Contour::mbAllowToModifyTheSources [private] |
int V4R::Contour::mdefEdgeLinkMode [private] |
int V4R::Contour::mdImgEdgeDirectionType [private] |
unsigned char V4R::Contour::mEdgeInProcess [private] |
unsigned char V4R::Contour::mEdgeProcessed [private] |
std::vector<CvPoint> V4R::Contour::mEdges [private] |
unsigned char V4R::Contour::mEdgeToProcess [private] |
int V4R::Contour::mImgHeight [private] |
int V4R::Contour::mImgWidth [private] |
unsigned int V4R::Contour::mNrOfEdges [private] |
const int V4R::Contour::MODE_COMPLEX = 4 [static] |
const int V4R::Contour::MODE_CONTOUR = 2 [static] |
const int V4R::Contour::MODE_GRAIDENT = 3 [static] |
const int V4R::Contour::MODE_SIMPLE = 1 [static] |
unsigned char* V4R::Contour::mpImgEdge [private] |
void* V4R::Contour::mpImgEdgeDirection [private] |
std::vector<cv::Range> V4R::Contour::mSegments [private] |
const int V4R::Contour::ppContourWeightsField [static, private] |
{ {8, 7, 5, 6, 2, 3, 1, 0, 4}, {7, 6, 8, 3, 5, 0, 2, 1, 4}, {6, 7, 3, 8, 0, 5, 1, 2, 4}, {5, 2, 8, 1, 7, 0, 6, 3, 4}, {0, 0, 0, 0, 0, 0, 0, 0, 0}, {3, 6, 0, 7, 1, 8, 2, 5, 4}, {2, 1, 5, 0, 8, 3, 7, 6, 4}, {1, 2, 0, 3, 5, 6, 8, 7, 4}, {0, 1, 3, 2, 6, 5, 7, 8, 4} }
const int V4R::Contour::ppGradientWeightsField [static, private] |
const int V4R::Contour::pppCommingFromEdgeWeightsField [static, private] |
const int V4R::Contour::pppDirectionWeightsField [static, private] |