Go to the documentation of this file.00001
00010 #ifndef CONTOUR_H
00011 #define CONTOUR_H
00012
00013 #include <vector>
00014 #include <valarray>
00015
00016 #include <opencv/cv.h>
00017
00018 namespace V4R {
00019
00020
00024 class Contour {
00025 public:
00026
00027 Contour();
00028 ~Contour();
00033 static const int ANGLE_8U;
00038 static const int ANGLE_32F;
00043 static const int ANGLE_64F;
00044
00048 static const int MODE_SIMPLE;
00052 static const int MODE_CONTOUR;
00056 static const int MODE_GRAIDENT;
00060 static const int MODE_COMPLEX;
00061
00062
00063
00074 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 );
00089 void Perform ( unsigned char* pImgEdgeStrength, int defEdgeLinkMode = MODE_CONTOUR, void* pImgEdgeDirection = NULL, int defImgEdgeDirectionType = ANGLE_8U );
00090
00095 void Draw( unsigned char* pImgRGB );
00096
00102 unsigned int GetNrOfEdges() {
00103 return mNrOfEdges;
00104 };
00105
00112 int GetEdgeListSplittedXY (std::vector<cv::Point_<int> > &rEdges, std::vector<unsigned char> **ppAngle8Bit = NULL);
00113
00120 int getContours( std::vector<std::vector<cv::Point> > &contours, unsigned min_length = 0);
00121
00126 std::vector<cv::Range> getSegmentIndexes();
00127
00132 void GetAbnormitiesInEdgesImage ( IplImage *ptImgEdge, std::vector<CvPoint> *pAbnormities, uchar iEdgeStrength = 0 );
00133
00134 private:
00135 unsigned char *mpImgEdge;
00136 void *mpImgEdgeDirection;
00137 int mdImgEdgeDirectionType;
00138 int mdefEdgeLinkMode;
00139 int mImgWidth;
00140 int mImgHeight;
00141 bool mbAllowToModifyTheSources;
00142 unsigned char mEdgeToProcess;
00143 unsigned char mEdgeInProcess;
00144 unsigned char mEdgeProcessed;
00145 static const int pppDirectionWeightsField[4][3][3];
00146 static const int ppGradientWeightsField[4][9];
00147 static const int pppCommingFromEdgeWeightsField[9][3][3];
00148 static const int ppContourWeightsField[9][9];
00149 static const float fPi;
00150 static const double dPi;
00151
00152 std::vector<CvPoint> mEdges;
00153 std::vector<unsigned char> mAngle8Bit;
00154 unsigned int mNrOfEdges;
00155 std::vector<cv::Range> mSegments;
00156
00157 void AllocateMemory();
00158 void RelaseMemory();
00159 void Linking_Simple();
00160 int GetImgDirectionIndex ( CvPoint tPoint );
00161 void Trace_Simple ( CvPoint tPoint, int *pEnd );
00162 void Linking_Complex();
00163 void Trace_Complex ( CvPoint tPoint, int *pEnd, unsigned int iCommingFromEdge );
00164 void Linking_Contour();
00165 void Trace_Contour ( CvPoint tPoint, int *pEnd, unsigned int iCommingFromEdge );
00166 void Linking_Gradient();
00167 void Trace_Gradient ( CvPoint tPoint, int *pEnd );
00168
00169 static const CvPoint GetNeighborPoint ( CvPoint pPtrCenter, int iNeighborIndex );
00170 static const void SortArrayIndexes ( int *pArray, int *pIndexes, const int iSize );
00171
00172
00173 inline unsigned char* getImgEdge ( CvPoint tPoint ) {
00174 return mpImgEdge + ( tPoint.y * mImgWidth + tPoint.x );
00175 };
00176 inline void SumArrayMatrix ( int *pMatrixA, int *pMatrixB, int *pSum, const int iSize ) {
00177 for ( int i = 0; i < iSize; i++ ) pSum[i] = pMatrixA[i] + pMatrixB[i];
00178 };
00179 inline bool isInImage( const CvPoint &p){
00180 return ( ( p.x > 0 ) && ( p.x < mImgWidth-1 ) && ( p.y > 0 ) && ( p.y < mImgHeight-1 ) );
00181 }
00182 inline void markNeighborEdgesAsProcessed(unsigned char *pPix){
00183 pPix[ mImgWidth-1] = mEdgeProcessed;
00184 pPix[ mImgWidth ] = mEdgeProcessed;
00185 pPix[ mImgWidth+1] = mEdgeProcessed;
00186 pPix[-1] = mEdgeProcessed;
00187 pPix[ 1] = mEdgeProcessed;
00188 pPix[-mImgWidth-1] = mEdgeProcessed;
00189 pPix[-mImgWidth ] = mEdgeProcessed;
00190 pPix[-mImgWidth+1] = mEdgeProcessed;
00191 }
00192 };
00193
00194 }
00195
00196 #endif //CONTOUR_H
00197