dsift.h
Go to the documentation of this file.
00001 
00007 /*
00008 Copyright (C) 2007-12 Andrea Vedaldi and Brian Fulkerson.
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 
00015 #ifndef VL_DSIFT_H
00016 #define VL_DSIFT_H
00017 
00018 //#include "generic.h"
00019 #include <emmintrin.h>
00020 #include <assert.h>
00021 
00022 // various defines
00023 #define VL_INLINE static __inline__
00024 #define VL_EXPORT extern "C"
00025 #define VL_EPSILON_F 1.19209290E-07F
00026 
00027 typedef int vl_bool ;    
00029 #define VL_TRUE 1   
00030 #define VL_FALSE 0  
00031 #define VL_TRANSPOSE         (0x1 << 2) 
00032 #define VL_PAD_BY_CONTINUITY (0x1 << 0) 
00033 #define VL_PAD_BY_ZERO       (0x0 << 0) 
00034 #define VL_PAD_MASK          (0x3)      
00035 #define VSIZE  4
00036 #define VSFX   s
00037 #define VTYPE  __m128
00038 #define VALIGNED(x) (! (((vl_uintptr)(x)) & 0xF))
00039 
00040 #define VL_PI 3.141592653589793
00041 #define VL_MAX(x,y) (((x)>(y))?(x):(y))
00042 #define VL_MIN(x,y) (((x)<(y))?(x):(y))
00043 
00044 #define VSTZ  _mm_setzero_ps
00045 #define VADD  _mm_add_ps
00046 #define VLD1 _mm_load1_ps
00047 #define VMUL  _mm_mul_ps
00048 
00049 // jic
00050 /* #define VMAX  VL_XCAT(_mm_max_p,     VSFX) */
00051 /* #define VDIV  VL_XCAT(_mm_div_p,     VSFX) */
00052 /* #define VSUB  VL_XCAT(_mm_sub_p,     VSFX) */
00053 /* #define VLDU  VL_XCAT(_mm_loadu_p,   VSFX) */
00054 /* #define VST1  VL_XCAT(_mm_store_s,   VSFX) */
00055 /* #define VSET1 VL_XCAT(_mm_set_s,     VSFX) */
00056 /* #define VSHU  VL_XCAT(_mm_shuffle_p, VSFX) */
00057 /* #define VNEQ  VL_XCAT(_mm_cmpneq_p,  VSFX) */
00058 /* #define VAND  VL_XCAT(_mm_and_p,     VSFX) */
00059 /* #define VANDN VL_XCAT(_mm_andnot_p,  VSFX) */
00060 
00061 typedef long long           vl_int64 ;   
00062 typedef long long unsigned  vl_uint64 ;  
00063 typedef vl_uint64           vl_uintptr ; 
00064 typedef vl_uint64           vl_size ;    
00065 typedef int                 vl_int32 ;   
00066 typedef vl_int64            vl_index ;   
00069 // Imported functions from other modules
00072 void vl_imconvcol_vf (float* dst, int dst_stride,
00073                       float const* src,
00074                       int src_width, int src_height, int src_stride,
00075                       float const* filt, int filt_begin, int filt_end,
00076                       int step, unsigned int flags) ;
00077 
00078 void vl_imconvcoltri_f(float * dest, vl_size destStride,
00079                        float const * image,
00080                        vl_size imageWidth, vl_size imageHeight, vl_size imageStride,
00081                        vl_size filterSize,
00082                        vl_size step, unsigned int flags) ;
00083 
00084 
00085 VL_INLINE float
00086 vl_abs_f (float x)
00087 {
00088 // deactivated for precaution...
00089 //#ifdef VL_COMPILER_GNUC
00090   return __builtin_fabsf (x) ;
00091 //#else
00092 //  return fabsf(x) ;
00093 //#endif
00094 }
00095 
00096 VL_INLINE float
00097 vl_mod_2pi_f (float x)
00098 {
00099   while (x > (float)(2 * VL_PI)) x -= (float) (2 * VL_PI) ;
00100   while (x < 0.0F) x += (float) (2 * VL_PI);
00101   return x ;
00102 }
00103 
00104 VL_INLINE long int
00105 vl_floor_f (float x)
00106 {
00107   long int xi = (long int) x ;
00108   if (x >= 0 || (float) xi == x) return xi ;
00109   else return xi - 1 ;
00110 }
00111 
00112 VL_INLINE float
00113 vl_fast_resqrt_f (float x)
00114 {
00115   /* 32-bit version */
00116   union {
00117     float x ;
00118     vl_int32  i ;
00119   } u ;
00120 
00121   float xhalf = (float) 0.5 * x ;
00122 
00123   /* convert floating point value in RAW integer */
00124   u.x = x ;
00125 
00126   /* gives initial guess y0 */
00127   u.i = 0x5f3759df - (u.i >> 1);
00128   /*u.i = 0xdf59375f - (u.i>>1);*/
00129 
00130   /* two Newton steps */
00131   u.x = u.x * ( (float) 1.5  - xhalf*u.x*u.x) ;
00132   u.x = u.x * ( (float) 1.5  - xhalf*u.x*u.x) ;
00133   return u.x ;
00134 }
00135 
00136 VL_INLINE float
00137 vl_fast_sqrt_f (float x)
00138 {
00139   return (x < 1e-8) ? 0 : x * vl_fast_resqrt_f (x) ;
00140 }
00141 
00142 VL_INLINE float
00143 vl_fast_atan2_f (float y, float x)
00144 {
00145   float angle, r ;
00146   float const c3 = 0.1821F ;
00147   float const c1 = 0.9675F ;
00148   float abs_y    = vl_abs_f (y) + VL_EPSILON_F ;
00149 
00150   if (x >= 0) {
00151     r = (x - abs_y) / (x + abs_y) ;
00152     angle = (float) (VL_PI / 4) ;
00153   } else {
00154     r = (x + abs_y) / (abs_y - x) ;
00155     angle = (float) (3 * VL_PI / 4) ;
00156   }
00157   angle += (c3*r*r - c1) * r ;
00158   return (y < 0) ? - angle : angle ;
00159 }
00160 
00161 
00162 
00163 
00164 
00166 
00167 
00169 typedef struct VlDsiftKeypoint_
00170 {
00171   double x ; 
00172   double y ; 
00173   double s ; 
00174   double norm ; 
00175 } VlDsiftKeypoint ;
00176 
00178 typedef struct VlDsiftDescriptorGeometry_
00179 {
00180   int numBinT ;  
00181   int numBinX ;  
00182   int numBinY ;  
00183   int binSizeX ; 
00184   int binSizeY ; 
00185 } VlDsiftDescriptorGeometry ;
00186 
00188 typedef struct VlDsiftFilter_
00189 {
00190   int imWidth ;            
00191   int imHeight ;           
00193   int stepX ;              
00194   int stepY ;              
00196   int boundMinX ;          
00197   int boundMinY ;          
00198   int boundMaxX ;          
00199   int boundMaxY ;          
00202   VlDsiftDescriptorGeometry geom ;
00203 
00204   int useFlatWindow ;      
00205   double windowSize ;      
00207   int numFrames ;          
00208   int descrSize ;          
00209   VlDsiftKeypoint *frames ; 
00210   float *descrs ;          
00212   int numBinAlloc ;        
00213   int numFrameAlloc ;      
00214   int numGradAlloc ;       
00216   float **grads ;          
00217   float *convTmp1 ;        
00218   float *convTmp2 ;        
00219 }  VlDsiftFilter ;
00220 
00221 VlDsiftFilter *vl_dsift_new (int width, int height) ;
00222 VlDsiftFilter *vl_dsift_new_basic (int width, int height, int step, int binSize) ;
00223 void vl_dsift_delete (VlDsiftFilter *self) ;
00224 void vl_dsift_process (VlDsiftFilter *self, float const* im) ;
00225 VL_INLINE void vl_dsift_transpose_descriptor (float* dst,
00226                                              float const* src,
00227                                              int numBinT,
00228                                              int numBinX,
00229                                              int numBinY) ;
00230 
00234 VL_INLINE void vl_dsift_set_steps (VlDsiftFilter *self,
00235                                   int stepX,
00236                                   int stepY) ;
00237 VL_INLINE void vl_dsift_set_bounds (VlDsiftFilter *self,
00238                                    int minX,
00239                                    int minY,
00240                                    int maxX,
00241                                    int maxY) ;
00242 VL_INLINE void vl_dsift_set_geometry (VlDsiftFilter *self,
00243                                       VlDsiftDescriptorGeometry const* geom) ;
00244 VL_INLINE void vl_dsift_set_flat_window (VlDsiftFilter *self, vl_bool useFlatWindow) ;
00245 VL_INLINE void vl_dsift_set_window_size (VlDsiftFilter *self, double windowSize) ;
00251 VL_INLINE float const    *vl_dsift_get_descriptors     (VlDsiftFilter const *self) ;
00252 VL_INLINE int             vl_dsift_get_descriptor_size (VlDsiftFilter const *self) ;
00253 VL_INLINE int             vl_dsift_get_keypoint_num    (VlDsiftFilter const *self) ;
00254 VL_INLINE VlDsiftKeypoint const *vl_dsift_get_keypoints (VlDsiftFilter const *self) ;
00255 VL_INLINE void            vl_dsift_get_bounds          (VlDsiftFilter const *self,
00256                                                        int* minX,
00257                                                        int* minY,
00258                                                        int* maxX,
00259                                                        int* maxY) ;
00260 VL_INLINE void            vl_dsift_get_steps           (VlDsiftFilter const* self,
00261                                                        int* stepX,
00262                                                        int* stepY) ;
00263 VL_INLINE VlDsiftDescriptorGeometry const* vl_dsift_get_geometry (VlDsiftFilter const *self) ;
00264 VL_INLINE vl_bool         vl_dsift_get_flat_window     (VlDsiftFilter const *self) ;
00265 VL_INLINE double          vl_dsift_get_window_size     (VlDsiftFilter const *self) ;
00269 void _vl_dsift_update_buffers (VlDsiftFilter *self) ;
00270 
00277 int
00278 vl_dsift_get_descriptor_size (VlDsiftFilter const *self)
00279 {
00280   return self->descrSize ;
00281 }
00282 
00289 float const *
00290 vl_dsift_get_descriptors (VlDsiftFilter const *self)
00291 {
00292   return self->descrs ;
00293 }
00294 
00300 VlDsiftKeypoint const *
00301 vl_dsift_get_keypoints (VlDsiftFilter const *self)
00302 {
00303   return self->frames ;
00304 }
00305 
00311 int
00312 vl_dsift_get_keypoint_num (VlDsiftFilter const *self)
00313 {
00314   return self->numFrames ;
00315 }
00316 
00323 VlDsiftDescriptorGeometry const* vl_dsift_get_geometry (VlDsiftFilter const *self)
00324 {
00325   return &self->geom ;
00326 }
00327 
00337 void
00338 vl_dsift_get_bounds (VlDsiftFilter const* self,
00339                     int *minX, int *minY, int *maxX, int *maxY)
00340 {
00341   *minX = self->boundMinX ;
00342   *minY = self->boundMinY ;
00343   *maxX = self->boundMaxX ;
00344   *maxY = self->boundMaxY ;
00345 }
00346 
00353 int
00354 vl_dsift_get_flat_window (VlDsiftFilter const* self)
00355 {
00356   return self->useFlatWindow ;
00357 }
00358 
00366 void
00367 vl_dsift_get_steps (VlDsiftFilter const* self,
00368                    int* stepX,
00369                    int* stepY)
00370 {
00371   *stepX = self->stepX ;
00372   *stepY = self->stepY ;
00373 }
00374 
00382 void
00383 vl_dsift_set_steps (VlDsiftFilter* self,
00384                    int stepX,
00385                    int stepY)
00386 {
00387   self->stepX = stepX ;
00388   self->stepY = stepY ;
00389   _vl_dsift_update_buffers(self) ;
00390 }
00391 
00401 void
00402 vl_dsift_set_bounds (VlDsiftFilter* self,
00403                     int minX, int minY, int maxX, int maxY)
00404 {
00405   self->boundMinX = minX ;
00406   self->boundMinY = minY ;
00407   self->boundMaxX = maxX ;
00408   self->boundMaxY = maxY ;
00409   _vl_dsift_update_buffers(self) ;
00410 }
00411 
00418 void
00419 vl_dsift_set_geometry (VlDsiftFilter *self,
00420                        VlDsiftDescriptorGeometry const *geom)
00421 {
00422   self->geom = *geom ;
00423   _vl_dsift_update_buffers(self) ;
00424 }
00425 
00432 void
00433 vl_dsift_set_flat_window (VlDsiftFilter* self,
00434                          vl_bool useFlatWindow)
00435 {
00436   self->useFlatWindow = useFlatWindow ;
00437 }
00438 
00454 VL_INLINE void
00455 vl_dsift_transpose_descriptor (float* dst,
00456                               float const* src,
00457                               int numBinT,
00458                               int numBinX,
00459                               int numBinY)
00460 {
00461   int t, x, y ;
00462 
00463   for (y = 0 ; y < numBinY ; ++y) {
00464     for (x = 0 ; x < numBinX ; ++x) {
00465       int offset  = numBinT * (x + y * numBinX) ;
00466       int offsetT = numBinT * (y + x * numBinY) ;
00467 
00468       for (t = 0 ; t < numBinT ; ++t) {
00469         int tT = numBinT / 4 - t ;
00470         dst [offsetT + (tT + numBinT) % numBinT] = src [offset + t] ;
00471       }
00472     }
00473   }
00474 }
00475 
00482 void
00483 vl_dsift_set_window_size(VlDsiftFilter * self, double windowSize)
00484 {
00485   assert(windowSize >= 0.0) ;
00486   self->windowSize = windowSize ;
00487 }
00488 
00495 VL_INLINE double
00496 vl_dsift_get_window_size(VlDsiftFilter const * self)
00497 {
00498   return self->windowSize ;
00499 }
00500 
00501 /*  VL_DSIFT_H */
00502 #endif


iri_sift
Author(s): dmartinez
autogenerated on Fri Dec 6 2013 22:44:31