Public Member Functions | Static Public Attributes | Private Member Functions | Static Private Member Functions | Private Attributes | Static Private Attributes
tuw::Contour Class Reference

Class to link detected images edges a typical source can be a cvCanny image. More...

#include <contour.h>

List of all members.

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]

Detailed Description

Class to link detected images edges a typical source can be a cvCanny image.

Definition at line 24 of file contour.h.


Constructor & Destructor Documentation

Definition at line 108 of file contour.cpp.

Definition at line 119 of file contour.cpp.


Member Function Documentation

void tuw::Contour::AllocateMemory ( ) [private]

Definition at line 123 of file contour.cpp.

void tuw::Contour::Draw ( unsigned char *  pImgRGB)

Draws the detected contours in a RGB image with radom colours.

Parameters:
pImgRGBtarget image

Definition at line 164 of file contour.cpp.

void tuw::Contour::GetAbnormitiesInEdgesImage ( IplImage *  ptImgEdge,
std::vector< CvPoint > *  pAbnormities,
uchar  iEdgeStrength = 0 
)

Find egde contour Abnormities in edge image.

Returns:
a vetor with points of the position abnormities

Definition at line 681 of file contour.cpp.

int tuw::Contour::getContours ( std::vector< std::vector< cv::Point > > &  contours,
unsigned  min_length = 0 
)

Returns the contour as vector of vector points.

Parameters:
contours
min_lengthon zero all controus are returned
Returns:
number of contours

Definition at line 148 of file contour.cpp.

int tuw::Contour::GetEdgeListSplittedXY ( std::vector< cv::Point_< int > > &  rEdges,
std::vector< unsigned char > **  ppAngle8Bit = NULL 
)

Returns number of edges and edges in the arguments.

Parameters:
listX
listY
Returns:
number of edges used to linke edges to semgents

Definition at line 649 of file contour.cpp.

int tuw::Contour::GetImgDirectionIndex ( CvPoint  tPoint) [private]

Definition at line 194 of file contour.cpp.

unsigned char* tuw::Contour::getImgEdge ( CvPoint  tPoint) [inline, private]

Definition at line 173 of file contour.h.

const CvPoint tuw::Contour::GetNeighborPoint ( CvPoint  pPtrCenter,
int  iNeighborIndex 
) [static, private]

Definition at line 608 of file contour.cpp.

unsigned int tuw::Contour::GetNrOfEdges ( ) [inline]

Returns a number of edges used to linke edges to semgents.

Returns:
number of edges used to linke edges to semgents
See also:
Contour::GetEdgeList

Definition at line 102 of file contour.h.

std::vector< cv::Range > tuw::Contour::getSegmentIndexes ( )

the indexes of the contour segments

Returns:
indexes

Definition at line 753 of file contour.cpp.

void tuw::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.

Parameters:
iImgWidthimage width
iImgHeightimage hight
bAllowToModifyTheSourcesif 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)
iEdgeToProcessthe strength of an edge in the source image, only of interrest if bAllowToModifyTheSources = true
iEdgeInProcessthe strength of an edge in process, only of interrest if bAllowToModifyTheSources = true
iEdgeProcessedthe strength of an edge after it was processed, only of interrest if bAllowToModifyTheSources = true
iEdgeStrengthRemovedthe strength of an edge whenn it was removed, only of interrest if bAllowToModifyTheSources = true

Definition at line 179 of file contour.cpp.

bool tuw::Contour::isInImage ( const CvPoint &  p) [inline, private]

Definition at line 179 of file contour.h.

void tuw::Contour::Linking_Complex ( ) [private]

Definition at line 545 of file contour.cpp.

void tuw::Contour::Linking_Contour ( ) [private]

Definition at line 402 of file contour.cpp.

void tuw::Contour::Linking_Gradient ( ) [private]

Definition at line 488 of file contour.cpp.

void tuw::Contour::Linking_Simple ( ) [private]

Definition at line 272 of file contour.cpp.

void tuw::Contour::markNeighborEdgesAsProcessed ( unsigned char *  pPix) [inline, private]

Definition at line 182 of file contour.h.

void tuw::Contour::Perform ( unsigned char *  pImgEdgeStrength,
int  defEdgeLinkMode = MODE_CONTOUR,
void *  pImgEdgeDirection = NULL,
int  defImgEdgeDirectionType = ANGLE_8U 
)

Starts the edge linking with a certain mode.

Parameters:
pImgEdgeStrengthedge image, where the edge must be at least of the iEdgeStrengthSrc defined in Contour::Init
defEdgeLinkModedefines 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
pImgEdgeDirectionpointer to the edge direction image with the angle information of every edge in the pImgEdgeStrength
defImgEdgeDirectionTypetype 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 tuw::Contour::RelaseMemory ( ) [private]

Definition at line 133 of file contour.cpp.

