vl_covdet.c
Go to the documentation of this file.
00001 
00008 /*
00009 Copyright (C) 2007-12 Karel Lencl, Andrea Vedaldi and Michal Perdoch.
00010 All rights reserved.
00011 
00012 This file is part of the VLFeat library and is made available under
00013 the terms of the BSD license (see the COPYING file).
00014 */
00015 
00016 #include <mexutils.h>
00017 #include <vl/covdet.h>
00018 #include <vl/mathop.h>
00019 #include <vl/sift.h>
00020 #include <vl/liop.h>
00021 
00022 #include <math.h>
00023 #include <assert.h>
00024 
00025 /* option codes */
00026 enum {
00027   opt_method = 0,
00028   opt_octave_resolution,
00029   opt_double_image,
00030   opt_peak_threshold,
00031   opt_edge_threshold,
00032   opt_laplacian_peak_threshold,
00033   opt_estimate_orientation,
00034   opt_estimate_affine_shape,
00035   opt_frames,
00036   opt_descriptor,
00037   opt_liop_bins,
00038   opt_liop_neighbours,
00039   opt_liop_threshold,
00040   opt_liop_radius,
00041   opt_patch_resolution,
00042   opt_patch_relative_smoothing,
00043   opt_patch_relative_extent,
00044   opt_verbose
00045 } ;
00046 
00047 /* options */
00048 vlmxOption  options [] = {
00049   {"Method",                1,   opt_method                  },
00050   {"OctaveResolution",      1,   opt_octave_resolution       },
00051   {"DoubleImage",           1,   opt_double_image            },
00052   {"PeakThreshold",         1,   opt_peak_threshold          },
00053   {"EdgeThreshold",         1,   opt_edge_threshold          },
00054   {"LaplacianPeakThreshold",1,   opt_laplacian_peak_threshold},
00055 
00056   {"EstimateOrientation",   1,   opt_estimate_orientation    },
00057   {"EstimateAffineShape",   1,   opt_estimate_affine_shape   },
00058 
00059   {"Frames",                1,   opt_frames                  },
00060 
00061   {"Descriptor",            1,   opt_descriptor              },
00062   {"LiopNumSpatialBins",    1,   opt_liop_bins               },
00063   {"LiopNumNeighbours",     1,   opt_liop_neighbours         },
00064   {"LiopIntensityThreshold",1,   opt_liop_threshold          },
00065   {"LiopRadius",            1,   opt_liop_radius             },
00066   {"PatchResolution",       1,   opt_patch_resolution        },
00067   {"PatchRelativeExtent",   1,   opt_patch_relative_extent   },
00068   {"PatchRelativeSmoothing",1,   opt_patch_relative_smoothing},
00069   {"Verbose",               0,   opt_verbose                 },
00070   {0,                       0,   0                           }
00071 } ;
00072 
00073 
00075 typedef enum _VlCovDetDescritporType {
00076   VL_COVDET_DESC_NONE = 0,
00077   VL_COVDET_DESC_PATCH,
00078   VL_COVDET_DESC_SIFT,
00079   VL_COVDET_DESC_LIOP,
00080   VL_COVDET_DESC_NUM
00081 } VlCovDetDescriptorType ;
00082 
00083 const char* vlCovDetDescriptorNames [VL_COVDET_DESC_NUM] =
00084 {
00085     "None", "Patch", "SIFT","LIOP"
00086 } ;
00087 
00088 VlEnumerator vlCovDetDescriptorTypes [VL_COVDET_DESC_NUM] =
00089 {
00090   {"None" ,   (vl_index)VL_COVDET_DESC_NONE             },
00091   {"Patch",   (vl_index)VL_COVDET_DESC_PATCH            },
00092   {"SIFT",    (vl_index)VL_COVDET_DESC_SIFT             },
00093   {"LIOP",    (vl_index)VL_COVDET_DESC_LIOP             }
00094 } ;
00095 
00101 static mxArray *
00102 _createArrayFromScaleSpace(VlScaleSpace const *ss)
00103 {
00104   mxArray *data_array = NULL;
00105   vl_size numOctaves, numSubdivisions ;
00106   vl_index o ;
00107   VlScaleSpaceGeometry geom ;
00108 
00109   if (ss == NULL) {
00110     return mxCreateDoubleMatrix(0,0,mxREAL);
00111   }
00112 
00113   geom = vl_scalespace_get_geometry(ss) ;
00114 
00115   numOctaves = geom.lastOctave - geom.firstOctave + 1 ;
00116   numSubdivisions = geom.octaveLastSubdivision - geom.octaveFirstSubdivision + 1 ;
00117 
00118   data_array = mxCreateCellMatrix(1, numOctaves);
00119   for (o = geom.firstOctave ; o <= geom.lastOctave ; ++o) {
00120     VlScaleSpaceOctaveGeometry oct = vl_scalespace_get_octave_geometry(ss, o) ;
00121     float const * octave = vl_scalespace_get_level_const(ss, o, geom.octaveFirstSubdivision) ;
00122     mwSize dims [3] = {oct.width, oct.height, numSubdivisions} ;
00123     mxArray * octave_array = mxCreateNumericArray(3, dims, mxSINGLE_CLASS, mxREAL) ;
00124     memcpy(mxGetData(octave_array),
00125            octave, oct.width * oct.height * numSubdivisions * sizeof(float)) ;
00126     mxSetCell(data_array, o - geom.firstOctave, octave_array) ;
00127   }
00128 
00129   {
00130     const char* names[] = {
00131       "firstOctave",
00132       "lastOctave",
00133       "octaveResolution",
00134       "octaveFirstSubdivision",
00135       "octaveLastSubdivision",
00136       "sigma0",
00137       "data" };
00138     mxArray * array = mxCreateStructMatrix(1, 1, 7, names) ;
00139     mxSetFieldByNumber(array, 0, 0, vlmxCreatePlainScalar((double)geom.firstOctave)) ;
00140     mxSetFieldByNumber(array, 0, 1, vlmxCreatePlainScalar((double)geom.lastOctave)) ;
00141     mxSetFieldByNumber(array, 0, 2, vlmxCreatePlainScalar((double)geom.octaveResolution)) ;
00142     mxSetFieldByNumber(array, 0, 3, vlmxCreatePlainScalar((double)geom.octaveFirstSubdivision)) ;
00143     mxSetFieldByNumber(array, 0, 4, vlmxCreatePlainScalar((double)geom.octaveLastSubdivision)) ;
00144     mxSetFieldByNumber(array, 0, 5, vlmxCreatePlainScalar(geom.baseScale)) ;
00145     mxSetFieldByNumber(array, 0, 6, data_array);
00146     return array ;
00147   }
00148 }
00149 
00161 static void
00162 flip_descriptor (float *dst, float const *src)
00163 {
00164   int const BO = 8 ;  /* number of orientation bins */
00165   int const BP = 4 ;  /* number of spatial bins     */
00166   int i, j, t ;
00167 
00168   for (j = 0 ; j < BP ; ++j) {
00169     int jp = BP - 1 - j ;
00170     for (i = 0 ; i < BP ; ++i) {
00171       int o  = BO * i + BP*BO * j  ;
00172       int op = BO * i + BP*BO * jp ;
00173       dst [op] = src[o] ;
00174       for (t = 1 ; t < BO ; ++t)
00175         dst [BO - t + op] = src [t + o] ;
00176     }
00177   }
00178 }
00179 
00184 void
00185 mexFunction(int nout, mxArray *out[],
00186             int nin, const mxArray *in[])
00187 {
00188   enum {IN_I = 0, IN_END} ;
00189   enum {OUT_FRAMES=0, OUT_DESCRIPTORS, OUT_INFO, OUT_END} ;
00190 
00191   int verbose = 0 ;
00192   int opt ;
00193   int next = IN_END ;
00194   mxArray const *optarg ;
00195   VlEnumerator *pair ;
00196 
00197   float const *image ;
00198   vl_size numCols, numRows ;
00199 
00200   VlCovDetMethod method = VL_COVDET_METHOD_DOG;
00201   vl_bool estimateAffineShape = VL_FALSE ;
00202   vl_bool estimateOrientation = VL_FALSE ;
00203 
00204   vl_bool doubleImage = VL_TRUE ;
00205   vl_index octaveResolution = -1 ;
00206   double edgeThreshold = -1 ;
00207   double peakThreshold = -1 ;
00208   double lapPeakThreshold = -1 ;
00209 
00210   int descriptorType = -1 ;
00211   vl_index patchResolution = -1 ;
00212   double patchRelativeExtent = -1 ;
00213   double patchRelativeSmoothing = -1 ;
00214   float *patch = NULL ;
00215   float *patchXY = NULL ;
00216 
00217   vl_int liopNumSpatialBins = 6;
00218   vl_int liopNumNeighbours = 4;
00219   float liopRadius = 6.0;
00220   float liopIntensityThreshold = VL_NAN_F ;
00221 
00222   double boundaryMargin = 2.0 ;
00223 
00224   double * userFrames = NULL ;
00225   vl_size userFrameDimension = 0 ;
00226   vl_size numUserFrames = 0 ;
00227 
00228   VL_USE_MATLAB_ENV ;
00229 
00230   /* -----------------------------------------------------------------
00231    *                                               Check the arguments
00232    * -------------------------------------------------------------- */
00233 
00234   if (nin < IN_END) {
00235     vlmxError(vlmxErrNotEnoughInputArguments, 0) ;
00236   } else if (nout > OUT_END) {
00237     vlmxError(vlmxErrTooManyOutputArguments, 0) ;
00238   }
00239 
00240   if (mxGetNumberOfDimensions(IN(I)) != 2 ||
00241       mxGetClassID(IN(I)) != mxSINGLE_CLASS){
00242     vlmxError(vlmxErrInvalidArgument, "I must be a matrix of class SINGLE.") ;
00243   }
00244 
00245   image = (float*) mxGetData(IN(I)) ;
00246   numRows = mxGetM(IN(I)) ;
00247   numCols = mxGetN(IN(I)) ;
00248 
00249   while ((opt = vlmxNextOption (in, nin, options, &next, &optarg)) >= 0) {
00250 
00251     switch (opt) {
00252 
00253     case opt_verbose :
00254       ++ verbose ;
00255       break ;
00256 
00257     case opt_method:
00258       pair = vlmxDecodeEnumeration(optarg, vlCovdetMethods, VL_TRUE) ;
00259       if (pair == NULL) {
00260         vlmxError(vlmxErrInvalidArgument, "METHOD is not a supported detection method.") ;
00261       }
00262       method = (VlCovDetMethod)pair->value ;
00263       break;
00264 
00265       case opt_descriptor:
00266         pair = vlmxDecodeEnumeration(optarg, vlCovDetDescriptorTypes, VL_TRUE) ;
00267         if (pair == NULL) {
00268           vlmxError(vlmxErrInvalidArgument, "DESCRIPTOR is not a supported descriptor.") ;
00269         }
00270         descriptorType = (VlCovDetDescriptorType)pair->value ;
00271         break;
00272 
00273     case opt_estimate_affine_shape:
00274       if (!mxIsLogicalScalar(optarg)) {
00275         vlmxError(vlmxErrInvalidArgument, "ESTIMATEAFFINESHAPE must be a logical scalar value.") ;
00276       } else {
00277         estimateAffineShape = *mxGetLogicals(optarg) ;
00278       }
00279       break ;
00280 
00281     case opt_estimate_orientation:
00282       if (!mxIsLogicalScalar(optarg)) {
00283         vlmxError(vlmxErrInvalidArgument, "ESTIMATEORIENTATION must be a logical scalar value.") ;
00284       } else {
00285         estimateOrientation = *mxGetLogicals(optarg);
00286       }
00287       break ;
00288 
00289     case opt_double_image:
00290       if (!mxIsLogicalScalar(optarg)) {
00291         vlmxError(vlmxErrInvalidArgument, "DOUBLEIMAGE must be a logical scalar value.") ;
00292       } else {
00293         doubleImage = *mxGetLogicals(optarg);
00294       }
00295       break ;
00296 
00297     case opt_octave_resolution :
00298       if (!vlmxIsPlainScalar(optarg) || (octaveResolution = (vl_index)*mxGetPr(optarg)) < 1) {
00299         vlmxError(vlmxErrInvalidArgument, "OCTAVERESOLUTION must be an integer not smaller than 1.") ;
00300       }
00301       break ;
00302 
00303     case opt_edge_threshold :
00304       if (!vlmxIsPlainScalar(optarg) || (edgeThreshold = *mxGetPr(optarg)) < 1) {
00305         vlmxError(vlmxErrInvalidArgument, "EDGETHRESHOLD must be a real not smaller than 1.") ;
00306       }
00307       break ;
00308 
00309     case opt_peak_threshold :
00310       if (!vlmxIsPlainScalar(optarg) || (peakThreshold = *mxGetPr(optarg)) < 0) {
00311         vlmxError(vlmxErrInvalidArgument, "PEAKTHRESHOLD must be a non-negative real.") ;
00312       }
00313       break ;
00314         
00315     case opt_laplacian_peak_threshold :
00316       if (!vlmxIsPlainScalar(optarg) || (lapPeakThreshold = *mxGetPr(optarg)) < 0) {
00317         vlmxError(vlmxErrInvalidArgument, "LAPLACIANPEAKTHRESHOLD must be a non-negative real.") ;
00318       }
00319       break ;
00320 
00321     case opt_patch_relative_smoothing :
00322       if (!vlmxIsPlainScalar(optarg) || (patchRelativeSmoothing = *mxGetPr(optarg)) < 0) {
00323         vlmxError(vlmxErrInvalidArgument, "PATCHRELATIVESMOOTHING must be a non-negative real.") ;
00324       }
00325       break ;
00326 
00327     case opt_patch_relative_extent :
00328       if (!vlmxIsPlainScalar(optarg) || (patchRelativeExtent = *mxGetPr(optarg)) <= 0) {
00329         vlmxError(vlmxErrInvalidArgument, "PATCHRELATIVEEXTENT must be a posiive real.") ;
00330       }
00331       break ;
00332 
00333     case opt_patch_resolution :
00334       if (!vlmxIsPlainScalar(optarg) || (patchResolution = (vl_index)*mxGetPr(optarg)) <= 0) {
00335         vlmxError(vlmxErrInvalidArgument, "PATCHRESOLUTION must be a positive integer.") ;
00336       }
00337       break ;
00338 
00339     case opt_liop_bins :
00340       if (!vlmxIsPlainScalar(optarg) || (liopNumSpatialBins = (vl_int)*mxGetPr(optarg)) <= 0) {
00341         vlmxError(vlmxErrInvalidArgument, "number of LIOPNUMSPATIALBINS is not a positive scalar.") ;
00342       }
00343       break ;
00344 
00345     case opt_liop_neighbours :
00346       if (!vlmxIsPlainScalar(optarg) || (liopNumNeighbours = (vl_int)*mxGetPr(optarg)) <= 0) {
00347         vlmxError(vlmxErrInvalidArgument, "number of LIOPNUMNEIGHBOURS is not a positive scalar.") ;
00348       }
00349       break ;
00350 
00351     case opt_liop_radius :
00352       if (!vlmxIsPlainScalar(optarg) || (liopRadius = (float)*mxGetPr(optarg)) <= 0) {
00353         vlmxError(vlmxErrInvalidArgument, "LIOPRADIUS must is not a positive scalar.") ;
00354       }
00355       break ;
00356 
00357     case opt_liop_threshold :
00358       if (!vlmxIsPlainScalar(optarg)) {
00359         vlmxError(vlmxErrInvalidArgument, "LIOPINTENSITYTHRESHOLD is not a scalar.") ;
00360       }
00361       liopIntensityThreshold = *mxGetPr(optarg) ;
00362       break ;
00363 
00364     case opt_frames:
00365       if (!vlmxIsPlainMatrix(optarg,-1,-1)) {
00366         vlmxError(vlmxErrInvalidArgument, "FRAMES must be a palin matrix.") ;
00367       }
00368       numUserFrames = mxGetN (optarg) ;
00369       userFrameDimension = mxGetM (optarg) ;
00370       userFrames = mxGetPr (optarg) ;
00371       switch (userFrameDimension) {
00372         case 2:
00373         case 3:
00374         case 4:
00375         case 5:
00376         case 6:
00377             /* ok */
00378           break ;
00379         default:
00380           vlmxError(vlmxErrInvalidArgument,
00381                     "FRAMES of dimensions %d are not recognised",
00382                     userFrameDimension); ;
00383       }
00384       break ;
00385 
00386     default :
00387       abort() ;
00388     }
00389   }
00390 
00391   if (descriptorType < 0) descriptorType = VL_COVDET_DESC_SIFT ;
00392 
00393   switch (descriptorType) {
00394     case VL_COVDET_DESC_NONE :
00395       break ;
00396 
00397     case VL_COVDET_DESC_PATCH :
00398       if (patchResolution < 0)  patchResolution = 20 ;
00399       if (patchRelativeExtent < 0) patchRelativeExtent = 6 ;
00400       if (patchRelativeSmoothing < 0) patchRelativeSmoothing = 1 ;
00401       break ;
00402 
00403     case VL_COVDET_DESC_SIFT :
00404       /* the patch parameters are selected to match the SIFT descriptor geometry */
00405       if (patchResolution < 0)  patchResolution = 15 ;
00406       if (patchRelativeExtent < 0) patchRelativeExtent = 7.5 ;
00407       if (patchRelativeSmoothing < 0) patchRelativeSmoothing = 1 ;
00408       break ;
00409 
00410     case VL_COVDET_DESC_LIOP :
00411       if (patchResolution < 0)  patchResolution = 20 ;
00412       if (patchRelativeExtent < 0) patchRelativeExtent = 4 ;
00413       if (patchRelativeSmoothing < 0) patchRelativeSmoothing = 0.5 ;
00414       break ;
00415   }
00416 
00417   if (patchResolution > 0) {
00418     vl_size w = 2*patchResolution + 1 ;
00419     patch = mxMalloc(sizeof(float) * w * w);
00420     patchXY = mxMalloc(2 * sizeof(float) * w * w);
00421   }
00422 
00423   if (descriptorType == VL_COVDET_DESC_LIOP && liopRadius > patchResolution) {
00424     vlmxError(vlmxErrInconsistentData, "LIOPRADIUS is larger than PATCHRESOLUTION.") ;
00425   }
00426 
00427   /* -----------------------------------------------------------------
00428    *                                                          Detector
00429    * -------------------------------------------------------------- */
00430   {
00431     VlCovDet * covdet = vl_covdet_new(method) ;
00432 
00433     /* set covdet parameters */
00434     vl_covdet_set_transposed(covdet, VL_TRUE) ;
00435     vl_covdet_set_first_octave(covdet, doubleImage ? -1 : 0) ;
00436     if (octaveResolution >= 0) vl_covdet_set_octave_resolution(covdet, octaveResolution) ;
00437     if (peakThreshold >= 0) vl_covdet_set_peak_threshold(covdet, peakThreshold) ;
00438     if (edgeThreshold >= 0) vl_covdet_set_edge_threshold(covdet, edgeThreshold) ;
00439     if (lapPeakThreshold >= 0) vl_covdet_set_laplacian_peak_threshold(covdet, lapPeakThreshold) ;
00440     
00441     if (verbose) {
00442       VL_PRINTF("vl_covdet: doubling image: %s\n",
00443                 VL_YESNO(vl_covdet_get_first_octave(covdet) < 0)) ;
00444     }
00445 
00446     /* process the image */
00447     vl_covdet_put_image(covdet, image, numRows, numCols) ;
00448 
00449     /* fill with frames: either run the detector of poure them in */
00450     if (numUserFrames > 0) {
00451       vl_index k ;
00452 
00453       if (verbose) {
00454         mexPrintf("vl_covdet: sourcing %d frames\n", numUserFrames) ;
00455       }
00456 
00457       for (k = 0 ; k < (signed)numUserFrames ; ++k) {
00458         double const * uframe = userFrames + userFrameDimension * k ;
00459         double a11, a21, a12, a22 ;
00460         VlCovDetFeature feature ;
00461         feature.peakScore = VL_INFINITY_F ;
00462         feature.edgeScore = 1.0 ;
00463         feature.frame.x = (float)uframe[1] - 1 ;
00464         feature.frame.y = (float)uframe[0] - 1 ;
00465 
00466         switch (userFrameDimension) {
00467           case 2:
00468             a11 = 1.0 ;
00469             a21 = 0.0 ;
00470             a12 = 0.0 ;
00471             a22 = 1.0 ;
00472             break ;
00473           case 3:
00474             a11 = uframe[2] ;
00475             a21 = 0.0 ;
00476             a12 = 0.0 ;
00477             a22 = uframe[2] ;
00478             break ;
00479           case 4:
00480           {
00481             double sigma = uframe[2] ;
00482             double c = cos(uframe[3]) ;
00483             double s = sin(uframe[3]) ;
00484             a11 = sigma * c ;
00485             a21 = sigma * s ;
00486             a12 = sigma * (-s) ;
00487             a22 = sigma * c ;
00488             break ;
00489           }
00490           case 5:
00491           {
00492             double d2 ;
00493             if (uframe[2] < 0) {
00494               vlmxError(vlmxErrInvalidArgument, "FRAMES(:,%d) does not have a PSD covariance.", k+1) ;
00495             }
00496             a11 = sqrt(uframe[2]) ;
00497             a21 = uframe[3] / VL_MAX(a11, 1e-10) ;
00498             a12 = 0.0 ;
00499             d2 = uframe[4] - a21*a21 ;
00500             if (d2 < 0) {
00501               vlmxError(vlmxErrInvalidArgument, "FRAMES(:,%d) does not have a PSD covariance.", k+1) ;
00502             }
00503             a22 = sqrt(d2) ;
00504             break ;
00505           }
00506           case 6:
00507           {
00508             a11 = uframe[2] ;
00509             a21 = uframe[3] ;
00510             a12 = uframe[4] ;
00511             a22 = uframe[5] ;
00512             break ;
00513           }
00514           default:
00515             a11 = 0 ;
00516             a21 = 0 ;
00517             a12 = 0 ;
00518             a22 = 0 ;
00519             assert(0) ;
00520         }
00521         feature.frame.a11 = (float)a22 ;
00522         feature.frame.a21 = (float)a12 ;
00523         feature.frame.a12 = (float)a21 ;
00524         feature.frame.a22 = (float)a11 ;
00525         vl_covdet_append_feature(covdet, &feature) ;
00526       }
00527     } else {
00528       if (verbose) {
00529         mexPrintf("vl_covdet: detector: %s\n",
00530                   vl_enumeration_get_by_value(vlCovdetMethods, method)->name) ;
00531         mexPrintf("vl_covdet: peak threshold: %g, edge threshold: %g\n",
00532                   vl_covdet_get_peak_threshold(covdet),
00533                   vl_covdet_get_edge_threshold(covdet)) ;
00534       }
00535 
00536       vl_covdet_detect(covdet) ;
00537 
00538       if (verbose) {
00539         vl_index i ;
00540         vl_size numFeatures = vl_covdet_get_num_features(covdet) ;
00541         mexPrintf("vl_covdet: %d features suppressed as duplicate (threshold: %g)\n",
00542                   vl_covdet_get_num_non_extrema_suppressed(covdet),
00543                   vl_covdet_get_non_extrema_suppression_threshold(covdet)) ;
00544         switch (method) {
00545         case VL_COVDET_METHOD_HARRIS_LAPLACE:
00546         case VL_COVDET_METHOD_HESSIAN_LAPLACE:
00547           {
00548             vl_size numScales ;
00549             vl_size const * numFeaturesPerScale ;
00550             numFeaturesPerScale = vl_covdet_get_laplacian_scales_statistics
00551               (covdet, &numScales) ;
00552             mexPrintf("vl_covdet: Laplacian scales:") ;
00553             for (i = 0 ; i <= (signed)numScales ; ++i) {
00554               mexPrintf("%d with %d scales;", numFeaturesPerScale[i], i) ;
00555             }
00556             mexPrintf("\n") ;
00557           }
00558           break ;
00559         default:
00560           break ;
00561         }
00562         mexPrintf("vl_covdet: detected %d features\n", numFeatures) ;
00563       }
00564 
00565       if (boundaryMargin > 0) {
00566         vl_covdet_drop_features_outside (covdet, boundaryMargin) ;
00567         if (verbose) {
00568           vl_size numFeatures = vl_covdet_get_num_features(covdet) ;
00569           mexPrintf("vl_covdet: kept %d inside the boundary margin (%g)\n",
00570                     numFeatures, boundaryMargin) ;
00571         }
00572       }
00573     }
00574 
00575     /* affine adaptation if needed */
00576     if (estimateAffineShape) {
00577       if (verbose) {
00578         vl_size numFeaturesBefore = vl_covdet_get_num_features(covdet) ;
00579         mexPrintf("vl_covdet: estimating affine shape for %d features\n", numFeaturesBefore) ;
00580       }
00581 
00582       vl_covdet_extract_affine_shape(covdet) ;
00583 
00584       if (verbose) {
00585         vl_size numFeaturesAfter = vl_covdet_get_num_features(covdet) ;
00586         mexPrintf("vl_covdet: %d features passed affine adaptation\n", numFeaturesAfter) ;
00587       }
00588     }
00589 
00590     /* orientation estimation if needed */
00591     if (estimateOrientation) {
00592       vl_size numFeaturesBefore = vl_covdet_get_num_features(covdet) ;
00593       vl_size numFeaturesAfter ;
00594 
00595       vl_covdet_extract_orientations(covdet) ;
00596 
00597       numFeaturesAfter = vl_covdet_get_num_features(covdet) ;
00598       if (verbose && numFeaturesAfter > numFeaturesBefore) {
00599         mexPrintf("vl_covdet: %d duplicate features were created due to ambiguous "
00600                   "orientation detection (%d total)\n",
00601                   numFeaturesAfter - numFeaturesBefore, numFeaturesAfter) ;
00602       }
00603     }
00604 
00605     /* store results back */
00606     {
00607       vl_index i  ;
00608       vl_size numFeatures = vl_covdet_get_num_features(covdet) ;
00609       VlCovDetFeature const * feature = vl_covdet_get_features(covdet);
00610       double * pt ;
00611 
00612       OUT(FRAMES) = mxCreateDoubleMatrix (6, numFeatures, mxREAL) ;
00613       pt = mxGetPr(OUT(FRAMES)) ;
00614 
00615       for (i = 0 ; i < (signed)numFeatures ; ++i) {
00616         /* save the transposed frame, adjust origin to MATLAB's*/
00617         *pt++ = feature[i].frame.y + 1 ;
00618         *pt++ = feature[i].frame.x + 1 ;
00619         *pt++ = feature[i].frame.a22 ;
00620         *pt++ = feature[i].frame.a12 ;
00621         *pt++ = feature[i].frame.a21 ;
00622         *pt++ = feature[i].frame.a11 ;
00623       }
00624     }
00625 
00626     if (nout >= 2) {
00627       switch (descriptorType) {
00628         case VL_COVDET_DESC_NONE:
00629           OUT(DESCRIPTORS) = mxCreateDoubleMatrix(0,0,mxREAL);
00630           break ;
00631 
00632         case VL_COVDET_DESC_PATCH:
00633         {
00634           vl_size numFeatures ;
00635           VlCovDetFeature const * feature ;
00636           vl_index i ;
00637           vl_size w = 2*patchResolution + 1 ;
00638           float * desc ;
00639 
00640           if (verbose) {
00641             mexPrintf("vl_covdet: descriptors: type=patch, "
00642                       "resolution=%d, extent=%g, smoothing=%g\n",
00643                       patchResolution, patchRelativeExtent,
00644                       patchRelativeSmoothing);
00645           }
00646           numFeatures = vl_covdet_get_num_features(covdet) ;
00647           feature = vl_covdet_get_features(covdet);
00648           OUT(DESCRIPTORS) = mxCreateNumericMatrix(w*w, numFeatures, mxSINGLE_CLASS, mxREAL) ;
00649           desc = mxGetData(OUT(DESCRIPTORS)) ;
00650           for (i = 0 ; i < (signed)numFeatures ; ++i) {
00651             vl_covdet_extract_patch_for_frame(covdet,
00652                                     desc,
00653                                     patchResolution,
00654                                     patchRelativeExtent,
00655                                     patchRelativeSmoothing,
00656                                     feature[i].frame) ;
00657             desc += w*w ;
00658           }
00659           break ;
00660         }
00661         case VL_COVDET_DESC_SIFT:
00662         {
00663           vl_size numFeatures = vl_covdet_get_num_features(covdet) ;
00664           VlCovDetFeature const * feature = vl_covdet_get_features(covdet);
00665           VlSiftFilt * sift = vl_sift_new(16, 16, 1, 3, 0) ;
00666           vl_index i ;
00667           vl_size dimension = 128 ;
00668           vl_size patchSide = 2 * patchResolution + 1 ;
00669           double patchStep = (double)patchRelativeExtent / patchResolution ;
00670           float tempDesc [128] ;
00671           float * desc ;
00672           if (verbose) {
00673             mexPrintf("vl_covdet: descriptors: type=sift, "
00674                       "resolution=%d, extent=%g, smoothing=%g\n",
00675                       patchResolution, patchRelativeExtent,
00676                       patchRelativeSmoothing);
00677           }
00678           OUT(DESCRIPTORS) = mxCreateNumericMatrix(dimension, numFeatures, mxSINGLE_CLASS, mxREAL) ;
00679           desc = mxGetData(OUT(DESCRIPTORS)) ;
00680           vl_sift_set_magnif(sift, 3.0) ;
00681           for (i = 0 ; i < (signed)numFeatures ; ++i) {
00682             vl_covdet_extract_patch_for_frame(covdet,
00683                                               patch,
00684                                               patchResolution,
00685                                               patchRelativeExtent,
00686                                               patchRelativeSmoothing,
00687                                               feature[i].frame) ;
00688 
00689             vl_imgradient_polar_f (patchXY, patchXY +1,
00690                                    2, 2 * patchSide,
00691                                    patch, patchSide, patchSide, patchSide) ;
00692 
00693 
00694             /*
00695              Note: the patch is transposed, so that x and y are swapped.
00696              However, if NBO is not divisible by 4, then the configuration
00697              of the SIFT orientations is not symmetric by rotations of pi/2.
00698              Hence the only option is to rotate the descriptor further by
00699              an angle we need to compute the descriptor rotated by an additional pi/2
00700              angle. In this manner, x coincides and y is flipped.
00701              */
00702             vl_sift_calc_raw_descriptor (sift,
00703                                          patchXY,
00704                                          tempDesc,
00705                                          (int)patchSide, (int)patchSide,
00706                                          (double)(patchSide-1) / 2, (double)(patchSide-1) / 2,
00707                                          (double)patchRelativeExtent / (3.0 * (4 + 1) / 2) /
00708                                          patchStep,
00709                                          VL_PI / 2) ;
00710 
00711             flip_descriptor (desc, tempDesc) ;
00712             desc += dimension ;
00713           }
00714           vl_sift_delete(sift) ;
00715           break ;
00716         }
00717         case VL_COVDET_DESC_LIOP :
00718         {          /* TODO: get parameters form input */
00719           vl_size numFeatures = vl_covdet_get_num_features(covdet) ;
00720           vl_size dimension ;
00721           VlCovDetFeature const * feature = vl_covdet_get_features(covdet);
00722           vl_index i ;
00723 
00724           vl_size patchSide = 2 * patchResolution + 1 ;
00725           float * desc ;
00726 
00727           VlLiopDesc * liop = vl_liopdesc_new(liopNumNeighbours, liopNumSpatialBins, liopRadius, (vl_size)patchSide) ;
00728           if (!vl_is_nan_f(liopIntensityThreshold)) {
00729             vl_liopdesc_set_intensity_threshold(liop, liopIntensityThreshold) ;
00730           }
00731           dimension = vl_liopdesc_get_dimension(liop) ;
00732           if (verbose) {
00733             mexPrintf("vl_covdet: descriptors: type=liop, "
00734                       "resolution=%d, extent=%g, smoothing=%g\n",
00735                       patchResolution, patchRelativeExtent,
00736                       patchRelativeSmoothing);
00737           }
00738           OUT(DESCRIPTORS) = mxCreateNumericMatrix(dimension, numFeatures, mxSINGLE_CLASS, mxREAL);
00739           desc = mxGetData(OUT(DESCRIPTORS)) ;
00740           for(i = 0; i < (signed)numFeatures; i++){
00741               vl_covdet_extract_patch_for_frame(covdet,
00742                                                 patch,
00743                                                 patchResolution,
00744                                                 patchRelativeExtent,
00745                                                 patchRelativeSmoothing,
00746                                                 feature[i].frame);
00747 
00748               vl_liopdesc_process(liop, desc, patch);
00749 
00750               desc += dimension;
00751 
00752           }
00753           vl_liopdesc_delete(liop);
00754           break;
00755         }
00756 
00757         default:
00758           assert(0) ; /* descriptor type */
00759       }
00760     }
00761 
00762     if (nout >= 3) {
00763       vl_index i ;
00764       vl_size numFeatures = vl_covdet_get_num_features(covdet) ;
00765       VlCovDetFeature const * feature = vl_covdet_get_features(covdet);
00766       const char* names[] = {
00767         "gss",
00768         "css",
00769         "peakScores",
00770         "edgeScores",
00771         "orientationScore",
00772         "laplacianScaleScore"
00773       };
00774       mxArray * gss_array = _createArrayFromScaleSpace(vl_covdet_get_gss(covdet)) ;
00775       mxArray * css_array = _createArrayFromScaleSpace(vl_covdet_get_css(covdet)) ;
00776       mxArray * peak_array = mxCreateNumericMatrix(1,numFeatures,mxSINGLE_CLASS,mxREAL) ;
00777       mxArray * edge_array = mxCreateNumericMatrix(1,numFeatures,mxSINGLE_CLASS,mxREAL) ;
00778       mxArray * orientation_array = mxCreateNumericMatrix(1,numFeatures,mxSINGLE_CLASS,mxREAL) ;
00779       mxArray * laplacian_array = mxCreateNumericMatrix(1,numFeatures,mxSINGLE_CLASS,mxREAL) ;
00780 
00781       float * peak = mxGetData(peak_array) ;
00782       float * edge = mxGetData(edge_array) ;
00783       float * orientation = mxGetData(orientation_array) ;
00784       float * laplacian = mxGetData(laplacian_array) ;
00785       for (i = 0 ; i < (signed)numFeatures ; ++i) {
00786         peak[i] = feature[i].peakScore ;
00787         edge[i] = feature[i].edgeScore ;
00788         orientation[i] = feature[i].orientationScore ;
00789         laplacian[i] = feature[i].laplacianScaleScore ;
00790       }
00791 
00792       OUT(INFO) = mxCreateStructMatrix(1, 1, 6, names) ;
00793       mxSetFieldByNumber(OUT(INFO), 0, 0, gss_array) ;
00794       mxSetFieldByNumber(OUT(INFO), 0, 1, css_array) ;
00795       mxSetFieldByNumber(OUT(INFO), 0, 2, peak_array) ;
00796       mxSetFieldByNumber(OUT(INFO), 0, 3, edge_array) ;
00797       mxSetFieldByNumber(OUT(INFO), 0, 4, orientation_array) ;
00798       mxSetFieldByNumber(OUT(INFO), 0, 5, laplacian_array) ;
00799     }
00800     /* cleanup */
00801     vl_covdet_delete (covdet) ;
00802   }
00803 
00804   if (patchXY) mxFree(patchXY) ;
00805   if (patch) mxFree(patch) ;
00806 }


libvlfeat
Author(s): Andrea Vedaldi
autogenerated on Thu Jun 6 2019 20:25:51