ipcccf.h
Go to the documentation of this file.
00001 /* 
00002 
00003 This "SOFTWARE" is a free software.
00004 
00005 You are allowed to download, use, modify and redistribute this software.
00006 The software is provided "AS IS" without warranty of any kind.
00007 
00008 Copyright: University of Koblenz, Patrick Sturm
00009 
00010 */
00011 
00012 
00013 /*
00014   CPluginImage* input = dynamic_cast<CPluginImage*>(pd);
00015   if (input && input->GetFormat()=="Matrix<GRAY>")
00016 {
00017           CPluginImage* output=new CPluginImage(input->GetWidth(),input->GetHeight(),
00018     (unsigned char*)new unsigned[input->GetWidth()*input->GetHeight()],
00019     4,true,"Matrix<GRAY>");
00020           if (input->GetBytesPerPixel()==1)
00021 {
00022     ipcConnectedComponentFilter<unsigned char,unsigned> ccf8bit;
00023     ccf8bit.init(input->GetWidth(),input->GetHeight());
00024     ccf8bit.execute(input->GetData(),(unsigned*)output->GetData());
00025 }
00026 */
00027 
00028 
00029 #ifndef _ipcccf_h_
00030 #define _ipcccf_h_
00031 
00032 /***********************************************
00033 iMAge pROcessing cLAsses Version 1.0
00034 
00035 Copyright 2003, Patrick Sturm
00036 ************************************************/
00037 
00038 // Include-Files
00039 template <typename ipcLabelType>
00040 class ipcEqClasses
00041 {
00042 protected:
00043         unsigned size,delta,maxLabel;
00044         ipcLabelType* eqClasses;
00045 
00046         void enlarge(unsigned newSize);
00047         void enlarge();
00048 public:
00049         ipcEqClasses();
00050         virtual ~ipcEqClasses();
00051 
00052         inline void init(int maxNumberOfLabels, float initPercentage = 0.25, float deltaPercentage = 0.1);
00053         inline ipcLabelType resolve();
00054         inline void insert(ipcLabelType label1, ipcLabelType label2);
00055         inline void clear();
00056         inline ipcLabelType newLabel();
00057 
00058         const ipcLabelType* getEQClasses() const { return eqClasses; };
00059 };
00060 
00061 template <typename ipcPixelType, typename ipcLabelType>
00062 class ipcConnectedComponentFilter: protected ipcEqClasses<ipcLabelType>
00063 {
00064 private:
00065         int w,h,d,numOfPixels;
00066 
00067 public:
00068         ipcConnectedComponentFilter();
00069         virtual ~ipcConnectedComponentFilter() {};
00070         inline void init(int width, int height, int depth=1);
00071         ipcLabelType execute(const ipcPixelType* input, ipcLabelType* labelImage);
00072 };
00073 
00074 template <typename ipcLabelType>
00075 struct AlwaysValid
00076 {
00077   bool operator()(int, ipcLabelType) const
00078   { return true; }
00079 };
00080 
00081 template <typename ipcPixelType, typename ipcLabelType, typename ipcSimilarity, typename ipcValidity=AlwaysValid<ipcLabelType> >
00082 class ipcConnectedComponentFilterSim: protected ipcEqClasses<ipcLabelType>
00083 {
00084 private:
00085         int w,h,numOfPixels;
00086 
00087 public:
00088         ipcConnectedComponentFilterSim();
00089         virtual ~ipcConnectedComponentFilterSim() {};
00090         inline void init(int width, int height);
00091         ipcLabelType execute(const ipcPixelType* input, ipcLabelType* labelImage, const ipcSimilarity& sim,
00092                        const ipcValidity& valid=ipcValidity(), int maxr=1);
00093 };
00094 
00095 //------------------------------------------------------------------------
00096 
00097 template <typename ipcLabelType>
00098 ipcEqClasses<ipcLabelType>::ipcEqClasses()
00099 {
00100         maxLabel=0;
00101         eqClasses=NULL;
00102         size=0;
00103         maxLabel=0;
00104 }
00105 
00106 template <typename ipcLabelType>
00107 ipcEqClasses<ipcLabelType>::~ipcEqClasses()
00108 {
00109         if (eqClasses) delete[] eqClasses;
00110 }
00111 
00112 template <typename ipcLabelType>
00113 inline void ipcEqClasses<ipcLabelType>::init(int maxNumberOfLabels, float initPercentage, float deltaPercentage)
00114 {
00115         maxLabel=0;
00116         delta=(unsigned)(deltaPercentage*maxNumberOfLabels);
00117         enlarge((unsigned)(initPercentage*maxNumberOfLabels));
00118         eqClasses[0]=0;
00119 }
00120 
00121 template <typename ipcLabelType>
00122 inline void ipcEqClasses<ipcLabelType>::enlarge(unsigned newSize)
00123 {
00124         if (newSize>size)
00125         {
00126                 ipcLabelType* newEQClasses = new ipcLabelType[newSize];
00127                 if (eqClasses)
00128                 {
00129                         memcpy(newEQClasses,eqClasses,sizeof(ipcLabelType)*(maxLabel+1));
00130                         delete[] eqClasses;
00131                 }
00132                 eqClasses=newEQClasses;
00133                 size=newSize;
00134         }
00135 }
00136 
00137 template <typename ipcLabelType>
00138 inline void ipcEqClasses<ipcLabelType>::enlarge()
00139 {
00140         enlarge(size+delta);
00141 }
00142 
00143 template <typename ipcLabelType>
00144 inline void ipcEqClasses<ipcLabelType>::insert(ipcLabelType label1, ipcLabelType label2)
00145 {
00146         ipcLabelType tmp;
00147 
00148         if (label1==label2) return;
00149 
00150         if (label1<label2)
00151         {
00152                 tmp=label1;
00153                 label1=label2;
00154                 label2=tmp;
00155         }
00156 
00157         while (eqClasses[label1]!=label2)
00158         {
00159                 if (eqClasses[label1]==label1)
00160                         eqClasses[label1]=label2;
00161                 else if (eqClasses[label1]<label2)
00162                 {
00163                         tmp=eqClasses[label1];
00164                         label1=label2;
00165                         label2=tmp;
00166                 }
00167                 else if (eqClasses[label1]>label2)
00168                 {
00169                         tmp=eqClasses[label1];
00170                         eqClasses[label1]=label2;
00171                         label1=tmp;
00172                 }
00173         }
00174 
00175         /*if (eqClasses[label1]==label1)
00176                 eqClasses[label1]=label2;
00177         else if (eqClasses[label1]<label2)
00178                 insert(label2,eqClasses[label1]);
00179         else
00180         {
00181                 tmp=eqClasses[label1];
00182                 eqClasses[label1]=label2;
00183                 insert(tmp,label2);
00184         }*/
00185 }
00186 
00187 template <typename ipcLabelType>
00188 inline ipcLabelType ipcEqClasses<ipcLabelType>::resolve()
00189 {
00190         ipcLabelType label = 0;
00191         for (ipcLabelType i=0; i<=maxLabel; ++i)
00192         {
00193                 if (i==eqClasses[i]) eqClasses[i]=label++;
00194                 else eqClasses[i]=eqClasses[eqClasses[i]];
00195         }
00196         return label;
00197 }
00198 
00199 template <typename ipcLabelType>
00200 inline void ipcEqClasses<ipcLabelType>::clear()
00201 {
00202         maxLabel=0;
00203 }
00204 
00205 template <typename ipcLabelType>
00206 inline ipcLabelType ipcEqClasses<ipcLabelType>::newLabel()
00207 {
00208         maxLabel++;
00209         if (maxLabel>=size) enlarge();
00210         eqClasses[maxLabel]=maxLabel;
00211 
00212         return maxLabel;
00213 }
00214 
00215 //-----------------------------------------------------------
00216 
00217 template <typename ipcPixelType, typename ipcLabelType>
00218 ipcConnectedComponentFilter<ipcPixelType, ipcLabelType>::ipcConnectedComponentFilter()
00219 {
00220         w=h=0;
00221         d=1;
00222 }
00223 
00224 
00225 template <typename ipcPixelType, typename ipcLabelType>
00226 void ipcConnectedComponentFilter<ipcPixelType, ipcLabelType>::init(int width, int height, int depth)
00227 {
00228         w=width;
00229         h=height;
00230         d=depth;
00231         numOfPixels=w*h;
00232         ipcEqClasses<ipcLabelType>::init(numOfPixels,0.25,0.25);
00233 }
00234 
00235 
00236 template <typename ipcPixelType, typename ipcLabelType>
00237 ipcLabelType ipcConnectedComponentFilter<ipcPixelType, ipcLabelType>::execute(const ipcPixelType* input, ipcLabelType* labelImage)
00238 {
00239         int x,y,z,n,off,noff;
00240         int delta[4] = {-1-w, -w, 1-w , -1};
00241         int deltaX[4] = {-1,0,1,-1};
00242         int deltaY[4] = {-1,-1,-1,0};
00243         ipcLabelType labels[4];
00244         int numOfLabels;
00245         ipcLabelType minLabel;
00246         ipcLabelType maxLabel=0;
00247 
00248         off=0;
00249         for (z=0; z<d; ++z)
00250         {
00251                 for (y=0; y<h; ++y)
00252                 {
00253                         for (x=0; x<w; ++x)
00254                         {
00255                                 if (input[off]>0)
00256                                 {
00257                                         numOfLabels=0;
00258                                         for (n=0; n<4; ++n)
00259                                         {
00260                                                 if (x+deltaX[n]>=0 && x+deltaX[n]<w && y+deltaY[n]>=0 && y+deltaY[n]<h)
00261                                                 {
00262                                                         noff=off+delta[n];
00263                                                         if (input[off]==input[noff])
00264                                                                 labels[numOfLabels++]=labelImage[noff];
00265                                                 }
00266                                         }
00267                                         if (numOfLabels>0)
00268                                         {
00269                                                 minLabel=labels[0];
00270                                                 for (n=1; n<numOfLabels; ++n)
00271                                                         if (labels[n]<minLabel) minLabel=labels[n];
00272                                         }
00273                                         else minLabel=this->newLabel();
00274                                         labelImage[off]=minLabel;
00275                                         if (labelImage[off]>maxLabel) maxLabel=labelImage[off];
00276                                         for (n=0; n<numOfLabels; ++n)
00277                                                 this->insert(minLabel,labels[n]);
00278                                 }
00279                                 else labelImage[off]=0;
00280                                 off++;
00281                         }
00282                 }
00283         }
00284         this->resolve();
00285         for (off=0; off<numOfPixels; ++off)
00286                 labelImage[off]=this->eqClasses[labelImage[off]];
00287         return (ipcLabelType)maxLabel;
00288 }
00289 
00290 //-----------------------------------------------------------
00291 
00292 template <typename ipcPixelType, typename ipcLabelType, typename ipcSimilarity, typename ipcValidity>
00293 ipcConnectedComponentFilterSim<ipcPixelType, ipcLabelType, ipcSimilarity, ipcValidity>::ipcConnectedComponentFilterSim()
00294 {
00295         w=h=0;
00296 }
00297 
00298 
00299 template <typename ipcPixelType, typename ipcLabelType, typename ipcSimilarity, typename ipcValidity>
00300 void ipcConnectedComponentFilterSim<ipcPixelType, ipcLabelType, ipcSimilarity, ipcValidity>::init(int width, int height)
00301 {
00302         w=width;
00303         h=height;
00304         numOfPixels=w*h;
00305         ipcEqClasses<ipcLabelType>::init(w*h,0.25,0.25);
00306 }
00307 
00308 template <typename ipcPixelType, typename ipcLabelType, typename ipcSimilarity, typename ipcValidity>
00309 ipcLabelType ipcConnectedComponentFilterSim<ipcPixelType, ipcLabelType, ipcSimilarity, ipcValidity>::execute(const ipcPixelType* input, ipcLabelType* labelImage, const ipcSimilarity& sim, const ipcValidity& valid, int maxr)
00310 {
00311         int x,y,n,off,noff;
00312         int delta[4] = {-1-w, -w, 1-w , -1};
00313         int deltaX[4] = {-1,0,1,-1};
00314         int deltaY[4] = {-1,-1,-1,0};
00315         ipcLabelType labels[4];
00316         int numOfLabels;
00317         ipcLabelType minLabel;
00318 
00319         off=0;
00320         for (y=0; y<h; ++y)
00321         {
00322                 for (x=0; x<w; ++x)
00323                 {
00324                         if (valid(off,input[off]))
00325                         {
00326                                 numOfLabels=0;
00327                                 for (n=0; n<4; ++n)
00328                                 {
00329                                         if (x+deltaX[n]>=0 && x+deltaX[n]<w && y+deltaY[n]>=0 && y+deltaY[n]<h)
00330                                         {
00331                                                 noff=off+delta[n];
00332                                                 if (valid(noff,input[noff]) && sim(input[off],input[noff]))
00333                                                         labels[numOfLabels++]=labelImage[noff];
00334                                         }
00335                                 }
00336                                 if (numOfLabels>0)
00337                                 {
00338                                         minLabel=labels[0];
00339                                         for (n=1; n<numOfLabels; ++n)
00340                                                 if (labels[n]<minLabel) minLabel=labels[n];
00341                                 }
00342                                 else
00343         {
00344           // Robocup 2010 HACK. Old:
00345           //
00346           // minLabel=this->newLabel();
00347           //
00348           // New: check all neighbors within certain distance for similarity instead of
00349           // direct neighbors. If this works, make it part of the real code.. and faster
00350           for ( int rmax = 2; rmax < maxr; ++rmax )
00351           {
00352             for ( int r = 2; r <= rmax; ++r )
00353             {
00354               for ( int ny = y-r; ny <= y+r; ++ny )
00355               {
00356                 for ( int nx = x-r; nx <= x+r; ++nx )
00357                 {
00358                   if ( ny < 0 || ny >= h || nx < 0 || nx >= w )
00359                     continue;
00360                   noff = ny*w+nx;
00361                   if ( !valid( noff, input[noff] ) )
00362                     continue;
00363                   if ( sim( input[off], input[noff] ) )
00364                   {
00365                     if ( numOfLabels < 4 )
00366                       labels[numOfLabels++]=labelImage[ny*w+nx];
00367                     else if ( labelImage[ny*w+nx] < labels[3] )
00368                       labels[3]=labelImage[ny*w+nx];
00369                   } // if
00370                 } // for nx
00371               } // for ny
00372               
00373               if ( numOfLabels > 0 )
00374               {
00375                 break;
00376               }
00377             } // for r
00378             if ( numOfLabels > 0 )
00379             {
00380               break;
00381             }
00382           } // for rmax
00383           if ( numOfLabels > 0 )
00384           {
00385             minLabel=labels[0];
00386             for (n=1; n<numOfLabels; ++n)
00387               if (labels[n]<minLabel) minLabel=labels[n];
00388           }
00389           else minLabel = this->newLabel();
00390         } // else
00391                                 labelImage[off]=minLabel;
00392                                 if (labelImage[off]==1)
00393                                         off=off;
00394                                 for (n=0; n<numOfLabels; ++n)
00395                                         this->insert(minLabel,labels[n]);
00396                         }
00397                         else labelImage[off]=0; // not a valid pixel
00398                         off++;
00399                 }
00400         }
00401         ipcLabelType maxLabel = 0;
00402         this->resolve();
00403         for (off=0; off<numOfPixels; ++off)
00404         {
00405                 labelImage[off]=this->eqClasses[labelImage[off]];
00406                 if (labelImage[off]>maxLabel) maxLabel=labelImage[off];
00407         }
00408         return maxLabel;
00409 }
00410 
00411 #endif


or_libs
Author(s): raphael
autogenerated on Mon Oct 6 2014 02:53:18