leaf-fitting.h
Go to the documentation of this file.
00001 /*
00002 Copyright (C) 2012 Babette Dellen
00003 
00004 Contour fitting algorithm 
00005 
00006 */
00007 
00008 #ifndef LEAF_FITTING
00009 #define LEAF_FITTING
00010 #include <iostream>
00011 //#include "cv.h"
00012 #include <cstdlib>
00013 #include <image.h>
00014 #include <misc.h>
00015 #include <filter.h>
00016 #include <vector>
00017 #define PI 3.14159265
00018 using std::vector;
00019 
00020 
00021 double ContourFittingError(int * contour_pointX, int * contour_pointY,int number_contour_points,image<rgb> *model, double * current_trans)
00022 {
00023   double dist;
00024   //dist=0;
00025   int j;
00026   int width = model->width();
00027   int height = model->height();
00028   int x;
00029   int y;
00030   double meanX=0;
00031   double meanY=0;
00032   double match_point_sum = number_contour_points;
00033   double rotX;
00034   double rotY;
00035   image<float> *dummy = new image<float>(width, height);
00036   // smooth each color channel  
00037   for (int y = 0; y < height; y++) {
00038     for (int x = 0; x < width; x++) {
00039       imRef(dummy, x, y) = 0;
00040       
00041     }
00042   }
00043   
00044   
00045   //transform contour according to parameters
00046   for (j=0;j<number_contour_points;j++)
00047   {//shift contour 
00048   meanX = meanX + contour_pointX[j];
00049   meanY = meanY + contour_pointY[j];
00050   
00051   }
00052   
00053   meanX = meanX/((double)(number_contour_points));
00054   meanY = meanY/((double)(number_contour_points));
00055   
00056   
00057   for (j=0;j<number_contour_points;j++)
00058   {
00059     // rotating + scaling + shifting
00060     rotX = current_trans[0]*((contour_pointX[j]-meanX)*cos(current_trans[3]) - (contour_pointY[j]-meanY)*sin(current_trans[3])) + meanX + current_trans[1];
00061     rotY = current_trans[0]*((contour_pointX[j]-meanX)*sin(current_trans[3]) + (contour_pointY[j]-meanY)*cos(current_trans[3])) + meanY + current_trans[2];
00062   
00063     x = round(rotX);
00064     y = round(rotY);
00065     //imRef(dummy, x, y)
00066     
00067     if ((x>=0)&&(x<width)&&(y>=0)&&(y<height))
00068     {
00069 //       printf("error %d value\n", x);
00070 //       printf("error %d value\n", y);
00071 //       printf("error %8f value\n",imRef(model,x,y).b);
00072       if (imRef(dummy,x,y)==0)
00073       {
00074       imRef(dummy,x,y)=1;
00075       match_point_sum = match_point_sum - (double)(imRef(model,x,y).b)/((double)(170));
00076       //printf("match %f value\n", (double)(imRef(model,x,y).b)/((double)(170)));
00077       }
00078       
00079     }
00080     
00081     
00082   }
00083   
00084   dist = match_point_sum/((double)(number_contour_points));
00085   delete dummy;
00086     
00087 return dist;
00088 }
00089 
00090 
00092 
00093 //****************************************************************************80
00094 
00095 void nelmin_contour (int n, double * start, double * xmin, 
00096   double * ynewlo, double reqmin, double * step, int konvge, int kcount, 
00097   int *icount, int *numres, int *ifault,int * contour_pointX, int * contour_pointY,int number_contour_points,image<rgb> *model)
00098   
00099   
00100 //****************************************************************************80
00101 //
00102 //  Purpose:
00103 //
00104 //    NELMIN minimizes a function using the Nelder-Mead algorithm.
00105 //
00106 //  Discussion:
00107 //
00108 //    This routine seeks the minimum value of a user-specified function.
00109 //
00110 //    Simplex function minimisation procedure due to Nelder+Mead(1965),
00111 //    as implemented by O'Neill(1971, Appl.Statist. 20, 338-45), with
00112 //    subsequent comments by Chambers+Ertel(1974, 23, 250-1), Benyon(1976,
00113 //    25, 97) and Hill(1978, 27, 380-2)
00114 //
00115 //    The function to be minimized must be defined by a function of
00116 //    the form
00117 //
00118 //      function fn ( x, f )
00119 //      double fn
00120 //      double x(*)
00121 //
00122 //    and the name of this subroutine must be declared EXTERNAL in the
00123 //    calling routine and passed as the argument FN.
00124 //
00125 //    This routine does not include a termination test using the
00126 //    fitting of a quadratic surface.
00127 //
00128 //  Licensing:
00129 //
00130 //    This code is distributed under the GNU LGPL license. 
00131 //
00132 //  Modified:
00133 //
00134 //    27 February 2008
00135 //
00136 //  Author:
00137 //
00138 //    Original FORTRAN77 version by R ONeill.
00139 //    C++ version by John Burkardt.
00140 //
00141 //  Reference:
00142 //
00143 //    John Nelder, Roger Mead,
00144 //    A simplex method for function minimization,
00145 //    Computer Journal,
00146 //    Volume 7, 1965, pages 308-313.
00147 //
00148 //    R ONeill,
00149 //    Algorithm AS 47:
00150 //    Function Minimization Using a Simplex Procedure,
00151 //    Applied Statistics,
00152 //    Volume 20, Number 3, 1971, pages 338-345.
00153 //
00154 //  Parameters:
00155 //
00156 //    Input, double FN ( double x[] ), the name of the routine which evaluates
00157 //    the function to be minimized.
00158 //
00159 //    Input, int N, the number of variables.
00160 //
00161 //    Input/output, double START[N].  On input, a starting point
00162 //    for the iteration.  On output, this data may have been overwritten.
00163 //
00164 //    Output, double XMIN[N], the coordinates of the point which
00165 //    is estimated to minimize the function.
00166 //
00167 //    Output, double YNEWLO, the minimum value of the function.
00168 //
00169 //    Input, double REQMIN, the terminating limit for the variance
00170 //    of function values.
00171 //
00172 //    Input, double STEP[N], determines the size and shape of the
00173 //    initial simplex.  The relative magnitudes of its elements should reflect
00174 //    the units of the variables.
00175 //
00176 //    Input, int KONVGE, the convergence check is carried out 
00177 //    every KONVGE iterations.
00178 //
00179 //    Input, int KCOUNT, the maximum number of function 
00180 //    evaluations.
00181 //
00182 //    Output, int *ICOUNT, the number of function evaluations 
00183 //    used.
00184 //
00185 //    Output, int *NUMRES, the number of restarts.
00186 //
00187 //    Output, int *IFAULT, error indicator.
00188 //    0, no errors detected.
00189 //    1, REQMIN, N, or KONVGE has an illegal value.
00190 //    2, iteration terminated because KCOUNT was exceeded without convergence.
00191 //
00192 {
00193   double ccoeff = 0.5;
00194   double del;
00195   double dn;
00196   double dnn;
00197   double ecoeff = 2.0;
00198   double eps = 0.001;
00199   int i;
00200   int ihi;
00201   int ilo;
00202   int j;
00203   int jcount;
00204   int l;
00205   int nn;
00206   double *p;
00207   double *p2star;
00208   double *pbar;
00209   double *pstar;
00210   double rcoeff = 1.0;
00211   double rq;
00212   double x;
00213   double *y;
00214   double y2star;
00215   double ylo;
00216   double ystar;
00217   double z;
00218   double * start_init;
00219 //
00220 //  Check the input parameters.
00221 //
00222   if ( reqmin <= 0.0 )
00223   {
00224     *ifault = 1;
00225     return;
00226   }
00227 
00228   if ( n < 1 )
00229   {
00230     *ifault = 1;
00231     return;
00232   }
00233 
00234   if ( konvge < 1 )
00235   {
00236     *ifault = 1;
00237     return;
00238   }
00239 
00240   p = new double[n*(n+1)];
00241   pstar = new double[n];
00242   p2star = new double[n];
00243   pbar = new double[n];
00244   y = new double[n+1];
00245   //start_init = new double[n];
00246   
00247 //   for ( i = 0; i < n; i++ )
00248 //     { 
00249 //       start_init[i] = start[i];
00250 //     }
00251 //   
00252 
00253   *icount = 0;
00254   *numres = 0;
00255 
00256   jcount = konvge; 
00257   dn = ( double ) ( n );
00258   nn = n + 1;
00259   dnn = ( double ) ( nn );
00260   del = 1.0;
00261   rq = reqmin * dn;
00262 //
00263 //  Initial or restarted loop.
00264 //
00265   for ( ; ; )
00266   {
00267     for ( i = 0; i < n; i++ )
00268     { 
00269       p[i+n*n] = start[i];
00270     }
00271     y[n] = ContourFittingError(contour_pointX, contour_pointY,number_contour_points,model,start);
00272     //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 );
00273     *icount = *icount + 1;
00274 
00275     for ( j = 0; j < n; j++ )
00276     {
00277       x = start[j];
00278       start[j] = start[j] + step[j] * del;
00279       for ( i = 0; i < n; i++ )
00280       {
00281 //      if (i==j)
00282 //      {start[i]=start_init[j] + step[j] * del;
00283 //      p[i+j*n] =start_init[j] + step[j] * del;
00284 //      }
00285 //      else
00286 //      {start[i]=start_init[i];
00287 //      p[i+j*n]=start_init[i];
00288 //      }
00289         
00290           
00291         p[i+j*n] = start[i];
00292       }
00293       y[j] = ContourFittingError(contour_pointX, contour_pointY,number_contour_points,model,start);
00294       //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 );
00295       *icount = *icount + 1;
00296       start[j] = x;
00297     }
00298 //                    
00299 //  The simplex construction is complete.
00300 //                    
00301 //  Find highest and lowest Y values.  YNEWLO = Y(IHI) indicates
00302 //  the vertex of the simplex to be replaced.
00303 //                
00304     ylo = y[0];
00305     ilo = 0;
00306 
00307     for ( i = 1; i < nn; i++ )
00308     {
00309       if ( y[i] < ylo )
00310       {
00311         ylo = y[i];
00312         ilo = i;
00313       }
00314     }
00315 //
00316 //  Inner loop.
00317 //
00318     for ( ; ; )
00319     {
00320       if ( kcount <= *icount )
00321       {
00322         break;
00323       }
00324       *ynewlo = y[0];
00325       ihi = 0;
00326 
00327       for ( i = 1; i < nn; i++ )
00328       {
00329         if ( *ynewlo < y[i] )
00330         {
00331           *ynewlo = y[i];
00332           ihi = i;
00333         }
00334       }
00335 //
00336 //  Calculate PBAR, the centroid of the simplex vertices
00337 //  excepting the vertex with Y value YNEWLO.
00338 //
00339       for ( i = 0; i < n; i++ )
00340       {
00341         z = 0.0;
00342         for ( j = 0; j < nn; j++ )
00343         { 
00344           z = z + p[i+j*n];
00345         }
00346         z = z - p[i+ihi*n];  
00347         pbar[i] = z / dn;
00348       }
00349 //
00350 //  Reflection through the centroid.
00351 //
00352       for ( i = 0; i < n; i++ )
00353       {
00354         pstar[i] = pbar[i] + rcoeff * ( pbar[i] - p[i+ihi*n] );
00355       }
00356       ystar = ContourFittingError(contour_pointX, contour_pointY,number_contour_points,model,pstar);
00357       //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 );
00358       *icount = *icount + 1;
00359 //
00360 //  Successful reflection, so extension.
00361 //
00362       if ( ystar < ylo )
00363       {
00364         for ( i = 0; i < n; i++ )
00365         {
00366           p2star[i] = pbar[i] + ecoeff * ( pstar[i] - pbar[i] );
00367         }
00368         y2star = ContourFittingError(contour_pointX, contour_pointY,number_contour_points,model,p2star);
00369         //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 );
00370         *icount = *icount + 1;
00371 //
00372 //  Check extension.
00373 //
00374         if ( ystar < y2star )
00375         {
00376           for ( i = 0; i < n; i++ )
00377           {
00378             p[i+ihi*n] = pstar[i];
00379           }
00380           y[ihi] = ystar;
00381         }
00382 //
00383 //  Retain extension or contraction.
00384 //
00385         else
00386         {
00387           for ( i = 0; i < n; i++ )
00388           {
00389             p[i+ihi*n] = p2star[i];
00390           }
00391           y[ihi] = y2star;
00392         }
00393       }
00394 //
00395 //  No extension.
00396 //
00397       else
00398       {
00399         l = 0;
00400         for ( i = 0; i < nn; i++ )
00401         {
00402           if ( ystar < y[i] )
00403           {
00404             l = l + 1;
00405           }
00406         }
00407 
00408         if ( 1 < l )
00409         {
00410           for ( i = 0; i < n; i++ )
00411           {
00412             p[i+ihi*n] = pstar[i];
00413           }
00414           y[ihi] = ystar;
00415         }
00416 //
00417 //  Contraction on the Y(IHI) side of the centroid.
00418 //
00419         else if ( l == 0 )
00420         {
00421           for ( i = 0; i < n; i++ )
00422           {
00423             p2star[i] = pbar[i] + ccoeff * ( p[i+ihi*n] - pbar[i] );
00424           }
00425           y2star = ContourFittingError(contour_pointX, contour_pointY,number_contour_points,model,p2star);
00426           //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 );
00427           *icount = *icount + 1;
00428 //
00429 //  Contract the whole simplex.
00430 //
00431           if ( y[ihi] < y2star )
00432           {
00433             for ( j = 0; j < nn; j++ )
00434             {
00435               for ( i = 0; i < n; i++ )
00436               {
00437                 p[i+j*n] = ( p[i+j*n] + p[i+ilo*n] ) * 0.5;
00438                 xmin[i] = p[i+j*n];
00439               }
00440               y[j] = ContourFittingError(contour_pointX, contour_pointY,number_contour_points,model,xmin);
00441               //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 );
00442               *icount = *icount + 1;
00443             }
00444             ylo = y[0];
00445             ilo = 0;
00446 
00447             for ( i = 1; i < nn; i++ )
00448             {
00449               if ( y[i] < ylo )
00450               {
00451                 ylo = y[i];
00452                 ilo = i;
00453               }
00454             }
00455             continue;
00456           }
00457 //
00458 //  Retain contraction.
00459 //
00460           else
00461           {
00462             for ( i = 0; i < n; i++ )
00463             {
00464               p[i+ihi*n] = p2star[i];
00465             }
00466             y[ihi] = y2star;
00467           }
00468         }
00469 //
00470 //  Contraction on the reflection side of the centroid.
00471 //
00472         else if ( l == 1 )
00473         {
00474           for ( i = 0; i < n; i++ )
00475           {
00476             p2star[i] = pbar[i] + ccoeff * ( pstar[i] - pbar[i] );
00477           }
00478           y2star = ContourFittingError(contour_pointX, contour_pointY,number_contour_points,model,p2star);
00479           //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 );
00480           *icount = *icount + 1;
00481 //
00482 //  Retain reflection?
00483 //
00484           if ( y2star <= ystar )
00485           {
00486             for ( i = 0; i < n; i++ )
00487             {
00488               p[i+ihi*n] = p2star[i];
00489             }
00490             y[ihi] = y2star;
00491           }
00492           else
00493           {
00494             for ( i = 0; i < n; i++ )
00495             {
00496               p[i+ihi*n] = pstar[i];
00497             }
00498             y[ihi] = ystar;
00499           }
00500         }
00501       }
00502 //
00503 //  Check if YLO improved.
00504 //
00505       if ( y[ihi] < ylo )
00506       {
00507         ylo = y[ihi];
00508         ilo = ihi;
00509       }
00510       jcount = jcount - 1;
00511 
00512       if ( 0 < jcount )
00513       {
00514         continue;
00515       }
00516 //
00517 //  Check to see if minimum reached.
00518 //
00519       if ( *icount <= kcount )
00520       {
00521         jcount = konvge;
00522 
00523         z = 0.0;
00524         for ( i = 0; i < nn; i++ )
00525         {
00526           z = z + y[i];
00527         }
00528         x = z / dnn;
00529 
00530         z = 0.0;
00531         for ( i = 0; i < nn; i++ )
00532         {
00533           z = z + pow ( y[i] - x, 2 );
00534         }
00535 
00536         if ( z <= rq )
00537         {
00538           break;
00539         }
00540       }
00541     }
00542 //
00543 //  Factorial tests to check that YNEWLO is a local minimum.
00544 //
00545     for ( i = 0; i < n; i++ )
00546     {
00547       xmin[i] = p[i+ilo*n];
00548     }
00549     *ynewlo = y[ilo];
00550 
00551     if ( kcount < *icount )
00552     {
00553       *ifault = 2;
00554       break;
00555     }
00556 
00557     *ifault = 0;
00558 
00559     for ( i = 0; i < n; i++ )
00560     {
00561       del = step[i] * eps;
00562       xmin[i] = xmin[i] + del;
00563       z = ContourFittingError(contour_pointX, contour_pointY,number_contour_points,model,xmin);
00564       //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 );
00565       *icount = *icount + 1;
00566       if ( z < *ynewlo )
00567       {
00568         *ifault = 2;
00569         break;
00570       }
00571       xmin[i] = xmin[i] - del - del;
00572       z = ContourFittingError(contour_pointX, contour_pointY,number_contour_points,model,xmin);
00573       //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 );
00574       *icount = *icount + 1;
00575       if ( z < *ynewlo )
00576       {
00577         *ifault = 2;
00578         break;
00579       }
00580       xmin[i] = xmin[i] + del;
00581     }
00582 
00583     if ( *ifault == 0 )
00584     {
00585       break;
00586     }
00587 //
00588 //  Restart the procedure.
00589 //
00590     for ( i = 0; i < n; i++ )
00591     {
00592       start[i] = xmin[i];
00593     }
00594     del = eps;
00595     *numres = *numres + 1;
00596   }
00597   delete [] p;
00598   delete [] pstar;
00599   delete [] p2star;
00600   delete [] pbar;
00601   delete [] y;
00602 
00603   return;
00604 }
00605 
00606 
00607 
00609 /*
00610  * Segment an image
00611  *
00612  * Returns a color image representing the segmentation.
00613  *
00614  * im: image to segment.
00615  * sigma: to smooth the image.
00616  * c: constant for treshold function.
00617  * min_size: minimum component size (enforced by post-processing stage).
00618  * num_ccs: number of connected components in the segmentation.
00619  */
00620 // image<float> *segment_image(image<rgb> *im, image<rgb> *pc, float sigma, float c, int min_size,
00621 //                        int *num_ccs) {
00622 image<rgb> *leaf_fitting(int ** clusters, image<rgb> *model,image<rgb> *model_area,int num_clusters, double *& fit_score_list, double **& transformation_params) 
00623 {
00624   int width = model->width();
00625   int height = model->height();
00626   int ** segment_contoursX; 
00627   int ** segment_contoursY; 
00628   //double ** transformation_params;
00629   //double ** found_transformation_params;
00630   int current_label;
00631   int * segment_contour_size;
00632   int edge_flag;
00633   int j_x;
00634   int j_y;
00635   int u_x;
00636   int u_y;
00637   int length_model_bound = 0;
00638   
00639   double center_modelX=0;
00640   double center_modelY=0;
00641   double model_size = 0;
00643   for (j_x=0;j_x<width;j_x++)
00644   {
00645   for (j_y=0;j_y<height;j_y++)
00646   {
00647     edge_flag = 0;
00648     //printf("%8d\n",current_label);
00649     if (imRef(model_area,j_x,j_y).b>10)
00650     {
00651        center_modelX = center_modelX + j_x;
00652        center_modelY = center_modelY + j_y;
00653        model_size = model_size +1;
00654        
00655       //test if edge point
00656       
00657        for (u_y = j_y-1; u_y< j_y+1+1; u_y++) 
00658        {
00659               for (u_x = j_x-1; u_x < j_x+1+1; u_x++) 
00660               {
00661              
00662               if ((u_y>=0)&&(u_x>=0)&&(u_x<width)&&(u_y<height))
00663               {
00664               if (imRef(model_area,u_x,u_y).b<10)
00665               {
00666               edge_flag = 1;
00667               }
00668               
00669               }
00670               
00671               
00672               
00673               }
00674        }
00675       
00676         
00677       }
00678     
00679         if (edge_flag==1)
00680         {
00681           length_model_bound = length_model_bound + 1;
00682        
00683         }
00684         
00685     
00686     
00687     
00688     }
00689   
00690   
00691    }
00692   
00693   center_modelX = center_modelX/model_size;
00694   center_modelY = center_modelY/model_size;
00696   
00697   segment_contoursX = (int**)malloc(sizeof(int*)*(num_clusters));
00698   segment_contoursY = (int**)malloc(sizeof(int*)*(num_clusters));
00699   segment_contour_size = (int*)malloc(sizeof(int)*num_clusters);
00700   double * segment_centerX = (double*)malloc(sizeof(double)*num_clusters);
00701   double * segment_centerY = (double*)malloc(sizeof(double)*num_clusters);
00702   double * segment_size = (double*)malloc(sizeof(double)*num_clusters);
00703   transformation_params = (double**)malloc(sizeof(double*)*(num_clusters));
00704   
00705   int u_label;
00706   for (u_label=0;u_label<num_clusters;u_label++)
00707   {
00708   segment_contour_size[u_label]=0;
00709   segment_size[u_label]=0;
00710   transformation_params[u_label] = (double*)malloc(sizeof(double)*4);
00711   segment_contoursX[u_label] = (int*)malloc(sizeof(int)*1);
00712   segment_contoursY[u_label] = (int*)malloc(sizeof(int)*1);
00713   }
00714   
00715   
00716   int contour_size;
00717 for (j_x=0;j_x<width;j_x++)
00718   {
00719   for (j_y=0;j_y<height;j_y++)
00720   {
00721     current_label = clusters[j_y][j_x];
00722     //printf("%8d\n",current_label);
00723     if (current_label>0)
00724     {
00725       segment_centerX[current_label-1] =  segment_centerX[current_label-1] + j_x;
00726       segment_centerY[current_label-1] =  segment_centerY[current_label-1] + j_y;
00727       segment_size[current_label-1] =  segment_size[current_label-1] + 1;
00728        edge_flag = 0;
00729       //test if edge point
00730       
00731        for (u_y = j_y-1; u_y< j_y+1+1; u_y++) 
00732        {
00733               for (u_x = j_x-1; u_x < j_x+1+1; u_x++) 
00734               {
00735              
00736               if ((u_y>=0)&&(u_x>=0)&&(u_x<width)&&(u_y<height))
00737               {
00738               if (clusters[u_y][u_x]!=current_label)
00739               {
00740               edge_flag = 1;
00741               }
00742               
00743               }
00744               
00745               
00746               
00747               }
00748        }
00749       
00750       
00751         if (edge_flag==1)
00752         {//add to boundary list
00753         contour_size = segment_contour_size[current_label-1];
00754         //printf("%8d\n",current_label);
00755         segment_contoursX[current_label-1] = (int*) realloc(segment_contoursX[current_label-1],(contour_size+1)*sizeof(int));
00756         segment_contoursX[current_label-1][contour_size] = j_x;
00757         segment_contoursY[current_label-1] = (int*) realloc(segment_contoursY[current_label-1],(contour_size+1)*sizeof(int));
00758         segment_contoursY[current_label-1][contour_size] = j_y;
00759         segment_contour_size[current_label-1] = contour_size+1;
00760        
00761         }
00762         
00763       
00764       }
00765     
00766     
00767     
00768     }
00769   
00770   
00771    }
00772   
00773   
00774 // fit extracted contours to model contour
00775 
00776  
00777 double initial_parameters_trans [4] = {1,0,0,0};//mean_depth};scale,trans_x,trans_y,angle
00778 double parameters_at_minimum [4] = {100,100,100,100};
00779 double min_fit_value [1] = {100}; 
00780 double required_min = 0.1;
00781 double initial_simplex_step [4] = {1,10,10,0.2};
00782 int konvergence_check = 100;
00783 int max_number_evaluations = 4000;
00784 int used_number_evaluations [1] = {0};
00785 int number_restarts [1] = {0};
00786 int error_detected [1] = {0};
00787 int parameter_trans = 4;  
00788 double final_params [4]; 
00789 double final_min;
00790 double dist;
00791 double x_shift;
00792 double y_shift;
00793 
00794 fit_score_list = (double*)malloc(sizeof(double)*num_clusters);
00795  for (u_label=0;u_label<num_clusters-1;u_label++)
00796   {
00797     //if (((model_size/segment_size[u_label])<10)&&((model_size/segment_size[u_label])>0.1)){
00798     if (((model_size/segment_size[u_label])<2)&&((model_size/segment_size[u_label])>0.5)){
00799 //dist = ContourFittingError(segment_contoursX[u_label], segment_contoursY[u_label],segment_contour_size[u_label],model, initial_parameters_trans);
00800       final_min = 1000;
00801       final_params[0]=0;
00802       final_params[1]=0;
00803       final_params[2]=0;
00804       final_params[3]=0;
00805       for (int u_rot=0;u_rot<18;u_rot++)
00806       {
00807         //int u_rot = 0;
00808         x_shift = center_modelX - segment_centerX[u_label]/segment_size[u_label];
00809         y_shift = center_modelY - segment_centerY[u_label]/segment_size[u_label];
00810         initial_parameters_trans[0]=model_size/segment_size[u_label];
00811     
00812       //printf("scale_param %8f value\n",model_size);
00813       //printf("scale_param %8f value\n",initial_parameters_trans[0]);
00814 
00815         initial_parameters_trans[1]= x_shift;
00816         initial_parameters_trans[2]= y_shift;
00817         initial_parameters_trans[3]=PI*(u_rot*20)/((double)(180));
00818     
00819       //printf("int angle %f value\n",initial_parameters_trans[3]);
00820       //dist = ContourFittingError(segment_contoursX[u_label], segment_contoursY[u_label],segment_contour_size[u_label],model, initial_parameters_trans);
00821       //printf("error %8f value\n", dist);
00822     
00823         nelmin_contour(parameter_trans,initial_parameters_trans, parameters_at_minimum, min_fit_value, required_min, initial_simplex_step, konvergence_check, max_number_evaluations,used_number_evaluations,number_restarts, error_detected,segment_contoursX[u_label],segment_contoursY[u_label],segment_contour_size[u_label],model);
00824       //printf("error %8f value\n", min_fit_value[0]);
00825               if (min_fit_value[0]<final_min)
00826               {
00827                 final_min = min_fit_value[0];
00828                 final_params[0]=parameters_at_minimum[0];
00829                 final_params[1]=parameters_at_minimum[1];
00830                 final_params[2]=parameters_at_minimum[2];
00831                 final_params[3]=parameters_at_minimum[3];
00832               }
00833       }
00834   
00835     //printf("final error %f value\n", final_min);
00836     //printf("size %f value\n", segment_size[u_label]);
00837 
00838       fit_score_list[u_label] = final_min;
00839       transformation_params[u_label][0]=final_params[0];
00840       transformation_params[u_label][1]=final_params[1];
00841       transformation_params[u_label][2]=final_params[2];
00842       transformation_params[u_label][3]=final_params[3];
00843     //printf("scale %f value\n",final_params[0]);
00844     //printf("angle %f value\n",final_params[3]);
00845     //printf("shift x %f value\n",final_params[1]);
00846     //printf("shift y %f value\n",final_params[2]);
00847     }
00848     else
00849     {
00850       fit_score_list[u_label] = 1;}
00851     }
00852     
00853     image<rgb> *output = new image<rgb>(width, height); 
00854   
00855     for (j_x=0;j_x<width;j_x++)
00856     {
00857       for (j_y=0;j_y<height;j_y++)
00858       {
00859         current_label = clusters[j_y][j_x];
00860         if (current_label>0)
00861         {
00862           imRef(output, j_x, j_y).r = (uchar)((1-fit_score_list[current_label-1])*250);
00863           imRef(output, j_x, j_y).g = (uchar)(current_label);//(uchar)((1-fit_score_list[current_label-1]))*250;
00864           imRef(output, j_x, j_y).b = 0;//(uchar)((1-fit_score_list[current_label-1]))*250;
00865         }
00866         else 
00867         {
00868           imRef(output, j_x, j_y).r = (uchar)(255);
00869           imRef(output, j_x, j_y).g = (uchar)(255);
00870           imRef(output, j_x, j_y).b = (uchar)(255);
00871         }
00872       }
00873     }
00874   
00875    
00877 //   image<rgb> *output = new image<rgb>(width, height);
00878 // 
00879 //   // pick random colors for each component
00880 //   rgb *colors = new rgb[width*height];
00881 //   
00882 //   c.r = (uchar)random();
00883 //   c.g = (uchar)random();
00884 //   c.b = (uchar)random();
00885 // 
00886 //   return c;
00887 // }
00888 //   for (int y = 0; y < height; y++) {
00889 //     for (int x = 0; x < width; x++) {
00890 //       int comp = ClusterArray[y][x]-1;
00891 // //       int comp = u->find(y * width + x);
00892 // //       printf ("%8d\n",comp);
00893 //       int comp_fin = labels_new[comp];
00894 // //       printf ("%8d\n",comp_fin);
00895 //       imRef(output, x, y) = clusters[y][x];//colors[comp_fin];
00896 //     }
00897 //   }  
00898 /*
00899   delete [] colors;  
00900   delete u;*/
00901 
00902   //return fitted_depth;
00903   return(output);
00904 }
00905 
00906 #endif


zyonz_image_based_leaf_probing
Author(s): Sergi Foix
autogenerated on Fri Dec 6 2013 23:25:27