00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 #ifndef LEAF_FITTING
00009 #define LEAF_FITTING
00010 #include <iostream>
00011 
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   
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   
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   
00046   for (j=0;j<number_contour_points;j++)
00047   {
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     
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     
00066     
00067     if ((x>=0)&&(x<width)&&(y>=0)&&(y<height))
00068     {
00069 
00070 
00071 
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       
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 
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 
00101 
00102 
00103 
00104 
00105 
00106 
00107 
00108 
00109 
00110 
00111 
00112 
00113 
00114 
00115 
00116 
00117 
00118 
00119 
00120 
00121 
00122 
00123 
00124 
00125 
00126 
00127 
00128 
00129 
00130 
00131 
00132 
00133 
00134 
00135 
00136 
00137 
00138 
00139 
00140 
00141 
00142 
00143 
00144 
00145 
00146 
00147 
00148 
00149 
00150 
00151 
00152 
00153 
00154 
00155 
00156 
00157 
00158 
00159 
00160 
00161 
00162 
00163 
00164 
00165 
00166 
00167 
00168 
00169 
00170 
00171 
00172 
00173 
00174 
00175 
00176 
00177 
00178 
00179 
00180 
00181 
00182 
00183 
00184 
00185 
00186 
00187 
00188 
00189 
00190 
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 
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   
00246   
00247 
00248 
00249 
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 
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     
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 
00282 
00283 
00284 
00285 
00286 
00287 
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       
00295       *icount = *icount + 1;
00296       start[j] = x;
00297     }
00298 
00299 
00300 
00301 
00302 
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 
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 
00337 
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 
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       
00358       *icount = *icount + 1;
00359 
00360 
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         
00370         *icount = *icount + 1;
00371 
00372 
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 
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 
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 
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           
00427           *icount = *icount + 1;
00428 
00429 
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               
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 
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 
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           
00480           *icount = *icount + 1;
00481 
00482 
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 
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 
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 
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       
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       
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 
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 
00611 
00612 
00613 
00614 
00615 
00616 
00617 
00618 
00619 
00620 
00621 
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   
00629   
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     
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       
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     
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       
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         {
00753         contour_size = segment_contour_size[current_label-1];
00754         
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 
00775 
00776  
00777 double initial_parameters_trans [4] = {1,0,0,0};
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     
00798     if (((model_size/segment_size[u_label])<2)&&((model_size/segment_size[u_label])>0.5)){
00799 
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         
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       
00813       
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       
00820       
00821       
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       
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     
00836     
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     
00844     
00845     
00846     
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);
00864           imRef(output, j_x, j_y).b = 0;
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 
00878 
00879 
00880 
00881 
00882 
00883 
00884 
00885 
00886 
00887 
00888 
00889 
00890 
00891 
00892 
00893 
00894 
00895 
00896 
00897 
00898 
00899 
00900 
00901 
00902   
00903   return(output);
00904 }
00905 
00906 #endif