sift.c
Go to the documentation of this file.
00001 
00006 /*
00007 Copyright (C) 2007-12 Andrea Vedaldi and Brian Fulkerson.
00008 All rights reserved.
00009 
00010 This file is part of the VLFeat library and is made available under
00011 the terms of the BSD license (see the COPYING file).
00012 */
00013 
00658 #include "sift.h"
00659 #include "imopv.h"
00660 #include "mathop.h"
00661 
00662 #include <assert.h>
00663 #include <stdlib.h>
00664 #include <string.h>
00665 #include <math.h>
00666 #include <stdio.h>
00667 
00669 #define VL_SIFT_BILINEAR_ORIENTATIONS 1
00670 
00671 #define EXPN_SZ  256          
00672 #define EXPN_MAX 25.0         
00673 double expn_tab [EXPN_SZ+1] ; 
00675 #define NBO 8
00676 #define NBP 4
00677 
00678 #define log2(x) (log(x)/VL_LOG_OF_2)
00679 
00691 VL_INLINE double
00692 fast_expn (double x)
00693 {
00694   double a,b,r ;
00695   int i ;
00696   /*assert(0 <= x && x <= EXPN_MAX) ;*/
00697 
00698   if (x > EXPN_MAX) return 0.0 ;
00699 
00700   x *= EXPN_SZ / EXPN_MAX ;
00701   i = (int)vl_floor_d (x) ;
00702   r = x - i ;
00703   a = expn_tab [i    ] ;
00704   b = expn_tab [i + 1] ;
00705   return a + r * (b - a) ;
00706 }
00707 
00713 VL_INLINE void
00714 fast_expn_init ()
00715 {
00716   int k  ;
00717   for(k = 0 ; k < EXPN_SZ + 1 ; ++ k) {
00718     expn_tab [k] = exp (- (double) k * (EXPN_MAX / EXPN_SZ)) ;
00719   }
00720 }
00721 
00738 static void
00739 copy_and_upsample_rows
00740 (vl_sift_pix       *dst,
00741  vl_sift_pix const *src, int width, int height)
00742 {
00743   int x, y ;
00744   vl_sift_pix a, b ;
00745 
00746   for(y = 0 ; y < height ; ++y) {
00747     b = a = *src++ ;
00748     for(x = 0 ; x < width - 1 ; ++x) {
00749       b = *src++ ;
00750       *dst = a ;             dst += height ;
00751       *dst = 0.5 * (a + b) ; dst += height ;
00752       a = b ;
00753     }
00754     *dst = b ; dst += height ;
00755     *dst = b ; dst += height ;
00756     dst += 1 - width * 2 * height ;
00757   }
00758 }
00759 
00772 static void
00773 _vl_sift_smooth (VlSiftFilt * self,
00774                  vl_sift_pix * outputImage,
00775                  vl_sift_pix * tempImage,
00776                  vl_sift_pix const * inputImage,
00777                  vl_size width,
00778                  vl_size height,
00779                  double sigma)
00780 {
00781   /* prepare Gaussian filter */
00782   if (self->gaussFilterSigma != sigma) {
00783     vl_uindex j ;
00784     vl_sift_pix acc = 0 ;
00785     if (self->gaussFilter) vl_free (self->gaussFilter) ;
00786     self->gaussFilterWidth = VL_MAX(ceil(4.0 * sigma), 1) ;
00787     self->gaussFilterSigma = sigma ;
00788     self->gaussFilter = vl_malloc (sizeof(vl_sift_pix) * (2 * self->gaussFilterWidth + 1)) ;
00789 
00790     for (j = 0 ; j < 2 * self->gaussFilterWidth + 1 ; ++j) {
00791       vl_sift_pix d = ((vl_sift_pix)((signed)j - (signed)self->gaussFilterWidth)) / ((vl_sift_pix)sigma) ;
00792       self->gaussFilter[j] = (vl_sift_pix) exp (- 0.5 * (d*d)) ;
00793       acc += self->gaussFilter[j] ;
00794     }
00795     for (j = 0 ; j < 2 * self->gaussFilterWidth + 1 ; ++j) {
00796       self->gaussFilter[j] /= acc ;
00797     }
00798   }
00799 
00800   if (self->gaussFilterWidth == 0) {
00801     memcpy (outputImage, inputImage, sizeof(vl_sift_pix) * width * height) ;
00802     return ;
00803   }
00804 
00805   vl_imconvcol_vf (tempImage, height,
00806                    inputImage, width, height, width,
00807                    self->gaussFilter,
00808                    - self->gaussFilterWidth, self->gaussFilterWidth,
00809                    1, VL_PAD_BY_CONTINUITY | VL_TRANSPOSE) ;
00810 
00811   vl_imconvcol_vf (outputImage, width,
00812                    tempImage, height, width, height,
00813                    self->gaussFilter,
00814                    - self->gaussFilterWidth, self->gaussFilterWidth,
00815                    1, VL_PAD_BY_CONTINUITY | VL_TRANSPOSE) ;
00816 }
00817 
00835 static void
00836 copy_and_downsample
00837 (vl_sift_pix       *dst,
00838  vl_sift_pix const *src,
00839  int width, int height, int d)
00840 {
00841   int x, y ;
00842 
00843   d = 1 << d ; /* d = 2^d */
00844   for(y = 0 ; y < height ; y+=d) {
00845     vl_sift_pix const * srcrowp = src + y * width ;
00846     for(x = 0 ; x < width - (d-1) ; x+=d) {
00847       *dst++ = *srcrowp ;
00848       srcrowp += d ;
00849     }
00850   }
00851 }
00852 
00872 VL_EXPORT
00873 VlSiftFilt *
00874 vl_sift_new (int width, int height,
00875              int noctaves, int nlevels,
00876              int o_min)
00877 {
00878   VlSiftFilt *f = vl_malloc (sizeof(VlSiftFilt)) ;
00879 
00880   int w   = VL_SHIFT_LEFT (width,  -o_min) ;
00881   int h   = VL_SHIFT_LEFT (height, -o_min) ;
00882   int nel = w * h ;
00883 
00884   /* negative value O => calculate max. value */
00885   if (noctaves < 0) {
00886     noctaves = VL_MAX (floor (log2 (VL_MIN(width, height))) - o_min - 3, 1) ;
00887   }
00888 
00889   f-> width   = width ;
00890   f-> height  = height ;
00891   f-> O       = noctaves ;
00892   f-> S       = nlevels ;
00893   f-> o_min   = o_min ;
00894   f-> s_min   = -1 ;
00895   f-> s_max   = nlevels + 1 ;
00896   f-> o_cur   = o_min ;
00897 
00898   f-> temp    = vl_malloc (sizeof(vl_sift_pix) * nel    ) ;
00899   f-> octave  = vl_malloc (sizeof(vl_sift_pix) * nel
00900                         * (f->s_max - f->s_min + 1)  ) ;
00901   f-> dog     = vl_malloc (sizeof(vl_sift_pix) * nel
00902                         * (f->s_max - f->s_min    )  ) ;
00903   f-> grad    = vl_malloc (sizeof(vl_sift_pix) * nel * 2
00904                         * (f->s_max - f->s_min    )  ) ;
00905 
00906   f-> sigman  = 0.5 ;
00907   f-> sigmak  = pow (2.0, 1.0 / nlevels) ;
00908   f-> sigma0  = 1.6 * f->sigmak ;
00909   f-> dsigma0 = f->sigma0 * sqrt (1.0 - 1.0 / (f->sigmak*f->sigmak)) ;
00910 
00911   f-> gaussFilter = NULL ;
00912   f-> gaussFilterSigma = 0 ;
00913   f-> gaussFilterWidth = 0 ;
00914 
00915   f-> octave_width  = 0 ;
00916   f-> octave_height = 0 ;
00917 
00918   f-> keys     = 0 ;
00919   f-> nkeys    = 0 ;
00920   f-> keys_res = 0 ;
00921 
00922   f-> peak_thresh = 0.0 ;
00923   f-> edge_thresh = 10.0 ;
00924   f-> norm_thresh = 0.0 ;
00925   f-> magnif      = 3.0 ;
00926   f-> windowSize  = NBP / 2 ;
00927 
00928   f-> grad_o  = o_min - 1 ;
00929 
00930   /* initialize fast_expn stuff */
00931   fast_expn_init () ;
00932 
00933   return f ;
00934 }
00935 
00944 VL_EXPORT
00945 void
00946 vl_sift_delete (VlSiftFilt* f)
00947 {
00948   if (f) {
00949     if (f->keys) vl_free (f->keys) ;
00950     if (f->grad) vl_free (f->grad) ;
00951     if (f->dog) vl_free (f->dog) ;
00952     if (f->octave) vl_free (f->octave) ;
00953     if (f->temp) vl_free (f->temp) ;
00954     if (f->gaussFilter) vl_free (f->gaussFilter) ;
00955     vl_free (f) ;
00956   }
00957 }
00958 
00975 VL_EXPORT
00976 int
00977 vl_sift_process_first_octave (VlSiftFilt *f, vl_sift_pix const *im)
00978 {
00979   int o, s, h, w ;
00980   double sa, sb ;
00981   vl_sift_pix *octave ;
00982 
00983   /* shortcuts */
00984   vl_sift_pix *temp   = f-> temp ;
00985   int width           = f-> width ;
00986   int height          = f-> height ;
00987   int o_min           = f-> o_min ;
00988   int s_min           = f-> s_min ;
00989   int s_max           = f-> s_max ;
00990   double sigma0       = f-> sigma0 ;
00991   double sigmak       = f-> sigmak ;
00992   double sigman       = f-> sigman ;
00993   double dsigma0      = f-> dsigma0 ;
00994 
00995   /* restart from the first */
00996   f->o_cur = o_min ;
00997   f->nkeys = 0 ;
00998   w = f-> octave_width  = VL_SHIFT_LEFT(f->width,  - f->o_cur) ;
00999   h = f-> octave_height = VL_SHIFT_LEFT(f->height, - f->o_cur) ;
01000 
01001   /* is there at least one octave? */
01002   if (f->O == 0)
01003     return VL_ERR_EOF ;
01004 
01005   /* ------------------------------------------------------------------
01006    *                     Compute the first sublevel of the first octave
01007    * --------------------------------------------------------------- */
01008 
01009   /*
01010    * If the first octave has negative index, we upscale the image; if
01011    * the first octave has positive index, we downscale the image; if
01012    * the first octave has index zero, we just copy the image.
01013    */
01014 
01015   octave = vl_sift_get_octave (f, s_min) ;
01016 
01017   if (o_min < 0) {
01018     /* double once */
01019     copy_and_upsample_rows (temp,   im,   width,      height) ;
01020     copy_and_upsample_rows (octave, temp, height, 2 * width ) ;
01021 
01022     /* double more */
01023     for(o = -1 ; o > o_min ; --o) {
01024       copy_and_upsample_rows (temp, octave,
01025                               width << -o,      height << -o ) ;
01026       copy_and_upsample_rows (octave, temp,
01027                               width << -o, 2 * (height << -o)) ;
01028     }
01029   }
01030   else if (o_min > 0) {
01031     /* downsample */
01032     copy_and_downsample (octave, im, width, height, o_min) ;
01033   }
01034   else {
01035     /* direct copy */
01036     memcpy(octave, im, sizeof(vl_sift_pix) * width * height) ;
01037   }
01038 
01039   /*
01040    * Here we adjust the smoothing of the first level of the octave.
01041    * The input image is assumed to have nominal smoothing equal to
01042    * f->simgan.
01043    */
01044 
01045   sa = sigma0 * pow (sigmak,   s_min) ;
01046   sb = sigman * pow (2.0,    - o_min) ;
01047 
01048   if (sa > sb) {
01049     double sd = sqrt (sa*sa - sb*sb) ;
01050     _vl_sift_smooth (f, octave, temp, octave, w, h, sd) ;
01051   }
01052 
01053   /* -----------------------------------------------------------------
01054    *                                          Compute the first octave
01055    * -------------------------------------------------------------- */
01056 
01057   for(s = s_min + 1 ; s <= s_max ; ++s) {
01058     double sd = dsigma0 * pow (sigmak, s) ;
01059     _vl_sift_smooth (f, vl_sift_get_octave(f, s), temp,
01060                      vl_sift_get_octave(f, s - 1), w, h, sd) ;
01061   }
01062 
01063   return VL_ERR_OK ;
01064 }
01065 
01081 VL_EXPORT
01082 int
01083 vl_sift_process_next_octave (VlSiftFilt *f)
01084 {
01085 
01086   int s, h, w, s_best ;
01087   double sa, sb ;
01088   vl_sift_pix *octave, *pt ;
01089 
01090   /* shortcuts */
01091   vl_sift_pix *temp   = f-> temp ;
01092   int O               = f-> O ;
01093   int S               = f-> S ;
01094   int o_min           = f-> o_min ;
01095   int s_min           = f-> s_min ;
01096   int s_max           = f-> s_max ;
01097   double sigma0       = f-> sigma0 ;
01098   double sigmak       = f-> sigmak ;
01099   double dsigma0      = f-> dsigma0 ;
01100 
01101   /* is there another octave ? */
01102   if (f->o_cur == o_min + O - 1)
01103     return VL_ERR_EOF ;
01104 
01105   /* retrieve base */
01106   s_best = VL_MIN(s_min + S, s_max) ;
01107   w      = vl_sift_get_octave_width  (f) ;
01108   h      = vl_sift_get_octave_height (f) ;
01109   pt     = vl_sift_get_octave        (f, s_best) ;
01110   octave = vl_sift_get_octave        (f, s_min) ;
01111 
01112   /* next octave */
01113   copy_and_downsample (octave, pt, w, h, 1) ;
01114 
01115   f-> o_cur            += 1 ;
01116   f-> nkeys             = 0 ;
01117   w = f-> octave_width  = VL_SHIFT_LEFT(f->width,  - f->o_cur) ;
01118   h = f-> octave_height = VL_SHIFT_LEFT(f->height, - f->o_cur) ;
01119 
01120   sa = sigma0 * powf (sigmak, s_min     ) ;
01121   sb = sigma0 * powf (sigmak, s_best - S) ;
01122 
01123   if (sa > sb) {
01124     double sd = sqrt (sa*sa - sb*sb) ;
01125     _vl_sift_smooth (f, octave, temp, octave, w, h, sd) ;
01126   }
01127 
01128   /* ------------------------------------------------------------------
01129    *                                                        Fill octave
01130    * --------------------------------------------------------------- */
01131 
01132   for(s = s_min + 1 ; s <= s_max ; ++s) {
01133     double sd = dsigma0 * pow (sigmak, s) ;
01134     _vl_sift_smooth (f, vl_sift_get_octave(f, s), temp,
01135                      vl_sift_get_octave(f, s - 1), w, h, sd) ;
01136   }
01137 
01138   return VL_ERR_OK ;
01139 }
01140 
01151 VL_EXPORT
01152 void
01153 vl_sift_detect (VlSiftFilt * f)
01154 {
01155   vl_sift_pix* dog   = f-> dog ;
01156   int          s_min = f-> s_min ;
01157   int          s_max = f-> s_max ;
01158   int          w     = f-> octave_width ;
01159   int          h     = f-> octave_height ;
01160   double       te    = f-> edge_thresh ;
01161   double       tp    = f-> peak_thresh ;
01162 
01163   int const    xo    = 1 ;      /* x-stride */
01164   int const    yo    = w ;      /* y-stride */
01165   int const    so    = w * h ;  /* s-stride */
01166 
01167   double       xper  = pow (2.0, f->o_cur) ;
01168 
01169   int x, y, s, i, ii, jj ;
01170   vl_sift_pix *pt, v ;
01171   VlSiftKeypoint *k ;
01172 
01173   /* clear current list */
01174   f-> nkeys = 0 ;
01175 
01176   /* compute difference of gaussian (DoG) */
01177   pt = f-> dog ;
01178   for (s = s_min ; s <= s_max - 1 ; ++s) {
01179     vl_sift_pix* src_a = vl_sift_get_octave (f, s    ) ;
01180     vl_sift_pix* src_b = vl_sift_get_octave (f, s + 1) ;
01181     vl_sift_pix* end_a = src_a + w * h ;
01182     while (src_a != end_a) {
01183       *pt++ = *src_b++ - *src_a++ ;
01184     }
01185   }
01186 
01187   /* -----------------------------------------------------------------
01188    *                                          Find local maxima of DoG
01189    * -------------------------------------------------------------- */
01190 
01191   /* start from dog [1,1,s_min+1] */
01192   pt  = dog + xo + yo + so ;
01193 
01194   for(s = s_min + 1 ; s <= s_max - 2 ; ++s) {
01195     for(y = 1 ; y < h - 1 ; ++y) {
01196       for(x = 1 ; x < w - 1 ; ++x) {
01197         v = *pt ;
01198 
01199 #define CHECK_NEIGHBORS(CMP,SGN)                    \
01200         ( v CMP ## = SGN 0.8 * tp &&                \
01201           v CMP *(pt + xo) &&                       \
01202           v CMP *(pt - xo) &&                       \
01203           v CMP *(pt + so) &&                       \
01204           v CMP *(pt - so) &&                       \
01205           v CMP *(pt + yo) &&                       \
01206           v CMP *(pt - yo) &&                       \
01207                                                     \
01208           v CMP *(pt + yo + xo) &&                  \
01209           v CMP *(pt + yo - xo) &&                  \
01210           v CMP *(pt - yo + xo) &&                  \
01211           v CMP *(pt - yo - xo) &&                  \
01212                                                     \
01213           v CMP *(pt + xo      + so) &&             \
01214           v CMP *(pt - xo      + so) &&             \
01215           v CMP *(pt + yo      + so) &&             \
01216           v CMP *(pt - yo      + so) &&             \
01217           v CMP *(pt + yo + xo + so) &&             \
01218           v CMP *(pt + yo - xo + so) &&             \
01219           v CMP *(pt - yo + xo + so) &&             \
01220           v CMP *(pt - yo - xo + so) &&             \
01221                                                     \
01222           v CMP *(pt + xo      - so) &&             \
01223           v CMP *(pt - xo      - so) &&             \
01224           v CMP *(pt + yo      - so) &&             \
01225           v CMP *(pt - yo      - so) &&             \
01226           v CMP *(pt + yo + xo - so) &&             \
01227           v CMP *(pt + yo - xo - so) &&             \
01228           v CMP *(pt - yo + xo - so) &&             \
01229           v CMP *(pt - yo - xo - so) )
01230 
01231         if (CHECK_NEIGHBORS(>,+) ||
01232             CHECK_NEIGHBORS(<,-) ) {
01233 
01234           /* make room for more keypoints */
01235           if (f->nkeys >= f->keys_res) {
01236             f->keys_res += 500 ;
01237             if (f->keys) {
01238               f->keys = vl_realloc (f->keys,
01239                                     f->keys_res *
01240                                     sizeof(VlSiftKeypoint)) ;
01241             } else {
01242               f->keys = vl_malloc (f->keys_res *
01243                                    sizeof(VlSiftKeypoint)) ;
01244             }
01245           }
01246 
01247           k = f->keys + (f->nkeys ++) ;
01248 
01249           k-> ix = x ;
01250           k-> iy = y ;
01251           k-> is = s ;
01252         }
01253         pt += 1 ;
01254       }
01255       pt += 2 ;
01256     }
01257     pt += 2 * yo ;
01258   }
01259 
01260   /* -----------------------------------------------------------------
01261    *                                               Refine local maxima
01262    * -------------------------------------------------------------- */
01263 
01264   /* this pointer is used to write the keypoints back */
01265   k = f->keys ;
01266 
01267   for (i = 0 ; i < f->nkeys ; ++i) {
01268 
01269     int x = f-> keys [i] .ix ;
01270     int y = f-> keys [i] .iy ;
01271     int s = f-> keys [i]. is ;
01272 
01273     double Dx=0,Dy=0,Ds=0,Dxx=0,Dyy=0,Dss=0,Dxy=0,Dxs=0,Dys=0 ;
01274     double A [3*3], b [3] ;
01275 
01276     int dx = 0 ;
01277     int dy = 0 ;
01278 
01279     int iter, i, j ;
01280 
01281     for (iter = 0 ; iter < 5 ; ++iter) {
01282 
01283       x += dx ;
01284       y += dy ;
01285 
01286       pt = dog
01287         + xo * x
01288         + yo * y
01289         + so * (s - s_min) ;
01290 
01292 #define at(dx,dy,ds) (*( pt + (dx)*xo + (dy)*yo + (ds)*so))
01293 
01295 #define Aat(i,j)     (A[(i)+(j)*3])
01296 
01297       /* compute the gradient */
01298       Dx = 0.5 * (at(+1,0,0) - at(-1,0,0)) ;
01299       Dy = 0.5 * (at(0,+1,0) - at(0,-1,0));
01300       Ds = 0.5 * (at(0,0,+1) - at(0,0,-1)) ;
01301 
01302       /* compute the Hessian */
01303       Dxx = (at(+1,0,0) + at(-1,0,0) - 2.0 * at(0,0,0)) ;
01304       Dyy = (at(0,+1,0) + at(0,-1,0) - 2.0 * at(0,0,0)) ;
01305       Dss = (at(0,0,+1) + at(0,0,-1) - 2.0 * at(0,0,0)) ;
01306 
01307       Dxy = 0.25 * ( at(+1,+1,0) + at(-1,-1,0) - at(-1,+1,0) - at(+1,-1,0) ) ;
01308       Dxs = 0.25 * ( at(+1,0,+1) + at(-1,0,-1) - at(-1,0,+1) - at(+1,0,-1) ) ;
01309       Dys = 0.25 * ( at(0,+1,+1) + at(0,-1,-1) - at(0,-1,+1) - at(0,+1,-1) ) ;
01310 
01311       /* solve linear system ....................................... */
01312       Aat(0,0) = Dxx ;
01313       Aat(1,1) = Dyy ;
01314       Aat(2,2) = Dss ;
01315       Aat(0,1) = Aat(1,0) = Dxy ;
01316       Aat(0,2) = Aat(2,0) = Dxs ;
01317       Aat(1,2) = Aat(2,1) = Dys ;
01318 
01319       b[0] = - Dx ;
01320       b[1] = - Dy ;
01321       b[2] = - Ds ;
01322 
01323       /* Gauss elimination */
01324       for(j = 0 ; j < 3 ; ++j) {
01325         double maxa    = 0 ;
01326         double maxabsa = 0 ;
01327         int    maxi    = -1 ;
01328         double tmp ;
01329 
01330         /* look for the maximally stable pivot */
01331         for (i = j ; i < 3 ; ++i) {
01332           double a    = Aat (i,j) ;
01333           double absa = vl_abs_d (a) ;
01334           if (absa > maxabsa) {
01335             maxa    = a ;
01336             maxabsa = absa ;
01337             maxi    = i ;
01338           }
01339         }
01340 
01341         /* if singular give up */
01342         if (maxabsa < 1e-10f) {
01343           b[0] = 0 ;
01344           b[1] = 0 ;
01345           b[2] = 0 ;
01346           break ;
01347         }
01348 
01349         i = maxi ;
01350 
01351         /* swap j-th row with i-th row and normalize j-th row */
01352         for(jj = j ; jj < 3 ; ++jj) {
01353           tmp = Aat(i,jj) ; Aat(i,jj) = Aat(j,jj) ; Aat(j,jj) = tmp ;
01354           Aat(j,jj) /= maxa ;
01355         }
01356         tmp = b[j] ; b[j] = b[i] ; b[i] = tmp ;
01357         b[j] /= maxa ;
01358 
01359         /* elimination */
01360         for (ii = j+1 ; ii < 3 ; ++ii) {
01361           double x = Aat(ii,j) ;
01362           for (jj = j ; jj < 3 ; ++jj) {
01363             Aat(ii,jj) -= x * Aat(j,jj) ;
01364           }
01365           b[ii] -= x * b[j] ;
01366         }
01367       }
01368 
01369       /* backward substitution */
01370       for (i = 2 ; i > 0 ; --i) {
01371         double x = b[i] ;
01372         for (ii = i-1 ; ii >= 0 ; --ii) {
01373           b[ii] -= x * Aat(ii,i) ;
01374         }
01375       }
01376 
01377       /* .......................................................... */
01378       /* If the translation of the keypoint is big, move the keypoint
01379        * and re-iterate the computation. Otherwise we are all set.
01380        */
01381 
01382       dx= ((b[0] >  0.6 && x < w - 2) ?  1 : 0)
01383         + ((b[0] < -0.6 && x > 1    ) ? -1 : 0) ;
01384 
01385       dy= ((b[1] >  0.6 && y < h - 2) ?  1 : 0)
01386         + ((b[1] < -0.6 && y > 1    ) ? -1 : 0) ;
01387 
01388       if (dx == 0 && dy == 0) break ;
01389     }
01390 
01391     /* check threshold and other conditions */
01392     {
01393       double val   = at(0,0,0)
01394         + 0.5 * (Dx * b[0] + Dy * b[1] + Ds * b[2]) ;
01395       double score = (Dxx+Dyy)*(Dxx+Dyy) / (Dxx*Dyy - Dxy*Dxy) ;
01396       double xn = x + b[0] ;
01397       double yn = y + b[1] ;
01398       double sn = s + b[2] ;
01399 
01400       vl_bool good =
01401         vl_abs_d (val)  > tp                  &&
01402         score           < (te+1)*(te+1)/te    &&
01403         score           >= 0                  &&
01404         vl_abs_d (b[0]) <  1.5                &&
01405         vl_abs_d (b[1]) <  1.5                &&
01406         vl_abs_d (b[2]) <  1.5                &&
01407         xn              >= 0                  &&
01408         xn              <= w - 1              &&
01409         yn              >= 0                  &&
01410         yn              <= h - 1              &&
01411         sn              >= s_min              &&
01412         sn              <= s_max ;
01413 
01414       if (good) {
01415         k-> o     = f->o_cur ;
01416         k-> ix    = x ;
01417         k-> iy    = y ;
01418         k-> is    = s ;
01419         k-> s     = sn ;
01420         k-> x     = xn * xper ;
01421         k-> y     = yn * xper ;
01422         k-> sigma = f->sigma0 * pow (2.0, sn/f->S) * xper ;
01423         ++ k ;
01424       }
01425 
01426     } /* done checking */
01427   } /* next keypoint to refine */
01428 
01429   /* update keypoint count */
01430   f-> nkeys = (int)(k - f->keys) ;
01431 }
01432 
01433 
01446 static void
01447 update_gradient (VlSiftFilt *f)
01448 {
01449   int       s_min = f->s_min ;
01450   int       s_max = f->s_max ;
01451   int       w     = vl_sift_get_octave_width  (f) ;
01452   int       h     = vl_sift_get_octave_height (f) ;
01453   int const xo    = 1 ;
01454   int const yo    = w ;
01455   int const so    = h * w ;
01456   int y, s ;
01457 
01458   if (f->grad_o == f->o_cur) return ;
01459 
01460   for (s  = s_min + 1 ;
01461        s <= s_max - 2 ; ++ s) {
01462 
01463     vl_sift_pix *src, *end, *grad, gx, gy ;
01464 
01465 #define SAVE_BACK                                                       \
01466     *grad++ = vl_fast_sqrt_f (gx*gx + gy*gy) ;                          \
01467     *grad++ = vl_mod_2pi_f   (vl_fast_atan2_f (gy, gx) + 2*VL_PI) ;     \
01468     ++src ;                                                             \
01469 
01470     src  = vl_sift_get_octave (f,s) ;
01471     grad = f->grad + 2 * so * (s - s_min -1) ;
01472 
01473     /* first pixel of the first row */
01474     gx = src[+xo] - src[0] ;
01475     gy = src[+yo] - src[0] ;
01476     SAVE_BACK ;
01477 
01478     /* middle pixels of the  first row */
01479     end = (src - 1) + w - 1 ;
01480     while (src < end) {
01481       gx = 0.5 * (src[+xo] - src[-xo]) ;
01482       gy =        src[+yo] - src[0] ;
01483       SAVE_BACK ;
01484     }
01485 
01486     /* last pixel of the first row */
01487     gx = src[0]   - src[-xo] ;
01488     gy = src[+yo] - src[0] ;
01489     SAVE_BACK ;
01490 
01491     for (y = 1 ; y < h -1 ; ++y) {
01492 
01493       /* first pixel of the middle rows */
01494       gx =        src[+xo] - src[0] ;
01495       gy = 0.5 * (src[+yo] - src[-yo]) ;
01496       SAVE_BACK ;
01497 
01498       /* middle pixels of the middle rows */
01499       end = (src - 1) + w - 1 ;
01500       while (src < end) {
01501         gx = 0.5 * (src[+xo] - src[-xo]) ;
01502         gy = 0.5 * (src[+yo] - src[-yo]) ;
01503         SAVE_BACK ;
01504       }
01505 
01506       /* last pixel of the middle row */
01507       gx =        src[0]   - src[-xo] ;
01508       gy = 0.5 * (src[+yo] - src[-yo]) ;
01509       SAVE_BACK ;
01510     }
01511 
01512     /* first pixel of the last row */
01513     gx = src[+xo] - src[0] ;
01514     gy = src[  0] - src[-yo] ;
01515     SAVE_BACK ;
01516 
01517     /* middle pixels of the last row */
01518     end = (src - 1) + w - 1 ;
01519     while (src < end) {
01520       gx = 0.5 * (src[+xo] - src[-xo]) ;
01521       gy =        src[0]   - src[-yo] ;
01522       SAVE_BACK ;
01523     }
01524 
01525     /* last pixel of the last row */
01526     gx = src[0]   - src[-xo] ;
01527     gy = src[0]   - src[-yo] ;
01528     SAVE_BACK ;
01529   }
01530   f->grad_o = f->o_cur ;
01531 }
01532 
01557 VL_EXPORT
01558 int
01559 vl_sift_calc_keypoint_orientations (VlSiftFilt *f,
01560                                     double angles [4],
01561                                     VlSiftKeypoint const *k)
01562 {
01563   double const winf   = 1.5 ;
01564   double       xper   = pow (2.0, f->o_cur) ;
01565 
01566   int          w      = f-> octave_width ;
01567   int          h      = f-> octave_height ;
01568   int const    xo     = 2 ;         /* x-stride */
01569   int const    yo     = 2 * w ;     /* y-stride */
01570   int const    so     = 2 * w * h ; /* s-stride */
01571   double       x      = k-> x     / xper ;
01572   double       y      = k-> y     / xper ;
01573   double       sigma  = k-> sigma / xper ;
01574 
01575   int          xi     = (int) (x + 0.5) ;
01576   int          yi     = (int) (y + 0.5) ;
01577   int          si     = k-> is ;
01578 
01579   double const sigmaw = winf * sigma ;
01580   int          W      = VL_MAX(floor (3.0 * sigmaw), 1) ;
01581 
01582   int          nangles= 0 ;
01583 
01584   enum {nbins = 36} ;
01585 
01586   double hist [nbins], maxh ;
01587   vl_sift_pix const * pt ;
01588   int xs, ys, iter, i ;
01589 
01590   /* skip if the keypoint octave is not current */
01591   if(k->o != f->o_cur)
01592     return 0 ;
01593 
01594   /* skip the keypoint if it is out of bounds */
01595   if(xi < 0            ||
01596      xi > w - 1        ||
01597      yi < 0            ||
01598      yi > h - 1        ||
01599      si < f->s_min + 1 ||
01600      si > f->s_max - 2  ) {
01601     return 0 ;
01602   }
01603 
01604   /* make gradient up to date */
01605   update_gradient (f) ;
01606 
01607   /* clear histogram */
01608   memset (hist, 0, sizeof(double) * nbins) ;
01609 
01610   /* compute orientation histogram */
01611   pt = f-> grad + xo*xi + yo*yi + so*(si - f->s_min - 1) ;
01612 
01613 #undef  at
01614 #define at(dx,dy) (*(pt + xo * (dx) + yo * (dy)))
01615 
01616   for(ys  =  VL_MAX (- W,       - yi) ;
01617       ys <=  VL_MIN (+ W, h - 1 - yi) ; ++ys) {
01618 
01619     for(xs  = VL_MAX (- W,       - xi) ;
01620         xs <= VL_MIN (+ W, w - 1 - xi) ; ++xs) {
01621 
01622 
01623       double dx = (double)(xi + xs) - x;
01624       double dy = (double)(yi + ys) - y;
01625       double r2 = dx*dx + dy*dy ;
01626       double wgt, mod, ang, fbin ;
01627 
01628       /* limit to a circular window */
01629       if (r2 >= W*W + 0.6) continue ;
01630 
01631       wgt  = fast_expn (r2 / (2*sigmaw*sigmaw)) ;
01632       mod  = *(pt + xs*xo + ys*yo    ) ;
01633       ang  = *(pt + xs*xo + ys*yo + 1) ;
01634       fbin = nbins * ang / (2 * VL_PI) ;
01635 
01636 #if defined(VL_SIFT_BILINEAR_ORIENTATIONS)
01637       {
01638         int bin = (int) vl_floor_d (fbin - 0.5) ;
01639         double rbin = fbin - bin - 0.5 ;
01640         hist [(bin + nbins) % nbins] += (1 - rbin) * mod * wgt ;
01641         hist [(bin + 1    ) % nbins] += (    rbin) * mod * wgt ;
01642       }
01643 #else
01644       {
01645         int    bin  = vl_floor_d (fbin) ;
01646         bin = vl_floor_d (nbins * ang / (2*VL_PI)) ;
01647         hist [(bin) % nbins] += mod * wgt ;
01648       }
01649 #endif
01650 
01651     } /* for xs */
01652   } /* for ys */
01653 
01654   /* smooth histogram */
01655   for (iter = 0; iter < 6; iter ++) {
01656     double prev  = hist [nbins - 1] ;
01657     double first = hist [0] ;
01658     int i ;
01659     for (i = 0; i < nbins - 1; i++) {
01660       double newh = (prev + hist[i] + hist[(i+1) % nbins]) / 3.0;
01661       prev = hist[i] ;
01662       hist[i] = newh ;
01663     }
01664     hist[i] = (prev + hist[i] + first) / 3.0 ;
01665   }
01666 
01667   /* find the histogram maximum */
01668   maxh = 0 ;
01669   for (i = 0 ; i < nbins ; ++i)
01670     maxh = VL_MAX (maxh, hist [i]) ;
01671 
01672   /* find peaks within 80% from max */
01673   nangles = 0 ;
01674   for(i = 0 ; i < nbins ; ++i) {
01675     double h0 = hist [i] ;
01676     double hm = hist [(i - 1 + nbins) % nbins] ;
01677     double hp = hist [(i + 1 + nbins) % nbins] ;
01678 
01679     /* is this a peak? */
01680     if (h0 > 0.8*maxh && h0 > hm && h0 > hp) {
01681 
01682       /* quadratic interpolation */
01683       double di = - 0.5 * (hp - hm) / (hp + hm - 2 * h0) ;
01684       double th = 2 * VL_PI * (i + di + 0.5) / nbins ;
01685       angles [ nangles++ ] = th ;
01686       if( nangles == 4 )
01687         goto enough_angles ;
01688     }
01689   }
01690  enough_angles:
01691   return nangles ;
01692 }
01693 
01694 
01702 VL_INLINE vl_sift_pix
01703 normalize_histogram
01704 (vl_sift_pix *begin, vl_sift_pix *end)
01705 {
01706   vl_sift_pix* iter ;
01707   vl_sift_pix  norm = 0.0 ;
01708 
01709   for (iter = begin ; iter != end ; ++ iter)
01710     norm += (*iter) * (*iter) ;
01711 
01712   norm = vl_fast_sqrt_f (norm) + VL_EPSILON_F ;
01713 
01714   for (iter = begin; iter != end ; ++ iter)
01715     *iter /= norm ;
01716 
01717   return norm;
01718 }
01719 
01752 VL_EXPORT
01753 void
01754 vl_sift_calc_raw_descriptor (VlSiftFilt const *f,
01755                              vl_sift_pix const* grad,
01756                              vl_sift_pix *descr,
01757                              int width, int height,
01758                              double x, double y,
01759                              double sigma,
01760                              double angle0)
01761 {
01762   double const magnif = f-> magnif ;
01763 
01764   int          w      = width ;
01765   int          h      = height ;
01766   int const    xo     = 2 ;         /* x-stride */
01767   int const    yo     = 2 * w ;     /* y-stride */
01768 
01769   int          xi     = (int) (x + 0.5) ;
01770   int          yi     = (int) (y + 0.5) ;
01771 
01772   double const st0    = sin (angle0) ;
01773   double const ct0    = cos (angle0) ;
01774   double const SBP    = magnif * sigma + VL_EPSILON_D ;
01775   int    const W      = floor
01776     (sqrt(2.0) * SBP * (NBP + 1) / 2.0 + 0.5) ;
01777 
01778   int const binto = 1 ;          /* bin theta-stride */
01779   int const binyo = NBO * NBP ;  /* bin y-stride */
01780   int const binxo = NBO ;        /* bin x-stride */
01781 
01782   int bin, dxi, dyi ;
01783   vl_sift_pix const *pt ;
01784   vl_sift_pix       *dpt ;
01785 
01786   /* check bounds */
01787   if(xi    <  0               ||
01788      xi    >= w               ||
01789      yi    <  0               ||
01790      yi    >= h -    1        )
01791     return ;
01792 
01793   /* clear descriptor */
01794   memset (descr, 0, sizeof(vl_sift_pix) * NBO*NBP*NBP) ;
01795 
01796   /* Center the scale space and the descriptor on the current keypoint.
01797    * Note that dpt is pointing to the bin of center (SBP/2,SBP/2,0).
01798    */
01799   pt  = grad + xi*xo + yi*yo ;
01800   dpt = descr + (NBP/2) * binyo + (NBP/2) * binxo ;
01801 
01802 #undef atd
01803 #define atd(dbinx,dbiny,dbint) *(dpt + (dbint)*binto + (dbiny)*binyo + (dbinx)*binxo)
01804 
01805   /*
01806    * Process pixels in the intersection of the image rectangle
01807    * (1,1)-(M-1,N-1) and the keypoint bounding box.
01808    */
01809   for(dyi =  VL_MAX(- W,   - yi   ) ;
01810       dyi <= VL_MIN(+ W, h - yi -1) ; ++ dyi) {
01811 
01812     for(dxi =  VL_MAX(- W,   - xi   ) ;
01813         dxi <= VL_MIN(+ W, w - xi -1) ; ++ dxi) {
01814 
01815       /* retrieve */
01816       vl_sift_pix mod   = *( pt + dxi*xo + dyi*yo + 0 ) ;
01817       vl_sift_pix angle = *( pt + dxi*xo + dyi*yo + 1 ) ;
01818       vl_sift_pix theta = vl_mod_2pi_f (angle - angle0) ;
01819 
01820       /* fractional displacement */
01821       vl_sift_pix dx = xi + dxi - x;
01822       vl_sift_pix dy = yi + dyi - y;
01823 
01824       /* get the displacement normalized w.r.t. the keypoint
01825          orientation and extension */
01826       vl_sift_pix nx = ( ct0 * dx + st0 * dy) / SBP ;
01827       vl_sift_pix ny = (-st0 * dx + ct0 * dy) / SBP ;
01828       vl_sift_pix nt = NBO * theta / (2 * VL_PI) ;
01829 
01830       /* Get the Gaussian weight of the sample. The Gaussian window
01831        * has a standard deviation equal to NBP/2. Note that dx and dy
01832        * are in the normalized frame, so that -NBP/2 <= dx <=
01833        * NBP/2. */
01834       vl_sift_pix const wsigma = f->windowSize ;
01835       vl_sift_pix win = fast_expn
01836         ((nx*nx + ny*ny)/(2.0 * wsigma * wsigma)) ;
01837 
01838       /* The sample will be distributed in 8 adjacent bins.
01839          We start from the ``lower-left'' bin. */
01840       int         binx = (int)vl_floor_f (nx - 0.5) ;
01841       int         biny = (int)vl_floor_f (ny - 0.5) ;
01842       int         bint = (int)vl_floor_f (nt) ;
01843       vl_sift_pix rbinx = nx - (binx + 0.5) ;
01844       vl_sift_pix rbiny = ny - (biny + 0.5) ;
01845       vl_sift_pix rbint = nt - bint ;
01846       int         dbinx ;
01847       int         dbiny ;
01848       int         dbint ;
01849 
01850       /* Distribute the current sample into the 8 adjacent bins*/
01851       for(dbinx = 0 ; dbinx < 2 ; ++dbinx) {
01852         for(dbiny = 0 ; dbiny < 2 ; ++dbiny) {
01853           for(dbint = 0 ; dbint < 2 ; ++dbint) {
01854 
01855             if (binx + dbinx >= - (NBP/2) &&
01856                 binx + dbinx <    (NBP/2) &&
01857                 biny + dbiny >= - (NBP/2) &&
01858                 biny + dbiny <    (NBP/2) ) {
01859               vl_sift_pix weight = win
01860                 * mod
01861                 * vl_abs_f (1 - dbinx - rbinx)
01862                 * vl_abs_f (1 - dbiny - rbiny)
01863                 * vl_abs_f (1 - dbint - rbint) ;
01864 
01865               atd(binx+dbinx, biny+dbiny, (bint+dbint) % NBO) += weight ;
01866             }
01867           }
01868         }
01869       }
01870     }
01871   }
01872 
01873   /* Standard SIFT descriptors are normalized, truncated and normalized again */
01874   if(1) {
01875 
01876     /* normalize L2 norm */
01877     vl_sift_pix norm = normalize_histogram (descr, descr + NBO*NBP*NBP) ;
01878 
01879     /*
01880        Set the descriptor to zero if it is lower than our
01881        norm_threshold.  We divide by the number of samples in the
01882        descriptor region because the Gaussian window used in the
01883        calculation of the descriptor is not normalized.
01884      */
01885     int numSamples =
01886       (VL_MIN(W, w - xi -1) - VL_MAX(-W, - xi) + 1) *
01887       (VL_MIN(W, h - yi -1) - VL_MAX(-W, - yi) + 1) ;
01888 
01889     if(f-> norm_thresh && norm < f-> norm_thresh * numSamples) {
01890         for(bin = 0; bin < NBO*NBP*NBP ; ++ bin)
01891             descr [bin] = 0;
01892     }
01893     else {
01894       /* truncate at 0.2. */
01895       for(bin = 0; bin < NBO*NBP*NBP ; ++ bin) {
01896         if (descr [bin] > 0.2) descr [bin] = 0.2;
01897       }
01898 
01899       /* normalize again. */
01900       normalize_histogram (descr, descr + NBO*NBP*NBP) ;
01901     }
01902   }
01903 }
01904 
01921 VL_EXPORT
01922 void
01923 vl_sift_calc_keypoint_descriptor (VlSiftFilt *f,
01924                                   vl_sift_pix *descr,
01925                                   VlSiftKeypoint const* k,
01926                                   double angle0)
01927 {
01928   /*
01929      The SIFT descriptor is a three dimensional histogram of the
01930      position and orientation of the gradient.  There are NBP bins for
01931      each spatial dimension and NBO bins for the orientation dimension,
01932      for a total of NBP x NBP x NBO bins.
01933 
01934      The support of each spatial bin has an extension of SBP = 3sigma
01935      pixels, where sigma is the scale of the keypoint.  Thus all the
01936      bins together have a support SBP x NBP pixels wide. Since
01937      weighting and interpolation of pixel is used, the support extends
01938      by another half bin. Therefore, the support is a square window of
01939      SBP x (NBP + 1) pixels. Finally, since the patch can be
01940      arbitrarily rotated, we need to consider a window 2W += sqrt(2) x
01941      SBP x (NBP + 1) pixels wide.
01942   */
01943 
01944   double const magnif      = f-> magnif ;
01945 
01946   double       xper        = pow (2.0, f->o_cur) ;
01947 
01948   int          w           = f-> octave_width ;
01949   int          h           = f-> octave_height ;
01950   int const    xo          = 2 ;         /* x-stride */
01951   int const    yo          = 2 * w ;     /* y-stride */
01952   int const    so          = 2 * w * h ; /* s-stride */
01953   double       x           = k-> x     / xper ;
01954   double       y           = k-> y     / xper ;
01955   double       sigma       = k-> sigma / xper ;
01956 
01957   int          xi          = (int) (x + 0.5) ;
01958   int          yi          = (int) (y + 0.5) ;
01959   int          si          = k-> is ;
01960 
01961   double const st0         = sin (angle0) ;
01962   double const ct0         = cos (angle0) ;
01963   double const SBP         = magnif * sigma + VL_EPSILON_D ;
01964   int    const W           = floor
01965     (sqrt(2.0) * SBP * (NBP + 1) / 2.0 + 0.5) ;
01966 
01967   int const binto = 1 ;          /* bin theta-stride */
01968   int const binyo = NBO * NBP ;  /* bin y-stride */
01969   int const binxo = NBO ;        /* bin x-stride */
01970 
01971   int bin, dxi, dyi ;
01972   vl_sift_pix const *pt ;
01973   vl_sift_pix       *dpt ;
01974 
01975   /* check bounds */
01976   if(k->o  != f->o_cur        ||
01977      xi    <  0               ||
01978      xi    >= w               ||
01979      yi    <  0               ||
01980      yi    >= h -    1        ||
01981      si    <  f->s_min + 1    ||
01982      si    >  f->s_max - 2     )
01983     return ;
01984 
01985   /* synchronize gradient buffer */
01986   update_gradient (f) ;
01987 
01988   /* VL_PRINTF("W = %d ; magnif = %g ; SBP = %g\n", W,magnif,SBP) ; */
01989 
01990   /* clear descriptor */
01991   memset (descr, 0, sizeof(vl_sift_pix) * NBO*NBP*NBP) ;
01992 
01993   /* Center the scale space and the descriptor on the current keypoint.
01994    * Note that dpt is pointing to the bin of center (SBP/2,SBP/2,0).
01995    */
01996   pt  = f->grad + xi*xo + yi*yo + (si - f->s_min - 1)*so ;
01997   dpt = descr + (NBP/2) * binyo + (NBP/2) * binxo ;
01998 
01999 #undef atd
02000 #define atd(dbinx,dbiny,dbint) *(dpt + (dbint)*binto + (dbiny)*binyo + (dbinx)*binxo)
02001 
02002   /*
02003    * Process pixels in the intersection of the image rectangle
02004    * (1,1)-(M-1,N-1) and the keypoint bounding box.
02005    */
02006   for(dyi =  VL_MAX (- W, 1 - yi    ) ;
02007       dyi <= VL_MIN (+ W, h - yi - 2) ; ++ dyi) {
02008 
02009     for(dxi =  VL_MAX (- W, 1 - xi    ) ;
02010         dxi <= VL_MIN (+ W, w - xi - 2) ; ++ dxi) {
02011 
02012       /* retrieve */
02013       vl_sift_pix mod   = *( pt + dxi*xo + dyi*yo + 0 ) ;
02014       vl_sift_pix angle = *( pt + dxi*xo + dyi*yo + 1 ) ;
02015       vl_sift_pix theta = vl_mod_2pi_f (angle - angle0) ;
02016 
02017       /* fractional displacement */
02018       vl_sift_pix dx = xi + dxi - x;
02019       vl_sift_pix dy = yi + dyi - y;
02020 
02021       /* get the displacement normalized w.r.t. the keypoint
02022          orientation and extension */
02023       vl_sift_pix nx = ( ct0 * dx + st0 * dy) / SBP ;
02024       vl_sift_pix ny = (-st0 * dx + ct0 * dy) / SBP ;
02025       vl_sift_pix nt = NBO * theta / (2 * VL_PI) ;
02026 
02027       /* Get the Gaussian weight of the sample. The Gaussian window
02028        * has a standard deviation equal to NBP/2. Note that dx and dy
02029        * are in the normalized frame, so that -NBP/2 <= dx <=
02030        * NBP/2. */
02031       vl_sift_pix const wsigma = f->windowSize ;
02032       vl_sift_pix win = fast_expn
02033         ((nx*nx + ny*ny)/(2.0 * wsigma * wsigma)) ;
02034 
02035       /* The sample will be distributed in 8 adjacent bins.
02036          We start from the ``lower-left'' bin. */
02037       int         binx = (int)vl_floor_f (nx - 0.5) ;
02038       int         biny = (int)vl_floor_f (ny - 0.5) ;
02039       int         bint = (int)vl_floor_f (nt) ;
02040       vl_sift_pix rbinx = nx - (binx + 0.5) ;
02041       vl_sift_pix rbiny = ny - (biny + 0.5) ;
02042       vl_sift_pix rbint = nt - bint ;
02043       int         dbinx ;
02044       int         dbiny ;
02045       int         dbint ;
02046 
02047       /* Distribute the current sample into the 8 adjacent bins*/
02048       for(dbinx = 0 ; dbinx < 2 ; ++dbinx) {
02049         for(dbiny = 0 ; dbiny < 2 ; ++dbiny) {
02050           for(dbint = 0 ; dbint < 2 ; ++dbint) {
02051 
02052             if (binx + dbinx >= - (NBP/2) &&
02053                 binx + dbinx <    (NBP/2) &&
02054                 biny + dbiny >= - (NBP/2) &&
02055                 biny + dbiny <    (NBP/2) ) {
02056               vl_sift_pix weight = win
02057                 * mod
02058                 * vl_abs_f (1 - dbinx - rbinx)
02059                 * vl_abs_f (1 - dbiny - rbiny)
02060                 * vl_abs_f (1 - dbint - rbint) ;
02061 
02062               atd(binx+dbinx, biny+dbiny, (bint+dbint) % NBO) += weight ;
02063             }
02064           }
02065         }
02066       }
02067     }
02068   }
02069 
02070   /* Standard SIFT descriptors are normalized, truncated and normalized again */
02071   if(1) {
02072 
02073     /* Normalize the histogram to L2 unit length. */
02074     vl_sift_pix norm = normalize_histogram (descr, descr + NBO*NBP*NBP) ;
02075 
02076     /* Set the descriptor to zero if it is lower than our norm_threshold */
02077     if(f-> norm_thresh && norm < f-> norm_thresh) {
02078         for(bin = 0; bin < NBO*NBP*NBP ; ++ bin)
02079             descr [bin] = 0;
02080     }
02081     else {
02082 
02083       /* Truncate at 0.2. */
02084       for(bin = 0; bin < NBO*NBP*NBP ; ++ bin) {
02085         if (descr [bin] > 0.2) descr [bin] = 0.2;
02086       }
02087 
02088       /* Normalize again. */
02089       normalize_histogram (descr, descr + NBO*NBP*NBP) ;
02090     }
02091   }
02092 
02093 }
02094 
02161 VL_EXPORT
02162 void
02163 vl_sift_keypoint_init (VlSiftFilt const *f,
02164                        VlSiftKeypoint *k,
02165                        double x,
02166                        double y,
02167                        double sigma)
02168 {
02169   int    o, ix, iy, is ;
02170   double s, phi, xper ;
02171 
02172   phi = log2 ((sigma + VL_EPSILON_D) / f->sigma0) ;
02173   o   = (int)vl_floor_d (phi -  ((double) f->s_min + 0.5) / f->S) ;
02174   o   = VL_MIN (o, f->o_min + f->O - 1) ;
02175   o   = VL_MAX (o, f->o_min           ) ;
02176   s   = f->S * (phi - o) ;
02177 
02178   is  = (int)(s + 0.5) ;
02179   is  = VL_MIN(is, f->s_max - 2) ;
02180   is  = VL_MAX(is, f->s_min + 1) ;
02181 
02182   xper = pow (2.0, o) ;
02183   ix   = (int)(x / xper + 0.5) ;
02184   iy   = (int)(y / xper + 0.5) ;
02185 
02186   k -> o  = o ;
02187 
02188   k -> ix = ix ;
02189   k -> iy = iy ;
02190   k -> is = is ;
02191 
02192   k -> x = x ;
02193   k -> y = y ;
02194   k -> s = s ;
02195 
02196   k->sigma = sigma ;
02197 }


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