27 const float Contour::fPi = 3.1415926535897932384626433832795;
28 const double Contour::dPi = 3.1415926535897932384626433832795;
50 {3, 5, 6, 8, 2, 0, 7, 1, 4},
51 {2, 6, 1, 3, 7, 5, 0, 8, 4},
52 {1, 7, 0, 6, 8, 2, 3, 5, 4},
53 {0, 8, 1, 7, 5, 3, 2, 6, 4}
96 {8, 7, 5, 6, 2, 3, 1, 0, 4},
97 {7, 6, 8, 3, 5, 0, 2, 1, 4},
98 {6, 7, 3, 8, 0, 5, 1, 2, 4},
99 {5, 2, 8, 1, 7, 0, 6, 3, 4},
100 {0, 0, 0, 0, 0, 0, 0, 0, 0},
101 {3, 6, 0, 7, 1, 8, 2, 5, 4},
102 {2, 1, 5, 0, 8, 3, 7, 6, 4},
103 {1, 2, 0, 3, 5, 6, 8, 7, 4},
104 {0, 1, 3, 2, 6, 5, 7, 8, 4}
109 mpImgEdgeDirection ( NULL ),
110 mdImgEdgeDirectionType ( 0 ),
111 mdefEdgeLinkMode ( 0 ),
114 mbAllowToModifyTheSources ( false ),
150 for (
unsigned int i = 0; i < idx.size(); i++ ) {
151 int length = idx[i].end - idx[i].start;
152 if (length > min_length) {
153 contours.push_back(std::vector<cv::Point>());
154 for (
int index = idx[i].start; index < idx[i].end; index++ ) {
155 CvPoint &edge = (
mEdges)[index];
156 contours.back().push_back( edge);
160 return contours.size();
166 for (
unsigned int i = 0; i < idx.size(); i++ ) {
167 unsigned char pColor[] = {rand() / ( RAND_MAX/0xFF ), rand() / ( RAND_MAX/0xFF ), rand() / ( RAND_MAX/0xFF ) };
168 for (
int index = idx[i].start; index < idx[i].end; index++ ) {
169 CvPoint edge = (
mEdges)[index];
170 pDes = pImgRGB + ( 3 * (
mImgWidth * edge.y + edge.x ) );
171 for (
int j = 0; j < 3; j++ ) {
178 void Contour::Init (
unsigned int iImgWidth,
unsigned int iImgHeight,
bool bAllowToModifyTheSources,
unsigned char iEdgeToProcess,
unsigned char iEdgeInProcess,
unsigned char iEdgeProcessed,
unsigned char iEdgeStrengthRemoved ) {
204 unsigned char i8BitAngle;
210 if ( i8BitAngle > 128 ) {
213 i8BitAngle = i8BitAngle + 16;
214 iIndex = i8BitAngle / 32;
221 iIndex = ( int ) ( ( fAngle +
fPi/8 ) * 3/
fPi );
229 iIndex = ( int ) ( ( dAngle +
dPi/8 ) * 3/
dPi );
235 void Contour::Perform (
unsigned char* pImgEdgeStrength,
int defEdgeLinkMode,
void* pImgEdgeDirection,
int dImgEdgeDirectionType ) {
256 if ( pImgEdgeDirection == NULL ) {
257 printf (
"The linker mode requires an edge direction image!\n" );
262 if ( pImgEdgeDirection == NULL ) {
263 printf (
"The linker mode requires an edge direction image!\n" );
272 CvPoint tPoint = cvPoint(0,0);
273 cv::Range range(0,0);
274 for ( tPoint.y = 1; tPoint.y <
mImgHeight-1; tPoint.y++ ) {
276 unsigned char *pCurrent =
getImgEdge ( tPoint );
277 for ( ; tPoint.x <
mImgWidth-1; tPoint.x++ ) {
336 CvPoint tCurrent = tPoint;
339 std::stack<CvPoint> trace_to_start;
340 std::stack<CvPoint> trace_to_end;
341 std::stack<CvPoint> *pEdgeStack = &trace_to_start;
342 while (bEnd ==
false) {
350 pEdgeStack->push(tCurrent);
353 tCurrent.x--, tCurrent.y--;
359 tCurrent.x++, tCurrent.y--;
368 tCurrent.x--, tCurrent.y++;
374 tCurrent.x++, tCurrent.y++;
376 if (bStart ==
false) {
378 while (!trace_to_start.empty()) {
379 trace_to_end.push(trace_to_start.top());
380 trace_to_start.pop();
382 pEdgeStack = &trace_to_end;
383 tCurrent = pEdgeStack->top();
391 while (!pEdgeStack->empty()) {
392 CvPoint p = pEdgeStack->top();
402 CvPoint tPoint = cvPoint(0,0);
403 cv::Range range(0,0);
404 for ( tPoint.y = 1; tPoint.y < (
int )
mImgHeight-1; tPoint.y++ ) {
406 unsigned char *pCurrent =
getImgEdge ( tPoint );
407 for ( ; tPoint.x < ( int )
mImgWidth-1; tPoint.x++ ) {
430 CvPoint tCurrent = tPoint;
433 std::stack<CvPoint> trace_to_start;
434 std::stack<CvPoint> trace_to_end;
435 std::stack<CvPoint> *pEdgeStack = &trace_to_start;
436 while (bEnd ==
false) {
438 pEdgeStack->push(tCurrent);
441 tCurrent.x--, tCurrent.y--;
447 tCurrent.x++, tCurrent.y--;
456 tCurrent.x--, tCurrent.y++;
462 tCurrent.x++, tCurrent.y++;
464 if (bStart ==
false) {
466 while (!trace_to_start.empty()) {
467 trace_to_end.push(trace_to_start.top());
468 trace_to_start.pop();
470 pEdgeStack = &trace_to_end;
471 tCurrent = pEdgeStack->top();
478 while (!pEdgeStack->empty()) {
488 CvPoint tPoint = cvPoint(0,0);;
489 cv::Range range(0,0);
490 for ( tPoint.y = 1; tPoint.y < (
int )
mImgHeight-1; tPoint.y++ ) {
492 unsigned char *pCurrent =
getImgEdge ( tPoint );
493 for ( ; tPoint.x < ( int )
mImgWidth-1; tPoint.x++ ) {
507 CvPoint tCurrent = cvPoint(0,0);;
508 CvPoint tNext = cvPoint(0,0);;
509 bool bRemove =
false;
510 unsigned char *pNeighbor;
517 for (
int i = 0; i < 9; i++ ) {
521 if ( pIndex[i] == 4 ) {
545 CvPoint tPoint = cvPoint(0,0);;
546 cv::Range range(0,0);
547 for ( tPoint.y = 1; tPoint.y < (
int )
mImgHeight-1; tPoint.y++ ) {
549 unsigned char *pCurrent =
getImgEdge ( tPoint );
550 for ( ; tPoint.x < ( int )
mImgWidth-1; tPoint.x++ ) {
565 CvPoint tNext = cvPoint(0,0);;
566 bool bRemove =
false;
567 unsigned char *pNeighbor = NULL;
568 unsigned int iGointToEdge = 0;
580 for (
int i = 0; i < 9; i++ ) {
584 if ( pIndex[i] == 4 ) {
596 iGointToEdge = 8-pIndex[i];
608 switch ( iNeighborIndex ) {
650 rEdges.resize (
mEdges.size() );
651 for (
unsigned int i = 0; i <
mEdges.size(); i++) {
654 if (ppAngle8Bit != NULL) {
664 for (
int j = 0; j < iSize; j++ ) {
665 for (
int i = 0; i < iSize; i++ ) {
666 if ( pArray[i] > iMax ) {
670 if ( pArray[i] < iMin ) {
674 pIndexes[j] = iMaxIndex;
675 pArray[iMaxIndex] = iMin;
681 pAbnormities->clear();
684 for ( tPoint.y = 1; tPoint.y < ptImgEdge->height-1; tPoint.y++ ) {
685 unsigned char *pRow0 = (
unsigned char * ) ptImgEdge->imageData + ptImgEdge->width* ( tPoint.y-1 );
686 unsigned char *pRow1 = pRow0 + ptImgEdge->width;
687 unsigned char *pRow2 = pRow1 + ptImgEdge->width;
688 for ( tPoint.x = 1; tPoint.x < ptImgEdge->width-1; tPoint.x++ ) {
689 bAbnormities =
false;
690 if ( pRow1[1] > iEdgeStrength ) {
691 int iNoOfNeighbors = 0;
692 if ( pRow0[0] > iEdgeStrength ) {
694 if ( ( pRow0[1] > iEdgeStrength ) || ( pRow1[0] > iEdgeStrength ) ) {
698 if ( pRow0[1] > iEdgeStrength ) {
700 if ( ( pRow0[0] > iEdgeStrength ) || ( pRow0[2] > iEdgeStrength ) ) {
704 if ( pRow0[2] > iEdgeStrength ) {
706 if ( ( pRow0[1] > iEdgeStrength ) || ( pRow1[2] > iEdgeStrength ) ) {
710 if ( pRow1[0] > iEdgeStrength ) {
712 if ( ( pRow0[0] > iEdgeStrength ) || ( pRow2[0] > iEdgeStrength ) ) {
716 if ( pRow1[2] > iEdgeStrength ) {
718 if ( ( pRow0[2] > iEdgeStrength ) || ( pRow2[2] > iEdgeStrength ) ) {
722 if ( pRow2[0] > iEdgeStrength ) {
724 if ( ( pRow1[0] > iEdgeStrength ) || ( pRow2[1] > iEdgeStrength ) ) {
728 if ( pRow2[1] > iEdgeStrength ) {
730 if ( ( pRow2[0] > iEdgeStrength ) || ( pRow2[2] > iEdgeStrength ) ) {
734 if ( pRow2[2] > iEdgeStrength ) {
736 if ( ( pRow2[1] > iEdgeStrength ) || ( pRow1[2] > iEdgeStrength ) ) {
740 if ( bAbnormities ) {
741 pAbnormities->push_back ( tPoint );
int GetEdgeListSplittedXY(std::vector< cv::Point_< int > > &rEdges, std::vector< unsigned char > **ppAngle8Bit=NULL)
Returns number of edges and edges in the arguments.
static const int pppDirectionWeightsField[4][3][3]
int GetImgDirectionIndex(CvPoint tPoint)
static const CvPoint GetNeighborPoint(CvPoint pPtrCenter, int iNeighborIndex)
void Trace_Simple(CvPoint tPoint, int *pEnd)
std::vector< cv::Range > getSegmentIndexes()
the indexes of the contour segments
void Perform(unsigned char *pImgEdgeStrength, int defEdgeLinkMode=MODE_CONTOUR, void *pImgEdgeDirection=NULL, int defImgEdgeDirectionType=ANGLE_8U)
Starts the edge linking with a certain mode.
static const void SortArrayIndexes(int *pArray, int *pIndexes, const int iSize)
std::vector< CvPoint > mEdges
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.
static const int ANGLE_32F
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.
unsigned char mEdgeInProcess
static const int ppGradientWeightsField[4][9]
static const int ANGLE_64F
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.
std::vector< unsigned char > mAngle8Bit
int mdImgEdgeDirectionType
int getContours(std::vector< std::vector< cv::Point > > &contours, unsigned min_length=0)
Returns the contour as vector of vector points.
void GetAbnormitiesInEdgesImage(IplImage *ptImgEdge, std::vector< CvPoint > *pAbnormities, uchar iEdgeStrength=0)
Find egde contour Abnormities in edge image.
void Trace_Contour(CvPoint tPoint, int *pEnd, unsigned int iCommingFromEdge)
static const int MODE_COMPLEX
Static const variable used to define the methode used to find the contour (linked edges) ...
static const int pppCommingFromEdgeWeightsField[9][3][3]
unsigned char mEdgeProcessed
unsigned char * getImgEdge(CvPoint tPoint)
unsigned char * mpImgEdge
void Trace_Complex(CvPoint tPoint, int *pEnd, unsigned int iCommingFromEdge)
std::vector< cv::Range > mSegments
void Draw(unsigned char *pImgRGB)
Draws the detected contours in a RGB image with radom colours.
void * mpImgEdgeDirection
static const int MODE_GRAIDENT
Static const variable used to define the methode used to find the contour (linked edges) ...
void SumArrayMatrix(int *pMatrixA, int *pMatrixB, int *pSum, const int iSize)
bool mbAllowToModifyTheSources
static const int MODE_CONTOUR
Static const variable used to define the methode used to find the contour (linked edges) ...
static const int ppContourWeightsField[9][9]
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
bool isInImage(const CvPoint &p)
void Trace_Gradient(CvPoint tPoint, int *pEnd)
static const int MODE_SIMPLE
Static const variable used to define the methode used to find the contour (linked edges) ...
unsigned char mEdgeToProcess
static const int ANGLE_8U
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.