const void tuw::Contour::SortArrayIndexes ( int *  pArray,
int *  pIndexes,
const int  iSize 
) [static, private]

Definition at line 661 of file contour.cpp.

void tuw::Contour::SumArrayMatrix ( int *  pMatrixA,
int *  pMatrixB,
int *  pSum,
const int  iSize 
) [inline, private]

Definition at line 176 of file contour.h.

void tuw::Contour::Trace_Complex ( CvPoint  tPoint,
int *  pEnd,
unsigned int  iCommingFromEdge 
) [private]

Definition at line 563 of file contour.cpp.

void tuw::Contour::Trace_Contour ( CvPoint  tPoint,
int *  pEnd,
unsigned int  iCommingFromEdge 
) [private]

Definition at line 420 of file contour.cpp.

void tuw::Contour::Trace_Gradient ( CvPoint  tPoint,
int *  pEnd 
) [private]

Definition at line 506 of file contour.cpp.

void tuw::Contour::Trace_Simple ( CvPoint  tPoint,
int *  pEnd 
) [private]

Definition at line 324 of file contour.cpp.


Member Data Documentation

const int tuw::Contour::ANGLE_32F = 32 [static]

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.

Definition at line 38 of file contour.h.

const int tuw::Contour::ANGLE_64F = 64 [static]

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.

Definition at line 43 of file contour.h.

const int tuw::Contour::ANGLE_8U = 8 [static]

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.

Definition at line 33 of file contour.h.

const double tuw::Contour::dPi = 3.1415926535897932384626433832795 [static, private]

Definition at line 150 of file contour.h.

const float tuw::Contour::fPi = 3.1415926535897932384626433832795 [static, private]

Definition at line 149 of file contour.h.

std::vector<unsigned char> tuw::Contour::mAngle8Bit [private]

Definition at line 153 of file contour.h.

Definition at line 141 of file contour.h.

Definition at line 138 of file contour.h.

Definition at line 137 of file contour.h.

unsigned char tuw::Contour::mEdgeInProcess [private]

Definition at line 143 of file contour.h.

unsigned char tuw::Contour::mEdgeProcessed [private]

Definition at line 144 of file contour.h.

std::vector<CvPoint> tuw::Contour::mEdges [private]

Definition at line 152 of file contour.h.

unsigned char tuw::Contour::mEdgeToProcess [private]

Definition at line 142 of file contour.h.

int tuw::Contour::mImgHeight [private]

Definition at line 140 of file contour.h.

int tuw::Contour::mImgWidth [private]

Definition at line 139 of file contour.h.

unsigned int tuw::Contour::mNrOfEdges [private]

Definition at line 154 of file contour.h.

const int tuw::Contour::MODE_COMPLEX = 4 [static]

Static const variable used to define the methode used to find the contour (linked edges)

Definition at line 60 of file contour.h.

const int tuw::Contour::MODE_CONTOUR = 2 [static]

Static const variable used to define the methode used to find the contour (linked edges)

Definition at line 52 of file contour.h.

const int tuw::Contour::MODE_GRAIDENT = 3 [static]

Static const variable used to define the methode used to find the contour (linked edges)

Definition at line 56 of file contour.h.

const int tuw::Contour::MODE_SIMPLE = 1 [static]

Static const variable used to define the methode used to find the contour (linked edges)

Definition at line 48 of file contour.h.

unsigned char* tuw::Contour::mpImgEdge [private]

Definition at line 135 of file contour.h.

Definition at line 136 of file contour.h.

std::vector<cv::Range> tuw::Contour::mSegments [private]

Definition at line 155 of file contour.h.

const int tuw::Contour::ppContourWeightsField [static, private]
Initial value:
 {
    {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}
}

Definition at line 148 of file contour.h.

const int tuw::Contour::ppGradientWeightsField [static, private]
Initial value:
 {
    {3, 5, 6, 8, 2, 0, 7, 1, 4},
    {2, 6, 1, 3, 7, 5, 0, 8, 4},
    {1, 7, 0, 6, 8, 2, 3, 5, 4},
    {0, 8, 1, 7, 5, 3, 2, 6, 4}
}

Definition at line 146 of file contour.h.

const int tuw::Contour::pppCommingFromEdgeWeightsField [static, private]

Definition at line 147 of file contour.h.

const int tuw::Contour::pppDirectionWeightsField [static, private]
Initial value:
 {
    {   {2,1,2}, 
        {4,0,4}, 
        {2,1,2}  
    },
    {   {1,2,4}, 
        {2,0,2}, 
        {4,2,1}  
    },
    {   {2,4,2}, 
        {1,0,1}, 
        {2,4,4}  
    },
    {   {4,2,1}, 
        {2,0,2}, 
        {1,2,4}  
    }
}

Definition at line 145 of file contour.h.


The documentation for this class was generated from the following files:


tuw_ellipses
Author(s):
autogenerated on Sun May 29 2016 02:50:24