00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #include <vector>
00033 #include <xmmintrin.h>
00034 #include "largest.h"
00038
00039 struct Cluster {
00041 int area;
00043 short minx;
00045 short maxx;
00047 short miny;
00049 short maxy;
00050 };
00051
00053
00061 int FindConnectedComponents(std::vector<short> &equivTable, int maxClusters,
00062 Image<unsigned char> &limg,
00063 Image<short> &comp, int label)
00064 {
00065 int w = limg.GetWidth();
00066 int h = limg.GetHeight();
00067 equivTable.resize(maxClusters);
00068 unsigned char *imgd = limg.GetData();
00069 short *comd = comp.GetData();
00070 int maxCompVal = maxClusters - 1;
00071 for (int i=0;i<maxClusters;i++)
00072 equivTable[i] = i;
00073 short currComp = 1;
00074
00075 if (imgd[0]==label) {
00076 equivTable[currComp] = currComp;
00077 comd[0] = currComp++;
00078 if (currComp>maxCompVal)
00079 currComp = maxCompVal;
00080 } else
00081 comd[0] = 0;
00082
00083 for (int x=1;x<w;x++) {
00084 int indx = x - 1;
00085 bool ison = (imgd[x]==label);
00086 if (ison && comd[indx]!=0) {
00087 comd[x] = comd[indx];
00088 } else if (ison) {
00089 comd[x] = currComp++;
00090 if (currComp>maxCompVal)
00091 currComp = maxCompVal;
00092 } else
00093 comd[x] = 0;
00094 }
00095
00096 for (int y=1;y<h;y++) {
00097 int indy = y*w - w;
00098 bool ison = (imgd[y*w]==label);
00099 if (ison && comd[indy]!=0) {
00100 comd[y*w] = comd[indy];
00101 } else if (ison) {
00102 comd[y*w] = currComp++;
00103 if (currComp>maxCompVal)
00104 currComp = maxCompVal;
00105 } else
00106 comd[y*w] = 0;
00107 short last = comd[y*w];
00108 for (int x=1;x<8;x++) {
00109 int p = y*w + x;
00110 short compx = equivTable[last];
00111 short compy = equivTable[comd[p-w]];
00112 last = 0;
00113 if (imgd[p]==label) {
00114 if (compx!=0) {
00115 last = compx;
00116 if (compy!=0 && compx!=compy) {
00117 if (compx>compy)
00118 equivTable[compx] = compy;
00119 else
00120 equivTable[compy] = compx;
00121 }
00122 } else if (compy!=0)
00123 last = compy;
00124 else {
00125 last = currComp++;
00126 if (currComp>maxCompVal)
00127 currComp = maxCompVal;
00128 }
00129 }
00130 comd[p] = last;
00131 }
00132 unsigned char *irow = &imgd[y*w];
00133 for (int x=8;x<w;x+=8) {
00134 int p = y*w + x;
00135 #ifdef __SSE__
00136 __m64 zero = _mm_setzero_si64();
00137 __m64 *pos = (__m64*)&irow[x];
00138 if (_mm_movemask_pi8(_mm_cmpeq_pi8(pos[0], zero))==0xff) {
00139 __m64 *cpos = (__m64*)&comd[p];
00140 cpos[0] = zero;
00141 cpos[1] = zero;
00142 continue;
00143 }
00144 #endif
00145 short last = comd[p-1];
00146 for (int i=0;i<8;i++,p++) {
00147 short compx = equivTable[last];
00148 short compy = equivTable[comd[p-w]];
00149 last = 0;
00150 if (irow[x+i]==label) {
00151 if (compx!=0) {
00152 last = compx;
00153 if (compy!=0) {
00154 if (compx!=compy) {
00155 if (compx>compy)
00156 equivTable[compx] = compy;
00157 else
00158 equivTable[compy] = compx;
00159 }
00160 }
00161 } else if (compy!=0)
00162 last = compy;
00163 else {
00164 last = currComp++;
00165 if (currComp>maxCompVal)
00166 currComp = maxCompVal;
00167 }
00168 }
00169 comd[p] = last;
00170 }
00171 }
00172 }
00173 for (short i=0;i<currComp;i++) {
00174 int eq = equivTable[i];
00175 while (eq!=equivTable[eq])
00176 eq = equivTable[eq];
00177 equivTable[i] = eq;
00178 }
00179 int numClusters = 0;
00180 for (short i=0;i<currComp;i++) {
00181 int eq = equivTable[i];
00182 if (eq==i)
00183 equivTable[i] = numClusters++;
00184 else
00185 equivTable[i] = equivTable[eq];
00186 }
00187 #if 0
00188 for (short i=0;i<currComp;i++)
00189 printf("equiv[%i] = %d\r\n", i, equivTable[i]);
00190 #endif
00191 #ifdef __SSE__
00192 _mm_empty();
00193 #endif
00194 return numClusters;
00195 }
00196
00198
00204 void Relabel(Image<short> &comp, std::vector<short> &equivTable, int numClusters, std::vector<Cluster> &clusters)
00205 {
00206 int width = comp.GetWidth();
00207 int height = comp.GetHeight();
00208 short *comd = comp.GetData();
00209 int w = width;
00210 int h = height;
00211 int num = numClusters;
00212 clusters.resize(numClusters);
00213 for (int i=0;i<num;i++) {
00214 clusters[i].area = 0;
00215 clusters[i].minx = 0x7fff;
00216 clusters[i].maxx = 0;
00217 clusters[i].miny = 0x7fff;
00218 clusters[i].maxy = 0;
00219 }
00220 #ifdef __SSE__
00221 __m64 zero = _mm_setzero_si64();
00222 for (int y=0;y<h;y++) {
00223 for (int x=0;x<w;x+=4) {
00224 int k = y*w + x;
00225 __m64 *comp4 = (__m64*)&comd[k];
00226 const __m64 c4 = *comp4;
00227 if ((_mm_movemask_pi8(_m_pcmpeqw(zero, c4))&0xaa)!=0xaa) {
00228 const __m64 c1 = _mm_set1_pi16(comd[k]);
00229 if ((_mm_movemask_pi8(_m_pcmpeqw(c1, c4))&0xaa)==0xaa) {
00230 short val = equivTable[comd[k]];
00231 int j = val - 1;
00232 *comp4 = _mm_set1_pi16(val);
00233 Cluster &cl = clusters[j];
00234 cl.area += 4;
00235 cl.maxy = y;
00236 if (y<cl.miny) cl.miny = y;
00237 if (x<cl.minx) cl.minx = x;
00238 if (x>cl.maxx-3) cl.maxx = x + 3;
00239 } else {
00240 for (int i=0;i<4;i++) {
00241 if (comd[i+k]!=0) {
00242 short val = equivTable[comd[i+k]];
00243 int j = val - 1;
00244 comd[i+k] = val;
00245 Cluster &cl = clusters[j];
00246 cl.area++;
00247 cl.maxy = y;
00248 if (y<cl.miny) cl.miny = y;
00249 if (x<cl.minx) cl.minx = x;
00250 if (x>cl.maxx) cl.maxx = x;
00251 }
00252 }
00253 }
00254 }
00255 }
00256 }
00257 _mm_empty();
00258 #else
00259 for (int y=0;y<h;y++) {
00260 for (int x=0;x<w;x++) {
00261 int i = y*w + x;
00262 if (comd[i]!=0) {
00263 short val = equivTable[comd[i]];
00264 comd[i] = val;
00265 Cluster &cl = clusters[val-1];
00266 cl.area++;
00267 cl.maxy = y;
00268 if (y<cl.miny) cl.miny = y;
00269 if (x<cl.minx) cl.minx = x;
00270 if (x>cl.maxx) cl.maxx = x;
00271 }
00272 }
00273 }
00274 #endif
00275 }
00276
00277
00278 void KeepLargestSegment(Image<unsigned char> &segment,
00279 int fromLabel, int toLabel, int minArea)
00280 {
00281 int width = segment.GetWidth();
00282 int height = segment.GetHeight();
00283 std::vector<short> equivTable;
00284 Image<short> components(width, height);
00285 int numClusters = FindConnectedComponents(equivTable, 4096,
00286 segment, components, fromLabel);
00287 std::vector<Cluster> clusters;
00288 Relabel(components, equivTable, numClusters, clusters);
00289 if (!clusters.size())
00290 return;
00291 unsigned char *segd = segment.GetData();
00292 short *comd = components.GetData();
00293 if (minArea==0) {
00294 int maxSize = 0;
00295 int maxCluster = 0;
00296 for (unsigned int i=0;i<clusters.size();i++) {
00297 if (clusters[i].area>maxSize) {
00298 maxSize = clusters[i].area;
00299 maxCluster = i;
00300 }
00301 }
00302 assert(segment.GetHeight() == height);
00303 assert(components.GetHeight() == height);
00304 maxCluster ++;
00305 if (maxSize<100)
00306 maxCluster = -1;
00307 for (int i=0;i<width*height;i++)
00308 if (segd[i]==fromLabel && comd[i]!=maxCluster)
00309 segd[i] = toLabel;
00310 } else {
00311 for (int i=0;i<width*height;i++)
00312 if (segd[i]==fromLabel && clusters[comd[i]-1].area<minArea)
00313 segd[i] = toLabel;
00314 }
00315 }
00316
00317