liop.c
Go to the documentation of this file.
00001 
00007 /*
00008 Copyright (C) 2013 Hana Sarbortova and Andrea Vedaldi.
00009 All rights reserved.
00010 
00011 This file is part of the VLFeat library and is made available under
00012 the terms of the BSD license (see the COPYING file).
00013 */
00014 
00203 #include "liop.h"
00204 #include "mathop.h"
00205 #include "imopv.h"
00206 #include <string.h>
00207 
00208 #define DEFAULT_INTENSITY_THRESHOLD -(5.0/255)
00209 #define DEFAULT_RADIUS 6.0
00210 #define DEFAULT_NUM_SPATIAL_BINS 6
00211 #define DEFAULT_NUM_NEIGHBOURS 4
00212 
00213 /* ---------------------------------------------------------------- */
00214 /*                                                 Helper functions */
00215 /* ---------------------------------------------------------------- */
00216 
00217 static
00218 vl_int factorial(vl_int num)
00219 {
00220   vl_int result = 1;
00221   while(num > 1){
00222     result = num*result;
00223     num--;
00224   }
00225   return result ;
00226 }
00227 
00250 VL_INLINE vl_index get_permutation_index(vl_uindex *permutation, vl_size size){
00251   vl_index index = 0 ;
00252   vl_index i ;
00253   vl_index j ;
00254 
00255   for (i = 0 ; i < (signed)size ; ++i) {
00256     index = index * ((signed)size - i) + permutation[i] ;
00257     for (j = i + 1 ; j < (signed)size ; ++j) {
00258       if (permutation[j] > permutation[i]) { permutation[j] -- ; }
00259     }
00260   }
00261   return index ;
00262 }
00263 
00264 /* instantiate two quick sort algorithms */
00265 VL_INLINE float patch_cmp (VlLiopDesc * liop, vl_index i, vl_index j)
00266 {
00267   vl_index ii = liop->patchPermutation[i] ;
00268   vl_index jj = liop->patchPermutation[j] ;
00269   return liop->patchIntensities[ii] - liop->patchIntensities[jj] ;
00270 }
00271 
00272 VL_INLINE void patch_swap (VlLiopDesc * liop, vl_index i, vl_index j)
00273 {
00274   vl_index tmp = liop->patchPermutation[i] ;
00275   liop->patchPermutation[i] = liop->patchPermutation[j] ;
00276   liop->patchPermutation[j] = tmp ;
00277 }
00278 
00279 #define VL_QSORT_prefix patch
00280 #define VL_QSORT_array VlLiopDesc*
00281 #define VL_QSORT_cmp patch_cmp
00282 #define VL_QSORT_swap patch_swap
00283 #include "qsort-def.h"
00284 
00285 VL_INLINE float neigh_cmp (VlLiopDesc * liop, vl_index i, vl_index j)
00286 {
00287   vl_index ii = liop->neighPermutation[i] ;
00288   vl_index jj = liop->neighPermutation[j] ;
00289   return liop->neighIntensities[ii] - liop->neighIntensities[jj] ;
00290 }
00291 
00292 VL_INLINE void neigh_swap (VlLiopDesc * liop, vl_index i, vl_index j)
00293 {
00294   vl_index tmp = liop->neighPermutation[i] ;
00295   liop->neighPermutation[i] = liop->neighPermutation[j] ;
00296   liop->neighPermutation[j] = tmp ;
00297 }
00298 
00299 #define VL_QSORT_prefix neigh
00300 #define VL_QSORT_array VlLiopDesc*
00301 #define VL_QSORT_cmp neigh_cmp
00302 #define VL_QSORT_swap neigh_swap
00303 #include "qsort-def.h"
00304 
00305 /* ---------------------------------------------------------------- */
00306 /*                                            Construct and destroy */
00307 /* ---------------------------------------------------------------- */
00308 
00320 VlLiopDesc *
00321 vl_liopdesc_new (vl_int numNeighbours, vl_int numSpatialBins,
00322                  float radius, vl_size sideLength)
00323 {
00324   vl_index i, t ;
00325   VlLiopDesc * self = vl_calloc(sizeof(VlLiopDesc), 1);
00326 
00327   assert(radius <= sideLength/2) ;
00328 
00329   self->numNeighbours = numNeighbours ;
00330   self->numSpatialBins = numSpatialBins ;
00331   self->neighRadius = radius ;
00332   self->intensityThreshold = DEFAULT_INTENSITY_THRESHOLD ;
00333 
00334   self->dimension = factorial(numNeighbours) * numSpatialBins ;
00335 
00336   /*
00337    Precompute a list of pixels within a circular patch inside
00338    the square image. Leave a suitable marging for sampling around
00339    these pixels.
00340    */
00341 
00342   self->patchSize = 0 ;
00343   self->patchPixels = vl_malloc(sizeof(vl_uindex)*sideLength*sideLength) ;
00344   self->patchSideLength = sideLength ;
00345 
00346   {
00347     vl_index x, y ;
00348     vl_index center = (sideLength - 1) / 2 ;
00349     double t = center - radius + 0.6 ;
00350     vl_index t2 = (vl_index) (t * t) ;
00351     for (y = 0 ; y < (signed)sideLength ; ++y) {
00352       for (x = 0 ; x < (signed)sideLength ; ++x) {
00353         vl_index dx = x - center ;
00354         vl_index dy = y - center ;
00355         if (x == 0 && y == 0) continue ;
00356         if (dx*dx + dy*dy <= t2) {
00357           self->patchPixels[self->patchSize++] = x + y * sideLength ;
00358         }
00359       }
00360     }
00361   }
00362 
00363   self->patchIntensities = vl_malloc(sizeof(vl_uindex)*self->patchSize) ;
00364   self->patchPermutation = vl_malloc(sizeof(vl_uindex)*self->patchSize) ;
00365 
00366   /*
00367    Precompute the samples in the circular neighbourhood of each
00368    measurement point.
00369    */
00370 
00371   self->neighPermutation = vl_malloc(sizeof(vl_uindex) * self->numNeighbours) ;
00372   self->neighIntensities = vl_malloc(sizeof(float) * self->numNeighbours) ;
00373   self->neighSamplesX = vl_calloc(sizeof(double), self->numNeighbours * self->patchSize) ;
00374   self->neighSamplesY = vl_calloc(sizeof(double), self->numNeighbours * self->patchSize) ;
00375 
00376   for (i = 0 ; i < (signed)self->patchSize ; ++i) {
00377     vl_index pixel ;
00378     double x, y ;
00379     double dangle = 2*VL_PI / (double)self->numNeighbours ;
00380     double angle0 ;
00381     vl_index center = (sideLength - 1) / 2 ;
00382 
00383     pixel = self->patchPixels[i] ;
00384     x = (pixel % (signed)self->patchSideLength) - center ;
00385     y = (pixel / (signed)self->patchSideLength) - center ;
00386 
00387     angle0 = atan2(y,x) ;
00388 
00389     for (t = 0 ; t < (signed)self->numNeighbours ; ++t) {
00390       double x1 = x + radius * cos(angle0 + dangle * t) + center ;
00391       double y1 = y + radius * sin(angle0 + dangle * t) + center ;
00392       self->neighSamplesX[t + (signed)self->numNeighbours * i] = x1 ;
00393       self->neighSamplesY[t + (signed)self->numNeighbours * i] = y1 ;
00394     }
00395   }
00396   return self ;
00397 }
00398 
00405 VlLiopDesc * vl_liopdesc_new_basic (vl_size sideLength)
00406 {
00407   return vl_liopdesc_new(DEFAULT_NUM_NEIGHBOURS,
00408                          DEFAULT_NUM_SPATIAL_BINS,
00409                          DEFAULT_RADIUS,
00410                          sideLength) ;
00411 }
00412 
00416 void
00417 vl_liopdesc_delete (VlLiopDesc * self)
00418 {
00419   vl_free (self->patchPixels) ;
00420   vl_free (self->patchIntensities) ;
00421   vl_free (self->patchPermutation) ;
00422   vl_free (self->neighPermutation) ;
00423   vl_free (self->neighIntensities) ;
00424   vl_free (self->neighSamplesX) ;
00425   vl_free (self->neighSamplesY) ;
00426   vl_free (self) ;
00427 }
00428 
00429 /* ---------------------------------------------------------------- */
00430 /*                                          Compute LIOP descriptor */
00431 /* ---------------------------------------------------------------- */
00432 
00441 void
00442 vl_liopdesc_process (VlLiopDesc * self, float * desc, float const * patch)
00443 {
00444   vl_index i,t ;
00445   vl_index offset,numPermutations ;
00446   vl_index spatialBinArea, spatialBinEnd, spatialBinIndex ;
00447   float threshold ;
00448 
00449   memset(desc, 0, sizeof(float) * self->dimension) ;
00450 
00451   /*
00452    * Sort pixels in the patch by increasing intensity.
00453    */
00454 
00455   for (i = 0 ; i < (signed)self->patchSize ; ++i) {
00456     vl_index pixel = self->patchPixels[i] ;
00457     self->patchIntensities[i] = patch[pixel] ;
00458     self->patchPermutation[i] = i ;
00459   }
00460   patch_sort(self, self->patchSize) ;
00461 
00462   /*
00463    * Tune the threshold if needed.
00464    */
00465 
00466   if (self->intensityThreshold < 0) {
00467     i = self->patchPermutation[0] ;
00468     t = self->patchPermutation[self->patchSize-1] ;
00469     threshold = - self->intensityThreshold
00470     * (self->patchIntensities[t] - self->patchIntensities[i]);
00471   } else {
00472     threshold = self->intensityThreshold ;
00473   }
00474 
00475   /*
00476    * Process pixels in order of increasing intenisity, dividing them into
00477    * spatial bins on the fly.
00478    */
00479 
00480   numPermutations = factorial(self->numNeighbours) ;
00481   spatialBinArea = self->patchSize / self->numSpatialBins ;
00482   spatialBinEnd = spatialBinArea ;
00483   spatialBinIndex = 0 ;
00484   offset = 0 ;
00485 
00486   for (i = 0 ; i < (signed)self->patchSize ; ++i) {
00487     vl_index permIndex ;
00488     double *sx, *sy ;
00489 
00490     /* advance to the next spatial bin if needed */
00491     if (i >= (signed)spatialBinEnd && spatialBinIndex < (signed)self->numSpatialBins - 1) {
00492       spatialBinEnd += spatialBinArea ;
00493       spatialBinIndex ++ ;
00494       offset += numPermutations ;
00495     }
00496 
00497     /* get intensities of neighbours of the current patch element and sort them */
00498     sx = self->neighSamplesX + self->numNeighbours * self->patchPermutation[i] ;
00499     sy = self->neighSamplesY + self->numNeighbours * self->patchPermutation[i] ;
00500     for (t = 0 ; t < self->numNeighbours ; ++t) {
00501       double x = *sx++ ;
00502       double y = *sy++ ;
00503 
00504       /* bilinear interpolation */
00505       vl_index ix = vl_floor_d(x) ;
00506       vl_index iy = vl_floor_d(y) ;
00507 
00508       double wx = x - ix ;
00509       double wy = y - iy ;
00510 
00511       double a = 0, b = 0, c = 0, d = 0 ;
00512 
00513       int L = (int) self->patchSideLength ;
00514 
00515       if (ix >= 0   && iy >= 0  ) { a = patch[ix   + iy * L] ; }
00516       if (ix <  L-1 && iy >= 0  ) { b = patch[ix+1 + iy * L] ; }
00517       if (ix >= 0   && iy <  L-1) { c = patch[ix   + (iy+1) * L] ; }
00518       if (ix <  L-1 && iy <  L-1) { d = patch[ix+1 + (iy+1) * L] ; }
00519 
00520       self->neighPermutation[t] = t;
00521       self->neighIntensities[t] = (1 - wy) * (a + (b - a) * wx) + wy * (c + (d - c) * wx) ;
00522     }
00523     neigh_sort (self, self->numNeighbours) ;
00524 
00525     /* get permutation index */
00526     permIndex = get_permutation_index(self->neighPermutation, self->numNeighbours);
00527 
00528     /*
00529      * Compute weight according to difference in intensity values and
00530      * accumulate.
00531      */
00532     {
00533       int k, t ;
00534       float weight = 0 ;
00535       for(k = 0; k < self->numNeighbours ; ++k) {
00536         for(t = k + 1; t < self->numNeighbours; ++t){
00537           double a = self->neighIntensities[k] ;
00538           double b = self->neighIntensities[t] ;
00539           weight += (a > b + threshold || b > a + threshold) ;
00540         }
00541       }
00542       desc[permIndex + offset] += weight ;
00543     }
00544   }
00545 
00546   /* normalization */
00547   {
00548     float norm = 0;
00549     for(i = 0; i < (signed)self->dimension; i++) {
00550       norm += desc[i]*desc[i];
00551     }
00552     norm = VL_MAX(sqrt(norm), 1e-12) ;
00553     for(i = 0; i < (signed)self->dimension; i++){
00554       desc[i] /= norm ;
00555     }
00556   }
00557 }
00558 
00559 
00560 /* ---------------------------------------------------------------- */
00561 /*                                              Getters and setters */
00562 /* ---------------------------------------------------------------- */
00563 
00568 vl_size
00569 vl_liopdesc_get_dimension (VlLiopDesc const * self)
00570 {
00571   return self->dimension ;
00572 }
00573 
00574 
00580 vl_size
00581 vl_liopdesc_get_num_neighbours (VlLiopDesc const * self)
00582 {
00583   assert(self) ;
00584   return self->numNeighbours ;
00585 }
00586 
00593 float
00594 vl_liopdesc_get_intensity_threshold (VlLiopDesc const * self)
00595 {
00596   assert(self) ;
00597   return self->intensityThreshold ;
00598 }
00599 
00612 void
00613 vl_liopdesc_set_intensity_threshold (VlLiopDesc * self, float x)
00614 {
00615   assert(self) ;
00616   self->intensityThreshold = x ;
00617 }
00618 
00624 double
00625 vl_liopdesc_get_neighbourhood_radius (VlLiopDesc const * self)
00626 {
00627   assert(self) ;
00628   return self->neighRadius ;
00629 }
00630 
00636 vl_size
00637 vl_liopdesc_get_num_spatial_bins (VlLiopDesc const * self)
00638 {
00639   assert(self) ;
00640   return self->numSpatialBins ;
00641 }


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