segment-image.h
Go to the documentation of this file.
00001 /*
00002 Copyright (C) 2012 Babette Dellen 
00003 (except for color segmentation and Nelder Mead function minimization parts)
00004 
00005 Algorithm for depth segmentation of ToF data and surface model fitting
00006 
00007 */
00008 
00009 #ifndef SEGMENT_IMAGE
00010 #define SEGMENT_IMAGE
00011 #include <iostream>
00012 //#include "cv.h"
00013 #include <cstdlib>
00014 #include <image.h>
00015 #include <misc.h>
00016 #include <filter.h>
00017 #include <vector>
00018 #include "segment-graph.h"
00019 using std::vector;
00020 
00021 // random color
00022 // rgb random_rgb(uchar in_value){ 
00023 //   rgb c;
00024 //   double r;
00025 //   
00026 //   c.r = in_value;//(uchar)random();
00027 //   c.g = in_value;//(uchar)random();
00028 //   c.b = in_value;//(uchar)random();
00029 // 
00030 //   return c;
00031 // }
00032 
00033 rgb random_rgb(){ 
00034   rgb c;
00035   double r;
00036   
00037   c.r = (uchar)random();
00038   c.g = (uchar)random();
00039   c.b = (uchar)random();
00040 
00041   return c;
00042 }
00043 
00044 
00045 
00046 // dissimilarity measure between pixels
00047 static inline float diff(image<float> *r, image<float> *g, image<float> *b,
00048                          int x1, int y1, int x2, int y2) {
00049   return sqrt(square(imRef(r, x1, y1)-imRef(r, x2, y2)) +
00050               square(imRef(g, x1, y1)-imRef(g, x2, y2)) +
00051               square(imRef(b, x1, y1)-imRef(b, x2, y2)));
00052 }
00053 
00054 
00055 
00056 
00057 
00059 double *** setArray3D (image<rgb> *image_input)
00060 {
00061     //allocate memory:, 
00062     double *** Array3D;
00063     
00064      int n_set = image_input->width();
00065      int m_set = image_input->height();
00066      int t_set = 3;
00067     
00068     
00069     Array3D=(double***)malloc(sizeof(double**)*m_set);
00070     
00071     
00072     
00073      
00074         for (int n=0; n<m_set; n++)
00075         {
00076                 Array3D[n] = (double**)malloc(sizeof(double*)*n_set);
00077         for (int m=0; m<n_set; m++)
00078         {
00079         Array3D[n][m] = (double*)malloc(sizeof(double)*t_set);
00080         }
00081                 
00082         }
00083     
00084     
00085 //     for(int t=0;t<t_set;t++)
00086 //             {
00087               
00088     for(int i=0;i<n_set;i++)
00089     {
00090          
00091         for(int j=0;j<m_set;j++)
00092         {
00093            
00094            Array3D[j][i][0]=imRef(image_input, i, j).r;//a_setSequence[(i*m_set + m_set*n_set*t +j)];
00095            Array3D[j][i][1]=imRef(image_input, i, j).g;
00096            Array3D[j][i][2]=imRef(image_input, i, j).b;
00097           }
00098             
00099         }
00100             
00101    //}
00102     
00103     
00104     return (Array3D);
00105 }
00106 
00108 
00109 void BubbleSort(vector<double> *in_values, vector<int> *indices)
00110 {
00111 
00112 //unsigned int vector_length = in_values.size();
00113 int swap_cond = 1;
00114 unsigned int j;
00115 unsigned int j_a;
00116 int swap_count;
00117 double value_1;
00118 double value_2;
00119 int vector_length = in_values->size();
00120 int index_1;
00121 int index_2;
00122 
00123 
00124 for (j_a=0;j_a<in_values->size();j_a++)
00125     {
00126     
00127     indices->push_back(j_a);
00128     }
00129 
00130 
00131   while (swap_cond>0)
00132   {  
00133     swap_count = 0;
00134     for (j=0;j<in_values->size()-1;j++)
00135     {
00136       value_1 = in_values->at(j);
00137       index_1 = indices->at(j);
00138       value_2 = in_values->at(j+1);
00139       index_2 = indices->at(j+1);
00140       if (value_2<value_1)
00141       {//swap
00142       in_values->at(j) = value_2;
00143       in_values->at(j+1) = value_1;
00144       indices->at(j) = index_2;
00145       indices->at(j+1) = index_1;
00146       swap_count = 1;
00147       }
00148       
00149     }
00150     
00151     if (swap_count==0)
00152     {swap_cond = 0;}
00153   }  
00154   //return;
00155 }  
00156 
00157 void ReArrange (vector<int> *label_values_sort,vector<int> *label_values, vector<int> *indices)
00158 {
00159 int index_new;
00160 int vector_length = indices->size();
00161 label_values_sort->assign (vector_length,0);
00162   int j_a;
00163   for (j_a=0;j_a<vector_length;j_a++)
00164     {
00165     index_new =  indices->at(j_a);
00166     //label_values_sort->at(index_new) = label_values->at(j_a);
00167     label_values_sort->at(j_a) = label_values->at(index_new);
00168     }
00169   
00170 //return;
00171 }
00173 //comp_size_list_new,label_list[label_1],number_of_labels_in_list[label_1])
00174 double FittingError(double ** x_val, double ** y_val, double ** z_val, double * param_cur, int * components_elements_number, int * list_of_labels, int num_labels_in_list)//int current_label)
00175 {
00176 int num_p;
00177 int current_label;
00178 int total_number_values=0;
00179 int j_current;
00180 double surf_out = 0;  
00181 
00182 // a=num_p[0], b=num_p[1], c=num_p[2], d=num_p[3], e=num_p[4]
00183   // surf_out = |a*x_val^2 + b*y_val^2 + c*x_val + d*y_val + e - z_val|^2 
00184 for (j_current=0;j_current<num_labels_in_list;j_current++)
00185     {  
00186       
00187     current_label = list_of_labels[j_current];
00188     num_p = components_elements_number[current_label];
00189     for (int j=0;j<num_p; j++)
00190     {
00191       
00192 //      if (x_val[current_label][j]>194)
00193 //      {
00194 //      printf("WARNING!!!");
00195 //      printf("WARNING!!!");
00196 //      printf("WARNING!!!");
00197 //      printf("%8d\n",current_label);
00198 //      printf("%8d\n",j);
00199 //      printf("%8f\n",x_val[current_label][j]);
00200 //      }
00201     surf_out = surf_out +  pow((param_cur[0]*pow(x_val[current_label][j],2) + param_cur[1]*pow(y_val[current_label][j],2) + param_cur[2]*x_val[current_label][j] + param_cur[3]*y_val[current_label][j] + param_cur[4] - z_val[current_label][j]),2);
00202     } 
00203 
00204     total_number_values = total_number_values + num_p;
00205         
00206     }
00207     surf_out = surf_out/((double)(total_number_values));
00208     return (surf_out);  
00209 }
00210 
00211 double FittedDepthValue(double x_val, double y_val, double z_val, double ** param_models,int label)
00212 {
00213   
00214 double depth_current = 0;  
00215 // a=num_p[0], b=num_p[1], c=num_p[2], d=num_p[3], e=num_p[4]
00216   // surf_out = |a*x_val^2 + b*y_val^2 + c*x_val + d*y_val + e - z_val|^2 
00217   
00218 depth_current  = param_models[label][0]*pow(x_val,2) + param_models[label][1]*pow(y_val,2) + param_models[label][2]*x_val + param_models[label][3]*y_val+ param_models[label][4];
00219 
00220 return (depth_current);  
00221   
00222 }
00223 
00224 
00225 
00227 
00228 //****************************************************************************80
00229 
00230 void nelmin (int n, double * start, double * xmin, 
00231   double * ynewlo, double reqmin, double * step, int konvge, int kcount, 
00232   int *icount, int *numres, int *ifault,double ** x_val, double ** y_val, double ** z_val, int * number_of_elements_in_segment, int * current_label_list, int number_current_labels)
00233 
00234 //****************************************************************************80
00235 //
00236 //  Purpose:
00237 //
00238 //    NELMIN minimizes a function using the Nelder-Mead algorithm.
00239 //
00240 //  Discussion:
00241 //
00242 //    This routine seeks the minimum value of a user-specified function.
00243 //
00244 //    Simplex function minimisation procedure due to Nelder+Mead(1965),
00245 //    as implemented by O'Neill(1971, Appl.Statist. 20, 338-45), with
00246 //    subsequent comments by Chambers+Ertel(1974, 23, 250-1), Benyon(1976,
00247 //    25, 97) and Hill(1978, 27, 380-2)
00248 //
00249 //    The function to be minimized must be defined by a function of
00250 //    the form
00251 //
00252 //      function fn ( x, f )
00253 //      double fn
00254 //      double x(*)
00255 //
00256 //    and the name of this subroutine must be declared EXTERNAL in the
00257 //    calling routine and passed as the argument FN.
00258 //
00259 //    This routine does not include a termination test using the
00260 //    fitting of a quadratic surface.
00261 //
00262 //  Licensing:
00263 //
00264 //    This code is distributed under the GNU LGPL license. 
00265 //
00266 //  Modified:
00267 //
00268 //    27 February 2008
00269 //
00270 //  Author:
00271 //
00272 //    Original FORTRAN77 version by R ONeill.
00273 //    C++ version by John Burkardt.
00274 //
00275 //  Reference:
00276 //
00277 //    John Nelder, Roger Mead,
00278 //    A simplex method for function minimization,
00279 //    Computer Journal,
00280 //    Volume 7, 1965, pages 308-313.
00281 //
00282 //    R ONeill,
00283 //    Algorithm AS 47:
00284 //    Function Minimization Using a Simplex Procedure,
00285 //    Applied Statistics,
00286 //    Volume 20, Number 3, 1971, pages 338-345.
00287 //
00288 //  Parameters:
00289 //
00290 //    Input, double FN ( double x[] ), the name of the routine which evaluates
00291 //    the function to be minimized.
00292 //
00293 //    Input, int N, the number of variables.
00294 //
00295 //    Input/output, double START[N].  On input, a starting point
00296 //    for the iteration.  On output, this data may have been overwritten.
00297 //
00298 //    Output, double XMIN[N], the coordinates of the point which
00299 //    is estimated to minimize the function.
00300 //
00301 //    Output, double YNEWLO, the minimum value of the function.
00302 //
00303 //    Input, double REQMIN, the terminating limit for the variance
00304 //    of function values.
00305 //
00306 //    Input, double STEP[N], determines the size and shape of the
00307 //    initial simplex.  The relative magnitudes of its elements should reflect
00308 //    the units of the variables.
00309 //
00310 //    Input, int KONVGE, the convergence check is carried out 
00311 //    every KONVGE iterations.
00312 //
00313 //    Input, int KCOUNT, the maximum number of function 
00314 //    evaluations.
00315 //
00316 //    Output, int *ICOUNT, the number of function evaluations 
00317 //    used.
00318 //
00319 //    Output, int *NUMRES, the number of restarts.
00320 //
00321 //    Output, int *IFAULT, error indicator.
00322 //    0, no errors detected.
00323 //    1, REQMIN, N, or KONVGE has an illegal value.
00324 //    2, iteration terminated because KCOUNT was exceeded without convergence.
00325 //
00326 {
00327   double ccoeff = 0.5;
00328   double del;
00329   double dn;
00330   double dnn;
00331   double ecoeff = 2.0;
00332   double eps = 0.001;
00333   int i;
00334   int ihi;
00335   int ilo;
00336   int j;
00337   int jcount;
00338   int l;
00339   int nn;
00340   double *p;
00341   double *p2star;
00342   double *pbar;
00343   double *pstar;
00344   double rcoeff = 1.0;
00345   double rq;
00346   double x;
00347   double *y;
00348   double y2star;
00349   double ylo;
00350   double ystar;
00351   double z;
00352   double * start_init;
00353 //
00354 //  Check the input parameters.
00355 //
00356   if ( reqmin <= 0.0 )
00357   {
00358     *ifault = 1;
00359     return;
00360   }
00361 
00362   if ( n < 1 )
00363   {
00364     *ifault = 1;
00365     return;
00366   }
00367 
00368   if ( konvge < 1 )
00369   {
00370     *ifault = 1;
00371     return;
00372   }
00373 
00374   p = new double[n*(n+1)];
00375   pstar = new double[n];
00376   p2star = new double[n];
00377   pbar = new double[n];
00378   y = new double[n+1];
00379   //start_init = new double[n];
00380   
00381 //   for ( i = 0; i < n; i++ )
00382 //     { 
00383 //       start_init[i] = start[i];
00384 //     }
00385 //   
00386 
00387   *icount = 0;
00388   *numres = 0;
00389 
00390   jcount = konvge; 
00391   dn = ( double ) ( n );
00392   nn = n + 1;
00393   dnn = ( double ) ( nn );
00394   del = 1.0;
00395   rq = reqmin * dn;
00396 //
00397 //  Initial or restarted loop.
00398 //
00399   for ( ; ; )
00400   {
00401     for ( i = 0; i < n; i++ )
00402     { 
00403       p[i+n*n] = start[i];
00404     }
00405     y[n] = FittingError(x_val,y_val,z_val,start,number_of_elements_in_segment,current_label_list, number_current_labels);//num_p,current_label);//fn ( start );
00406     *icount = *icount + 1;
00407 
00408     for ( j = 0; j < n; j++ )
00409     {
00410       x = start[j];
00411       start[j] = start[j] + step[j] * del;
00412       for ( i = 0; i < n; i++ )
00413       {
00414 //      if (i==j)
00415 //      {start[i]=start_init[j] + step[j] * del;
00416 //      p[i+j*n] =start_init[j] + step[j] * del;
00417 //      }
00418 //      else
00419 //      {start[i]=start_init[i];
00420 //      p[i+j*n]=start_init[i];
00421 //      }
00422         
00423           
00424         p[i+j*n] = start[i];
00425       }
00426       y[j] = FittingError(x_val,y_val,z_val,start,number_of_elements_in_segment,current_label_list, number_current_labels);//num_p,current_label);//fn ( start );
00427       *icount = *icount + 1;
00428       start[j] = x;
00429     }
00430 //                    
00431 //  The simplex construction is complete.
00432 //                    
00433 //  Find highest and lowest Y values.  YNEWLO = Y(IHI) indicates
00434 //  the vertex of the simplex to be replaced.
00435 //                
00436     ylo = y[0];
00437     ilo = 0;
00438 
00439     for ( i = 1; i < nn; i++ )
00440     {
00441       if ( y[i] < ylo )
00442       {
00443         ylo = y[i];
00444         ilo = i;
00445       }
00446     }
00447 //
00448 //  Inner loop.
00449 //
00450     for ( ; ; )
00451     {
00452       if ( kcount <= *icount )
00453       {
00454         break;
00455       }
00456       *ynewlo = y[0];
00457       ihi = 0;
00458 
00459       for ( i = 1; i < nn; i++ )
00460       {
00461         if ( *ynewlo < y[i] )
00462         {
00463           *ynewlo = y[i];
00464           ihi = i;
00465         }
00466       }
00467 //
00468 //  Calculate PBAR, the centroid of the simplex vertices
00469 //  excepting the vertex with Y value YNEWLO.
00470 //
00471       for ( i = 0; i < n; i++ )
00472       {
00473         z = 0.0;
00474         for ( j = 0; j < nn; j++ )
00475         { 
00476           z = z + p[i+j*n];
00477         }
00478         z = z - p[i+ihi*n];  
00479         pbar[i] = z / dn;
00480       }
00481 //
00482 //  Reflection through the centroid.
00483 //
00484       for ( i = 0; i < n; i++ )
00485       {
00486         pstar[i] = pbar[i] + rcoeff * ( pbar[i] - p[i+ihi*n] );
00487       }
00488       ystar = FittingError(x_val,y_val,z_val,p2star,number_of_elements_in_segment,current_label_list, number_current_labels);//num_p,current_label);//fn ( pstar );
00489       *icount = *icount + 1;
00490 //
00491 //  Successful reflection, so extension.
00492 //
00493       if ( ystar < ylo )
00494       {
00495         for ( i = 0; i < n; i++ )
00496         {
00497           p2star[i] = pbar[i] + ecoeff * ( pstar[i] - pbar[i] );
00498         }
00499         y2star = FittingError(x_val,y_val,z_val,p2star,number_of_elements_in_segment,current_label_list, number_current_labels);//num_p,current_label);//fn ( p2star );
00500         *icount = *icount + 1;
00501 //
00502 //  Check extension.
00503 //
00504         if ( ystar < y2star )
00505         {
00506           for ( i = 0; i < n; i++ )
00507           {
00508             p[i+ihi*n] = pstar[i];
00509           }
00510           y[ihi] = ystar;
00511         }
00512 //
00513 //  Retain extension or contraction.
00514 //
00515         else
00516         {
00517           for ( i = 0; i < n; i++ )
00518           {
00519             p[i+ihi*n] = p2star[i];
00520           }
00521           y[ihi] = y2star;
00522         }
00523       }
00524 //
00525 //  No extension.
00526 //
00527       else
00528       {
00529         l = 0;
00530         for ( i = 0; i < nn; i++ )
00531         {
00532           if ( ystar < y[i] )
00533           {
00534             l = l + 1;
00535           }
00536         }
00537 
00538         if ( 1 < l )
00539         {
00540           for ( i = 0; i < n; i++ )
00541           {
00542             p[i+ihi*n] = pstar[i];
00543           }
00544           y[ihi] = ystar;
00545         }
00546 //
00547 //  Contraction on the Y(IHI) side of the centroid.
00548 //
00549         else if ( l == 0 )
00550         {
00551           for ( i = 0; i < n; i++ )
00552           {
00553             p2star[i] = pbar[i] + ccoeff * ( p[i+ihi*n] - pbar[i] );
00554           }
00555           y2star = FittingError(x_val,y_val,z_val,p2star,number_of_elements_in_segment,current_label_list, number_current_labels);//num_p,current_label);//fn ( p2star );
00556           *icount = *icount + 1;
00557 //
00558 //  Contract the whole simplex.
00559 //
00560           if ( y[ihi] < y2star )
00561           {
00562             for ( j = 0; j < nn; j++ )
00563             {
00564               for ( i = 0; i < n; i++ )
00565               {
00566                 p[i+j*n] = ( p[i+j*n] + p[i+ilo*n] ) * 0.5;
00567                 xmin[i] = p[i+j*n];
00568               }
00569               y[j] = FittingError(x_val,y_val,z_val,xmin,number_of_elements_in_segment,current_label_list, number_current_labels);//num_p,current_label);//fn ( xmin );
00570               *icount = *icount + 1;
00571             }
00572             ylo = y[0];
00573             ilo = 0;
00574 
00575             for ( i = 1; i < nn; i++ )
00576             {
00577               if ( y[i] < ylo )
00578               {
00579                 ylo = y[i];
00580                 ilo = i;
00581               }
00582             }
00583             continue;
00584           }
00585 //
00586 //  Retain contraction.
00587 //
00588           else
00589           {
00590             for ( i = 0; i < n; i++ )
00591             {
00592               p[i+ihi*n] = p2star[i];
00593             }
00594             y[ihi] = y2star;
00595           }
00596         }
00597 //
00598 //  Contraction on the reflection side of the centroid.
00599 //
00600         else if ( l == 1 )
00601         {
00602           for ( i = 0; i < n; i++ )
00603           {
00604             p2star[i] = pbar[i] + ccoeff * ( pstar[i] - pbar[i] );
00605           }
00606           y2star = FittingError(x_val,y_val,z_val,p2star,number_of_elements_in_segment,current_label_list, number_current_labels);//num_p,current_label);//fn ( p2star );
00607           *icount = *icount + 1;
00608 //
00609 //  Retain reflection?
00610 //
00611           if ( y2star <= ystar )
00612           {
00613             for ( i = 0; i < n; i++ )
00614             {
00615               p[i+ihi*n] = p2star[i];
00616             }
00617             y[ihi] = y2star;
00618           }
00619           else
00620           {
00621             for ( i = 0; i < n; i++ )
00622             {
00623               p[i+ihi*n] = pstar[i];
00624             }
00625             y[ihi] = ystar;
00626           }
00627         }
00628       }
00629 //
00630 //  Check if YLO improved.
00631 //
00632       if ( y[ihi] < ylo )
00633       {
00634         ylo = y[ihi];
00635         ilo = ihi;
00636       }
00637       jcount = jcount - 1;
00638 
00639       if ( 0 < jcount )
00640       {
00641         continue;
00642       }
00643 //
00644 //  Check to see if minimum reached.
00645 //
00646       if ( *icount <= kcount )
00647       {
00648         jcount = konvge;
00649 
00650         z = 0.0;
00651         for ( i = 0; i < nn; i++ )
00652         {
00653           z = z + y[i];
00654         }
00655         x = z / dnn;
00656 
00657         z = 0.0;
00658         for ( i = 0; i < nn; i++ )
00659         {
00660           z = z + pow ( y[i] - x, 2 );
00661         }
00662 
00663         if ( z <= rq )
00664         {
00665           break;
00666         }
00667       }
00668     }
00669 //
00670 //  Factorial tests to check that YNEWLO is a local minimum.
00671 //
00672     for ( i = 0; i < n; i++ )
00673     {
00674       xmin[i] = p[i+ilo*n];
00675     }
00676     *ynewlo = y[ilo];
00677 
00678     if ( kcount < *icount )
00679     {
00680       *ifault = 2;
00681       break;
00682     }
00683 
00684     *ifault = 0;
00685 
00686     for ( i = 0; i < n; i++ )
00687     {
00688       del = step[i] * eps;
00689       xmin[i] = xmin[i] + del;
00690       z = FittingError(x_val,y_val,z_val,xmin,number_of_elements_in_segment,current_label_list, number_current_labels);//num_p,current_label);//fn ( xmin );
00691       *icount = *icount + 1;
00692       if ( z < *ynewlo )
00693       {
00694         *ifault = 2;
00695         break;
00696       }
00697       xmin[i] = xmin[i] - del - del;
00698       z = FittingError(x_val,y_val,z_val,xmin,number_of_elements_in_segment,current_label_list, number_current_labels);//num_p,current_label);//fn ( xmin );
00699       *icount = *icount + 1;
00700       if ( z < *ynewlo )
00701       {
00702         *ifault = 2;
00703         break;
00704       }
00705       xmin[i] = xmin[i] + del;
00706     }
00707 
00708     if ( *ifault == 0 )
00709     {
00710       break;
00711     }
00712 //
00713 //  Restart the procedure.
00714 //
00715     for ( i = 0; i < n; i++ )
00716     {
00717       start[i] = xmin[i];
00718     }
00719     del = eps;
00720     *numres = *numres + 1;
00721   }
00722   delete [] p;
00723   delete [] pstar;
00724   delete [] p2star;
00725   delete [] pbar;
00726   delete [] y;
00727 
00728   return;
00729 }
00730 
00731 
00732 
00734 /* Color segmentation: 
00735 Copyright (C) 2006 Pedro Felzenszwalb
00736 
00737 This program is free software; you can redistribute it and/or modify
00738 it under the terms of the GNU General Public License as published by
00739 the Free Software Foundation; either version 2 of the License, or
00740 (at your option) any later version.
00741 
00742 This program is distributed in the hope that it will be useful,
00743 but WITHOUT ANY WARRANTY; without even the implied warranty of
00744 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00745 GNU General Public License for more details.
00746 
00747 You should have received a copy of the GNU General Public License
00748 along with this program; if not, write to the Free Software
00749 Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307 USA
00750 */
00751   
00752   
00753 image<rgb> *segment_image(image<rgb> *im, image<rgb> *pc, float sigma, float c, int min_size,
00754                           int *num_ccs, int *num_ccs_fin, int **& ClusterArray) {
00755   int width = im->width();
00756   int height = im->height();
00757 
00758   image<float> *r = new image<float>(width, height);
00759   image<float> *g = new image<float>(width, height);
00760   image<float> *b = new image<float>(width, height);
00761 
00762   // smooth each color channel  
00763   for (int y = 0; y < height; y++) {
00764     for (int x = 0; x < width; x++) {
00765       imRef(r, x, y) = imRef(im, x, y).r;
00766       imRef(g, x, y) = imRef(im, x, y).g;
00767       imRef(b, x, y) = imRef(im, x, y).b;
00768     }
00769   }
00770   image<float> *smooth_r = smooth(r, sigma);
00771   image<float> *smooth_g = smooth(g, sigma);
00772   image<float> *smooth_b = smooth(b, sigma);
00773   delete r;
00774   delete g;
00775   delete b;
00776  
00777   // build graph
00778   edge *edges = new edge[width*height*4];
00779   int num = 0;
00780   for (int y = 0; y < height; y++) {
00781     for (int x = 0; x < width; x++) {
00782       if (x < width-1) {
00783         edges[num].a = y * width + x;
00784         edges[num].b = y * width + (x+1);
00785         edges[num].w = diff(smooth_r, smooth_g, smooth_b, x, y, x+1, y);
00786         num++;
00787       }
00788       
00789       if (y < height-1) {
00790         edges[num].a = y * width + x;
00791         edges[num].b = (y+1) * width + x;
00792         edges[num].w = diff(smooth_r, smooth_g, smooth_b, x, y, x, y+1);
00793         num++;
00794       }
00795       
00796       if ((x < width-1) && (y < height-1)) {
00797         edges[num].a = y * width + x;
00798         edges[num].b = (y+1) * width + (x+1);
00799         edges[num].w = diff(smooth_r, smooth_g, smooth_b, x, y, x+1, y+1);
00800         num++;
00801       }
00802       
00803       if ((x < width-1) && (y > 0)) {
00804         edges[num].a = y * width + x;
00805         edges[num].b = (y-1) * width + (x+1);
00806         edges[num].w = diff(smooth_r, smooth_g, smooth_b, x, y, x+1, y-1);
00807         num++;
00808       }
00809     }
00810   }
00811   delete smooth_r;
00812   delete smooth_g;
00813   delete smooth_b;
00814 
00815   // segment
00816   universe *u = segment_graph(width*height, num, edges, c);
00817   
00818   // post process small components
00819   for (int i = 0; i < num; i++) {
00820     int a = u->find(edges[i].a);
00821     int b = u->find(edges[i].b);
00822     if ((a != b) && ((u->size(a) < min_size) || (u->size(b) < min_size)))
00823       u->join(a, b);
00824   }
00825   delete [] edges;
00826   *num_ccs = u->num_sets();
00827 
00828   
00830  //int ** ClusterArray;
00831  
00832   ClusterArray=(int**)malloc(sizeof(int*)*height);
00833     
00834         for (int k=0; k<height; k++)
00835         {
00836                 ClusterArray[k] = (int*)malloc(sizeof(int)*width);
00837         }
00838    
00839   int * comp_label_list; 
00840   comp_label_list =  (int*)malloc(sizeof(int)*height*width);
00841  
00842   for (int j = 0; j<(height*width); j++)
00843   {comp_label_list[j] = 0;
00844   }
00845   
00846   int j_count = 1;
00847   for (int y = 0; y < height; y++) {
00848     for (int x = 0; x < width; x++) {
00849       int comp = u->find(y * width + x);
00850      
00851       //ClusterArray[y][x] = comp;
00852       if (comp_label_list[comp]==0){
00853         comp_label_list[comp]=j_count;
00854         ClusterArray[y][x] = j_count;
00855         // printf ("%8d\n",j_count);
00856         // printf ("%8d\n",j_count);
00857         j_count = j_count +1;
00858       }
00859      
00860       if (comp_label_list[comp]>0){
00861         ClusterArray[y][x] = comp_label_list[comp];
00862         //printf ("%8d\n",comp_label_list[comp]);
00863       }
00864     }
00865   }  
00866   
00868  /* 
00869  double *** PointCloud;
00870  
00871  PointCloud = setArray3D(pc);*/
00872   
00873   
00875 
00876 double ** ComponentListX;
00877 double ** ComponentListY;
00878 double ** ComponentListZ;
00879 
00880 ComponentListX = (double**)malloc(sizeof(double*)*j_count);
00881 ComponentListY = (double**)malloc(sizeof(double*)*j_count);
00882 ComponentListZ = (double**)malloc(sizeof(double*)*j_count);
00883 
00884 
00885 for (int k=0; k<j_count; k++){
00886   ComponentListX[k] = (double*)malloc(sizeof(double));
00887   ComponentListY[k] = (double*)malloc(sizeof(double));
00888   ComponentListZ[k] = (double*)malloc(sizeof(double));
00889 }
00890 
00891 
00892 int * comp_size_list; 
00893 double * comp_depth_list; 
00894 comp_size_list =  (int*)malloc(sizeof(int)*j_count);
00895 comp_depth_list =  (double*)malloc(sizeof(double)*j_count);
00896 for (int j = 0; j<j_count; j++){
00897   comp_size_list[j] = 0;
00898   comp_depth_list[j] = 0;
00899 }
00900   
00901 // 
00902 // 
00903 
00904 int size_thres = 20;
00905 int label;
00906 int comp_size;
00907 double comp_depth;
00908 double depth_value;
00909 for (int y = 0; y < height; y++) {
00910     for (int x = 0; x < width; x++) {
00911       depth_value = (double)(imRef(pc, x, y).b);
00912       if (depth_value>0){
00913       label = ClusterArray[y][x];
00914       
00915       comp_size = comp_size_list[label-1];
00916       comp_depth = comp_depth_list[label-1];
00917       ComponentListX[label-1] = (double*) realloc(ComponentListX[label-1],(comp_size+1)*sizeof(double));
00918       ComponentListX[label-1][comp_size]= (double)(imRef(pc, x, y).r);
00919       
00920       ComponentListY[label-1] = (double*) realloc(ComponentListY[label-1],(comp_size+1)*sizeof(double));
00921       ComponentListY[label-1][comp_size]= (double)(imRef(pc, x, y).g);
00922       
00923       ComponentListZ[label-1] = (double*) realloc(ComponentListZ[label-1],(comp_size+1)*sizeof(double));
00924       ComponentListZ[label-1][comp_size]= (double)(imRef(pc, x, y).b);
00925       
00926       comp_size_list[label-1] = comp_size + 1;
00927       comp_depth_list[label-1] = comp_depth + (double)(imRef(pc, x, y).b);
00928       }
00929     }
00930 }
00931 
00933 
00934 double ** SurfaceModelsParameters;
00935 double ** SurfaceModelsParameters_new;
00936 ;
00937 SurfaceModelsParameters= (double**)malloc(sizeof(double*)*j_count);
00938 SurfaceModelsParameters_new= (double**)malloc(sizeof(double*)*j_count);
00939 
00940 
00941 for (int k=0; k<j_count; k++)
00942         {
00943                 SurfaceModelsParameters[k] = (double*)malloc(sizeof(double)*5);
00944                 SurfaceModelsParameters_new[k] = (double*)malloc(sizeof(double)*5);
00945                 
00946         }
00947 
00948 
00949 double * ErrorFit; 
00950 ErrorFit = (double*)malloc(sizeof(double)*j_count);;
00951 double * ErrorFit_new; 
00952 ErrorFit_new = (double*)malloc(sizeof(double)*j_count);;
00953 
00954 
00955 double mean_depth;
00956 int list_of_labels_a [1] = {0};
00957 
00958 
00959 double initial_parameters_quadric [5] = {0,0,-0.05,-0.05,0};//mean_depth};
00960 double parameters_at_minimum [5] = {0,0,0,0,0};
00961 double min_fit_value [1] = {100}; 
00962 double required_min = 0.1;
00963 double initial_simplex_step [5] = {0.01,0.01,0.1,0.1,10};
00964 int konvergence_check = 100;
00965 int max_number_evaluations = 2000;
00966 int used_number_evaluations [1] = {0};
00967 int number_restarts [1] = {0};
00968 int error_detected [1] = {0};
00969 int parameter_quadric = 5;  
00970 
00971 
00972 for (int label_j=0;label_j<j_count-1;label_j++){
00973   mean_depth = comp_depth_list[label_j]/((double)(comp_size_list[label_j]));
00974   
00975   initial_parameters_quadric[0]=0;
00976   initial_parameters_quadric[1]=0;
00977   initial_parameters_quadric[2]=-0.05;
00978   initial_parameters_quadric[3]=-0.05;
00979   initial_parameters_quadric[4]=mean_depth-5;
00980   
00981   list_of_labels_a[0] = label_j;
00982   // double fit_error;
00983   // int label_test = j_count-2;//j_count -1;
00984   // 
00985   // fit_error = FittingError(ComponentListX, ComponentListY, ComponentListZ, initial_parameters_quadric,parameter_quadric,label_test);
00986 
00987   // printf ("%8d\n",comp_size_list[label_j]);
00988   if (comp_size_list[label_j]>size_thres){
00989     nelmin (parameter_quadric,initial_parameters_quadric, parameters_at_minimum, 
00990             min_fit_value, required_min, initial_simplex_step, konvergence_check, max_number_evaluations, 
00991             used_number_evaluations,number_restarts, error_detected,ComponentListX, ComponentListY, ComponentListZ, comp_size_list,list_of_labels_a,1);//comp_size_list[label_j],label_j);
00992 
00993     //printf ("%8f\n",round(min_fit_value[0]));
00994 
00995     for (int k_a=0; k_a<5; k_a++){
00996       SurfaceModelsParameters[label_j][k_a] = parameters_at_minimum[k_a];
00997       SurfaceModelsParameters_new[label_j][k_a] = parameters_at_minimum[k_a];
00998     }
00999     
01000     ErrorFit[label_j] = min_fit_value[0];
01001     ErrorFit_new[label_j] = min_fit_value[0];
01002   }else{
01003     for (int k_a=0; k_a<5; k_a++){
01004       SurfaceModelsParameters[label_j][k_a] = 0;//parameters_at_minimum[k_a];
01005       SurfaceModelsParameters_new[label_j][k_a] = 0;//parameters_at_minimum[k_a];               
01006     }
01007   }
01008   
01009   ErrorFit[label_j] = 100;//min_fit_value[0];
01010   ErrorFit_new[label_j] = 100;//min_fit_value[0];
01011   
01012 }
01013 
01014 
01015 
01017 /*
01018 double ** FittedDepthArray;
01019  
01020    FittedDepthArray=(double**)malloc(sizeof(double*)*height);
01021     
01022         for (int k=0; k<height; k++)
01023         {
01024                  FittedDepthArray[k] = (double*)malloc(sizeof(double)*width);
01025                 
01026                 
01027         }*/
01028 
01029 
01030 
01031 
01032 
01033 image<rgb> *fitted_depth = new image<rgb>(width, height);
01034  
01035 double x_val;
01036 double y_val;
01037 double z_val;
01038      
01039 int cluster_label;
01040  for (int y = 0; y < height; y++) {
01041     for (int x = 0; x < width; x++) {
01042       x_val = (double)(imRef(pc, x, y).r);
01043       y_val = (double)(imRef(pc, x, y).g);
01044       z_val = (double)(imRef(pc, x, y).b);
01045       
01046      
01047      cluster_label = ClusterArray[y][x]-1;
01048      
01049     // FittedDepthArray[y][x] = FittedDepthValue(x_val, y_val,z_val,SurfaceModelsParameters,cluster_label);
01050     imRef(fitted_depth, x, y).r = (uchar)(x_val);
01051     imRef(fitted_depth, x, y).g = (uchar)(y_val);
01052     imRef(fitted_depth, x, y).b = (uchar)(FittedDepthValue(x_val,y_val,z_val,SurfaceModelsParameters,cluster_label));//FittepdDepthValue;//(uchar)(comp_depth_list[cluster_label]/(double)(comp_size_list[cluster_label]));//
01053      
01054     }
01055   }  
01056 
01058 
01059 //printf ("Surfaces Fitted to Segments!");
01061 int is_boundary;
01062 
01063 //int is_neighbor;
01064 
01065 int ** NeighborGraph;
01066 
01067 int delta = 4;
01068 double depth;
01069 double depth_neighbor;
01070 double depth_dist;
01071 double depth_thres = 5;
01072 int label_neighbor;
01073 int k_1;
01074 int k_2;
01075   NeighborGraph=(int**)malloc(sizeof(int*)*j_count);
01076     
01077         for (int k=0; k<j_count; k++)
01078         {
01079                 NeighborGraph[k] = (int*)malloc(sizeof(int)*j_count);
01080                 
01081                 
01082         }
01083 
01084 
01085 for (k_1=0; k_1<j_count; k_1++)
01086         {
01087           for (k_2=0; k_2<j_count; k_2++)
01088         
01089           
01090           {
01091         NeighborGraph[k_1][k_2]=0;
01092         }
01093         
01094         }
01095           
01096           
01097 
01098 int y;
01099 int x;
01100 int j_y;
01101 int j_x;
01102 for (y = 0; y < height; y++) {
01103     for (x = 0; x < width; x++) {
01104              
01105       is_boundary = 0;
01106              label = ClusterArray[y][x]-1;
01107             if (comp_size_list[label]>size_thres){
01108              depth = (double)(imRef(fitted_depth, x, y).b);
01109              
01110          //   is_neighbor = 0;
01112            for (j_y = y-1; j_y<y+2; j_y++) {
01113               for (j_x = x-1; j_x<x+2; j_x++) {
01114             
01115               if ((j_y>=0)&&(j_x>=0)&&(j_x<width)&&(j_y<height))
01116               {
01117               label_neighbor = ClusterArray[j_y][j_x]-1;
01118               //printf ("%8d\n",j_x);
01119               if (label!=label_neighbor)
01120               { 
01121               is_boundary = 1;
01122               }
01123               
01124               }
01125                 
01126              
01127               }
01128            }
01129       
01130             }
01131       if (is_boundary==1)
01132       {
01133          for (j_y = y-delta; j_y< y+1+delta; j_y++) {
01134               for (j_x = x-delta; j_x < x+1+delta; j_x++) {
01135             
01136               if ((j_y>=0)&&(j_x>=0)&&(j_x<width)&&(j_y<height))
01137               {
01138                 // check if neighbor
01139                 
01140                 label_neighbor = ClusterArray[j_y][j_x]-1;
01141                 if (comp_size_list[label_neighbor]>size_thres){
01142              //printf ("%8d\n",j_x);
01143                 //if (label_neighbor>label){
01144                 depth_neighbor = (double)(imRef(fitted_depth, j_x, j_y).b);
01145                 depth_dist = abs(depth - depth_neighbor);
01146                 if ((label!=label_neighbor)&&(depth_dist<depth_thres))
01147                 {NeighborGraph[label][label_neighbor]=1;
01148                 NeighborGraph[label_neighbor][label]=1;
01149                  
01150                   //add labels to label vector
01151 
01152                 //NeighborGraph[label-1][label_neighbor-1] = 1;
01153                 //is_neighbor = is_neighbor + 1;
01154                 
01155                 }
01156                 
01157                 //}
01158                 
01159               }
01160               }
01161               
01162               }
01163          }
01164         
01165         
01166       
01167       }
01168       
01169  
01170  
01171       
01172   }
01173 }
01174 
01175 //printf ("Segment Graph Constructed!");     
01176 
01178 vector<double> graph_links;
01179 vector<int> graph_label_1;
01180 vector<int> graph_label_2;
01181 double e_fit_12;
01182 double e_fit_21;
01183 double e_fit_min;
01184 double param_fit[5] = {0,0,0,0,0};
01185 int p_c;
01186 int label_dummy;
01187 
01188 for (k_1=0; k_1<j_count; k_1++) 
01189 {
01190           for (k_2=0; k_2<j_count; k_2++)
01191           {
01192             if (k_1<k_2){
01193                 
01194               if (NeighborGraph[k_1][k_2]==1)
01195                 {
01196                  //compute fitting error
01197                   for (p_c=0;p_c<5;p_c++)
01198                   {
01199                     param_fit[p_c]= SurfaceModelsParameters[k_1][p_c];
01200                   }
01201                     
01202                 
01203 
01204                    
01205                   //e_fit_12 =  FittingError(ComponentListX, ComponentListY, ComponentListZ,param_fit,comp_size_list[label-1],label_dummy);//label_neighbor-1);
01206                   list_of_labels_a[0] = k_2;//label_neighbor-1;
01207                   
01208                   e_fit_12 =  FittingError(ComponentListX, ComponentListY, ComponentListZ,SurfaceModelsParameters[k_1],comp_size_list,list_of_labels_a,1);
01209                   list_of_labels_a[0] =k_1;//label-1;
01210                   e_fit_21 =  FittingError(ComponentListX, ComponentListY, ComponentListZ,SurfaceModelsParameters[k_2],comp_size_list,list_of_labels_a,1);
01211 //                e_fit_12 =  FittingError(ComponentListX, ComponentListY, ComponentListZ,SurfaceModelsParameters[label-1],comp_size_list[label-1],label_neighbor-1);
01212 //                   e_fit_21 =  FittingError(ComponentListX, ComponentListY, ComponentListZ,SurfaceModelsParameters[label_neighbor-1],comp_size_list[label_neighbor-1],label-1);
01213                   if (e_fit_12<e_fit_21)
01214                   {e_fit_min = e_fit_12;}
01215                   else
01216                   {e_fit_min = e_fit_21;}
01217                 
01218                   //add error to link vector              
01219                   graph_links.push_back (e_fit_min);
01220                   graph_label_1.push_back (k_1);
01221                   graph_label_2.push_back (k_2);
01222                 
01223                 }
01224             }
01225         
01226         }
01227         
01228 }
01229 
01230 
01231 
01232 
01233 
01234 // 
01235 // 
01236 // 
01237 // 
01238 
01239 
01240 
01242 
01243 // sort graph links in ascending order      
01244       
01245  vector<int> graph_index;
01246  vector<int> graph_label_1_sort;
01247  vector<int> graph_label_2_sort;
01248  
01249  BubbleSort(&graph_links,&graph_index);
01250  ReArrange(&graph_label_1_sort,&graph_label_1,&graph_index);
01251  ReArrange(&graph_label_2_sort,&graph_label_2,&graph_index);
01252       
01253 
01254 //printf ("Links Sorted!");     
01255 
01256 // ////// Do graph-based merging
01257 
01258 
01259 int * labels_new;
01260 labels_new = (int*)malloc(sizeof(int)*j_count);
01261 
01262 int * comp_size_list_new;
01263 comp_size_list_new = (int*)malloc(sizeof(int)*j_count);
01264 
01265 double * comp_depth_list_new;
01266 comp_depth_list_new = (double*)malloc(sizeof(double)*j_count);
01267 
01268 
01269 for (int label_j=0;label_j<j_count-1;label_j++)
01270 {labels_new[label_j]=label_j;
01271 comp_size_list_new[label_j]=comp_size_list[label_j];//label_j;
01272 comp_depth_list_new[label_j]=comp_depth_list[label_j];
01273 }
01274 
01275 
01276 int ** label_list;
01277 label_list = (int**)malloc(sizeof(int*)*j_count);
01278 
01279 
01280 int * number_of_labels_in_list;
01281 number_of_labels_in_list = (int*)malloc(sizeof(int)*j_count);
01282 for (int k_b=0; k_b<j_count; k_b++)
01283         {
01284                 label_list[k_b] = (int*)malloc(sizeof(int));
01285                 
01286         }
01287 
01288 for (int label_j=0;label_j<j_count-1;label_j++)
01289 {label_list[label_j][0]=label_j;
01290 number_of_labels_in_list[label_j] = 1;
01291 }
01292 
01293 // int aa** = (int**) new int*[10];
01294 // for (i=0..9)
01295 //   aa[i]=(int*) new int[100];
01296 // 
01297 // for (i=0..9)
01298 //   delete [] aa[i];
01299 // delete [] aa;
01300 
01301 
01302 int u_1;
01303 int u_2;
01304 int label_1;
01305 int label_2;
01306 int error_1;
01307 int error_2;
01308 int size_1;
01309 int size_2;
01310 int label_1_total_size;
01311 int label_2_total_size;
01312 double thres_merge = 15;
01313 int number_merged_labels;
01314 double min_error;
01315 int number_of_links = graph_links.size();
01316 int label_keep;
01317 int label_replace;
01318 
01319 
01320 for (int link_index=0;link_index<number_of_links;link_index++)
01321 {
01322 u_1 = graph_label_1_sort.at(link_index);
01323 u_2 = graph_label_2_sort.at(link_index);
01324 
01325 label_1=labels_new[u_1];
01326 label_2=labels_new[u_2];
01327 
01328 error_1 = ErrorFit_new[label_1];
01329 error_2 = ErrorFit_new[label_2];
01330 
01331 size_1 = comp_size_list_new[label_1];
01332 size_2 = comp_size_list_new[label_2];
01333 
01334 //printf ("%8f\n",(graph_links.at(link_index)));
01335 // printf ("%8d\n",(graph_label_1_sort.at(link_index)));
01336 // printf ("%8d\n",(graph_label_2_sort.at(link_index)));
01337 
01338 
01339 if ((size_1>size_thres)&&(size_2>size_thres)&&(label_1!=label_2))
01340 {
01341 // printf("Test!");
01342 // 
01343 // printf("%8d\n",label_1);
01344 // 
01345 // printf("%8d\n",number_of_labels_in_list[label_1]);
01346 //   
01347 // for (int j_test=0;j_test<number_of_labels_in_list[label_1];j_test++)
01348 // {
01349 // printf("%8d\n",label_list[label_1][j_test]);
01350 // 
01351 // }
01352 // for (int i_test=0;i_test<number_of_labels_in_list[label_1];i_test++)
01353 // {
01354 // 
01355 // printf("%8d\n",comp_size_list_new[label_list[label_1][i_test]]);
01356 // }
01357   /*
01358 for (int u_test=0;u_test<5;u_test++)
01359 {
01360 printf("Models!");
01361 printf("%8f\n",SurfaceModelsParameters_new[label_2][u_test]);
01362 }*/
01363   
01365 e_fit_12 =  FittingError(ComponentListX, ComponentListY, ComponentListZ,SurfaceModelsParameters_new[label_1],comp_size_list,label_list[label_2],number_of_labels_in_list[label_2]);    
01366 e_fit_21 =FittingError(ComponentListX,ComponentListY,ComponentListZ,SurfaceModelsParameters_new[label_2],comp_size_list,label_list[label_1],number_of_labels_in_list[label_1]);//list_of_labels_a,1);
01367 
01368 //list_of_labels_a[0] = k_2;//label_neighbor-1;
01369                   
01370 //                e_fit_12 =  FittingError(ComponentListX, ComponentListY, ComponentListZ,SurfaceModelsParameters[k_1],comp_size_list,list_of_labels_a,1);
01371 
01372 
01373 min_error = e_fit_12;
01374 if (e_fit_21<e_fit_12)
01375 {min_error = e_fit_21;}
01376 
01377 // printf("MinError!");
01378 // printf ("%8f\n",(min_error));
01379 
01380 
01381 if (min_error<thres_merge)
01382 {
01383   
01384 // merged label list
01385 number_merged_labels = number_of_labels_in_list[label_1]+number_of_labels_in_list[label_2];
01386 int * merged_labels = (int*)malloc(sizeof(int)*number_merged_labels);
01387  
01388 for (int j_merge_1=0;j_merge_1<number_of_labels_in_list[label_1];j_merge_1++)
01389 {
01390 merged_labels[j_merge_1]= label_list[label_1][j_merge_1]; 
01391 }
01392 
01393 for (int j_merge_2=0;j_merge_2<number_of_labels_in_list[label_2];j_merge_2++)
01394 {
01395 merged_labels[j_merge_2+number_of_labels_in_list[label_1]]= label_list[label_2][j_merge_2]; 
01396 }
01397 
01398 
01399 
01400   
01402 //mean_depth = (comp_depth_list_new[label_1]*comp_size_list_new[label_1] +  comp_depth_list_new[label_2]*comp_size_list_new[label_2])/((double)(comp_size_list_new[label_1]+comp_size_list_new[label_2]));
01403 
01404 mean_depth = (comp_depth_list_new[label_1] +  comp_depth_list_new[label_2])/((double)(comp_size_list_new[label_1]+comp_size_list_new[label_2]));
01405 
01406 initial_parameters_quadric[0]=0;
01407 initial_parameters_quadric[1]=0;
01408 initial_parameters_quadric[2]=-0.05;
01409 initial_parameters_quadric[3]=-0.05;
01410 initial_parameters_quadric[4]=mean_depth-5;
01411 // printf("MeanDepth!");
01412 // printf ("%8f\n",mean_depth);
01413 nelmin (parameter_quadric,initial_parameters_quadric, parameters_at_minimum, 
01414  min_fit_value, required_min, initial_simplex_step, konvergence_check, max_number_evaluations, 
01415  used_number_evaluations,number_restarts, error_detected,ComponentListX, ComponentListY, ComponentListZ,comp_size_list,merged_labels,number_merged_labels);//comp_size_list[label_j],label_j);
01416 
01417  
01418  
01419 //  nelmin (parameter_quadric,initial_parameters_quadric, parameters_at_minimum, 
01420 //  min_fit_value, required_min, initial_simplex_step, konvergence_check, max_number_evaluations, 
01421 //  used_number_evaluations,number_restarts, error_detected,ComponentListX, ComponentListY, ComponentListZ, comp_size_list,list_of_labels_a,1);
01422 //  
01423 // printf("FitValue!");
01424 // printf ("%8f\n",round(min_fit_value[0]));
01425 
01426 if (min_fit_value[0]<10)//<500)
01427 {//do merge
01428 // udpdate arrays
01429 
01430 comp_depth_list_new[label_1] = comp_depth_list_new[label_1] +  comp_depth_list_new[label_2];//mean_depth;
01431 comp_depth_list_new[label_2] = comp_depth_list_new[label_1] +  comp_depth_list_new[label_2];//mean_depth;
01432 comp_size_list_new[label_1] = comp_size_list_new[label_1]+comp_size_list_new[label_2];//size_1 + size_2;
01433 comp_size_list_new[label_2] = comp_size_list_new[label_1]+comp_size_list_new[label_2];//size_1 + size_2;
01434 ErrorFit_new[label_1]=min_fit_value[0];
01435 ErrorFit_new[label_2]=min_fit_value[0];
01436 number_of_labels_in_list[label_1]=number_merged_labels;
01437 number_of_labels_in_list[label_2]=number_merged_labels;
01438 // update SurfaceModelParameters_new
01439 for (int w_1=0;w_1<5;w_1++)
01440 {
01441 SurfaceModelsParameters_new[label_1][w_1] = parameters_at_minimum[w_1];
01442 SurfaceModelsParameters_new[label_2][w_1] = parameters_at_minimum[w_1];
01443 }
01444 
01445 if (label_1<label_2)
01446 {
01447   label_replace = label_2;
01448   label_keep = label_1;
01449 }
01450 else
01451   {
01452   label_replace = label_1;
01453   label_keep = label_2;
01454 }
01455   
01456 // update label_new
01457 for (int w_2=0;w_2<j_count-1;w_2++)
01458 {
01459 if (labels_new[w_2]==label_replace)
01460 {
01461  labels_new[w_2]=label_keep;
01462 }
01463 } 
01464 
01465 //update label_list
01466 label_list[label_keep] = (int*) realloc (label_list[label_keep], number_merged_labels * sizeof(int));
01467 for (int j_merge=0;j_merge<number_merged_labels;j_merge++)
01468 {
01469 label_list[label_keep][j_merge]=merged_labels[j_merge];
01470 }
01471 
01472 }
01473 
01474 // free number_merged_labels
01475 free (merged_labels);
01476 
01477 }
01478 
01479 
01480 }
01481 
01482 
01483 }
01484 
01485 
01487    image<rgb> *output = new image<rgb>(width, height);
01488 
01489   // pick random colors for each component
01490   rgb *colors = new rgb[width*height];
01491   for (int i = 0; i < width*height; i++)
01492     colors[i] = random_rgb();
01493 
01494 
01495 
01496   int * comp_label_list_fin; 
01497   comp_label_list_fin =  (int*)malloc(sizeof(int)*height*width);
01498   
01499  
01500   for (int j = 0; j<(height*width); j++)
01501   {comp_label_list_fin[j] = 0;
01502   }
01503   
01504   
01505   int j_count_fin = 1;
01506   for (int y = 0; y < height; y++) {
01507     for (int x = 0; x < width; x++) {
01508       int comp = ClusterArray[y][x]-1;
01509       int comp_fin = labels_new[comp];
01510      if (comp_size_list_new[comp_fin]>size_thres)
01511      {
01512      if (comp_label_list_fin[comp_fin]==0)
01513      {comp_label_list_fin[comp_fin]=j_count_fin;
01514      ClusterArray[y][x] = j_count_fin;
01515      j_count_fin = j_count_fin +1;}
01516      else
01517      {
01518      ClusterArray[y][x] = comp_label_list_fin[comp_fin];
01519      imRef(output, x, y) = colors[comp_fin];
01520      }
01521      
01522     
01523      }
01524      else
01525      {ClusterArray[y][x] = 0;
01526      imRef(output, x, y) = colors[0];
01527      }
01528      
01529 //      if (comp_label_list_fin[comp_fin]>0)
01530 //      {
01531 //      ClusterArray[y][x] = comp_label_list_fin[comp_fin];
01532 //      imRef(output, x, y) = colors[comp_fin];
01533 //      //printf ("%8d\n",comp_label_list[comp]);
01534 //      }
01535      
01536     }
01537   }  
01538   
01539 // printf("cluster %d labels\n", ClusterArray[120][60]); 
01540   
01541 
01542 *num_ccs_fin = j_count_fin;
01543 
01545   delete [] colors;  
01546   delete u;
01547   delete fitted_depth;
01548   
01549 free(comp_size_list);
01550 free(comp_depth_list);
01551 free(comp_depth_list_new);
01552 free(comp_label_list);
01553 free(comp_size_list_new);
01554 free(labels_new);
01555 free(comp_label_list_fin);
01556 free(ErrorFit);
01557 free(ErrorFit_new);
01558   
01559  for (int k=0; k<j_count; k++)
01560         {
01561                 free(SurfaceModelsParameters[k]);
01562                 free(SurfaceModelsParameters_new[k]);
01563                 free(label_list[k]);
01564                 free(NeighborGraph[k]);
01565                 free(ComponentListX[k]);
01566                 free(ComponentListY[k]);
01567                 free(ComponentListZ[k]);
01568         }
01569         
01570 free(SurfaceModelsParameters_new);
01571 free(SurfaceModelsParameters);
01572 free(label_list);
01573 free(NeighborGraph);
01574 free(ComponentListX);
01575 free(ComponentListY);
01576 free(ComponentListZ);
01577 
01578 
01579         
01580         
01581   
01582   //return fitted_depth;
01583   return output;
01584 }
01585 
01586 #endif


iri_leaf_segmentation
Author(s): Sergi Foix
autogenerated on Fri Dec 6 2013 20:27:24