Classes | Defines | Typedefs | Functions
dsift.h File Reference

Dense SIFT (Dense Scale Invariant Feature Transform (DSIFT)) More...

#include <emmintrin.h>
#include <assert.h>
Include dependency graph for dsift.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  VlDsiftDescriptorGeometry_
 Dense SIFT descriptor geometry. More...
struct  VlDsiftFilter_
 Dense SIFT filter. More...
struct  VlDsiftKeypoint_
 DSIFT H. More...

Defines

#define VADD   _mm_add_ps
#define VALIGNED(x)   (! (((vl_uintptr)(x)) & 0xF))
#define VL_EPSILON_F   1.19209290E-07F
#define VL_EXPORT   extern "C"
#define VL_FALSE   0
 false (0) constant
#define VL_INLINE   static __inline__
#define VL_MAX(x, y)   (((x)>(y))?(x):(y))
#define VL_MIN(x, y)   (((x)<(y))?(x):(y))
#define VL_PAD_BY_CONTINUITY   (0x1 << 0)
 Pad by continuity.
#define VL_PAD_BY_ZERO   (0x0 << 0)
 Pad with zeroes.
#define VL_PAD_MASK   (0x3)
 Padding field selector.
#define VL_PI   3.141592653589793
#define VL_TRANSPOSE   (0x1 << 2)
 Transpose result.
#define VL_TRUE   1
 true (1) constant
#define VLD1   _mm_load1_ps
#define VMUL   _mm_mul_ps
#define VSFX   s
#define VSIZE   4
#define VSTZ   _mm_setzero_ps
#define VTYPE   __m128

Typedefs

typedef int vl_bool
 Boolean.
typedef vl_int64 vl_index
 Signed version of vl_size and ::vl_uindex.
typedef int vl_int32
 Signed 32-bit integer.
typedef long long vl_int64
 Signed 64-bit integer.
typedef vl_uint64 vl_size
 Unsigned integer holding the size of a memory block.
typedef long long unsigned vl_uint64
 Unsigned 64-bit integer.
typedef vl_uint64 vl_uintptr
 Unsigned integer holding a pointer.

Functions

void _vl_dsift_update_buffers (VlDsiftFilter *self)
Setting parameters
VL_INLINE void vl_dsift_set_steps (VlDsiftFilter *self, int stepX, int stepY)
 Set steps.
VL_INLINE void vl_dsift_set_bounds (VlDsiftFilter *self, int minX, int minY, int maxX, int maxY)
 Set bounds.
VL_INLINE void vl_dsift_set_geometry (VlDsiftFilter *self, VlDsiftDescriptorGeometry const *geom)
 Set SIFT descriptor geometry.
VL_INLINE void vl_dsift_set_flat_window (VlDsiftFilter *self, vl_bool useFlatWindow)
 Set flat window flag.
VL_INLINE void vl_dsift_set_window_size (VlDsiftFilter *self, double windowSize)
 Set SIFT descriptor Gaussian window size.
Retrieving data and parameters
VL_INLINE float const * vl_dsift_get_descriptors (VlDsiftFilter const *self)
 Get descriptors.
VL_INLINE int vl_dsift_get_descriptor_size (VlDsiftFilter const *self)
 Get descriptor size.
VL_INLINE int vl_dsift_get_keypoint_num (VlDsiftFilter const *self)
 Get number of keypoints.
VL_INLINE VlDsiftKeypoint const * vl_dsift_get_keypoints (VlDsiftFilter const *self)
 Get keypoints.
VL_INLINE void vl_dsift_get_bounds (VlDsiftFilter const *self, int *minX, int *minY, int *maxX, int *maxY)
 Get bounds.
VL_INLINE void vl_dsift_get_steps (VlDsiftFilter const *self, int *stepX, int *stepY)
 Get steps.
VL_INLINE
VlDsiftDescriptorGeometry
const * 
vl_dsift_get_geometry (VlDsiftFilter const *self)
 Get SIFT descriptor geometry.
VL_INLINE vl_bool vl_dsift_get_flat_window (VlDsiftFilter const *self)
 Get flat window flag.
VL_INLINE double vl_dsift_get_window_size (VlDsiftFilter const *self)
 Get SIFT descriptor Gaussian window size.

Image convolution

typedef struct VlDsiftKeypoint_ VlDsiftKeypoint
 DSIFT H.
typedef struct
VlDsiftDescriptorGeometry_ 
VlDsiftDescriptorGeometry
 Dense SIFT descriptor geometry.
typedef struct VlDsiftFilter_ VlDsiftFilter
 Dense SIFT filter.
void vl_imconvcol_vf (float *dst, int dst_stride, float const *src, int src_width, int src_height, int src_stride, float const *filt, int filt_begin, int filt_end, int step, unsigned int flags)
void vl_imconvcoltri_f (float *dest, vl_size destStride, float const *image, vl_size imageWidth, vl_size imageHeight, vl_size imageStride, vl_size filterSize, vl_size step, unsigned int flags)
 convolution triangular kernel
VL_INLINE float vl_abs_f (float x)
VL_INLINE float vl_mod_2pi_f (float x)
VL_INLINE long int vl_floor_f (float x)
VL_INLINE float vl_fast_resqrt_f (float x)
VL_INLINE float vl_fast_sqrt_f (float x)
VL_INLINE float vl_fast_atan2_f (float y, float x)
VlDsiftFiltervl_dsift_new (int width, int height)
 Create a new DSIFT filter.
VlDsiftFiltervl_dsift_new_basic (int width, int height, int step, int binSize)
 Create a new DSIFT filter (basic interface)
void vl_dsift_delete (VlDsiftFilter *self)
 Delete DSIFT filter.
void vl_dsift_process (VlDsiftFilter *self, float const *im)
 Compute keypoints and descriptors.
VL_INLINE void vl_dsift_transpose_descriptor (float *dst, float const *src, int numBinT, int numBinX, int numBinY)
 Transpose descriptor.

Detailed Description

Dense SIFT (Dense Scale Invariant Feature Transform (DSIFT))

Author:
Andrea Vedaldi
Brian Fulkerson

Definition in file dsift.h.


Define Documentation

#define VADD   _mm_add_ps

Definition at line 45 of file dsift.h.

#define VALIGNED (   x)    (! (((vl_uintptr)(x)) & 0xF))

Definition at line 38 of file dsift.h.

#define VL_EPSILON_F   1.19209290E-07F

Definition at line 25 of file dsift.h.

#define VL_EXPORT   extern "C"

Definition at line 24 of file dsift.h.

#define VL_FALSE   0

false (0) constant

Definition at line 30 of file dsift.h.

#define VL_INLINE   static __inline__

Definition at line 23 of file dsift.h.

#define VL_MAX (   x,
  y 
)    (((x)>(y))?(x):(y))

Definition at line 41 of file dsift.h.

#define VL_MIN (   x,
  y 
)    (((x)<(y))?(x):(y))

Definition at line 42 of file dsift.h.

#define VL_PAD_BY_CONTINUITY   (0x1 << 0)

Pad by continuity.

Definition at line 32 of file dsift.h.

#define VL_PAD_BY_ZERO   (0x0 << 0)

Pad with zeroes.

Definition at line 33 of file dsift.h.

#define VL_PAD_MASK   (0x3)

Padding field selector.

Definition at line 34 of file dsift.h.

#define VL_PI   3.141592653589793

Definition at line 40 of file dsift.h.

#define VL_TRANSPOSE   (0x1 << 2)

Transpose result.

Definition at line 31 of file dsift.h.

#define VL_TRUE   1

true (1) constant

Definition at line 29 of file dsift.h.

#define VLD1   _mm_load1_ps

Definition at line 46 of file dsift.h.

#define VMUL   _mm_mul_ps

Definition at line 47 of file dsift.h.

#define VSFX   s

Definition at line 36 of file dsift.h.

#define VSIZE   4

Definition at line 35 of file dsift.h.

#define VSTZ   _mm_setzero_ps

Definition at line 44 of file dsift.h.

#define VTYPE   __m128

Definition at line 37 of file dsift.h.


Typedef Documentation

typedef int vl_bool

Boolean.

Definition at line 27 of file dsift.h.

typedef vl_int64 vl_index

Signed version of vl_size and ::vl_uindex.

Definition at line 66 of file dsift.h.

typedef int vl_int32

Signed 32-bit integer.

Definition at line 65 of file dsift.h.

typedef long long vl_int64

Signed 64-bit integer.

Definition at line 61 of file dsift.h.

typedef vl_uint64 vl_size

Unsigned integer holding the size of a memory block.

Definition at line 64 of file dsift.h.

typedef long long unsigned vl_uint64

Unsigned 64-bit integer.

Definition at line 62 of file dsift.h.

Unsigned integer holding a pointer.

Definition at line 63 of file dsift.h.

Dense SIFT descriptor geometry.

typedef struct VlDsiftFilter_ VlDsiftFilter

Dense SIFT filter.

DSIFT H.

Dense SIFT keypoint


Function Documentation

------------------------------------------------------------------

Definition at line 355 of file dsift.c.

VL_INLINE float vl_abs_f ( float  x)

Definition at line 86 of file dsift.h.

void vl_dsift_delete ( VlDsiftFilter self)

Delete DSIFT filter.

------------------------------------------------------------------

Parameters:
selfDSIFT filter.

Definition at line 493 of file dsift.c.

void vl_dsift_get_bounds ( VlDsiftFilter const *  self,
int *  minX,
int *  minY,
int *  maxX,
int *  maxY 
)

Get bounds.

------------------------------------------------------------------

Parameters:
selfDSIFT filter object.
minXbounding box minimum X coordinate.
minYbounding box minimum Y coordinate.
maxXbounding box maximum X coordinate.
maxYbounding box maximum Y coordinate.

Definition at line 338 of file dsift.h.

Get descriptor size.

------------------------------------------------------------------

Parameters:
selfDSIFT filter object.
Returns:
size of a descriptor.

Definition at line 278 of file dsift.h.

float const * vl_dsift_get_descriptors ( VlDsiftFilter const *  self)

Get descriptors.

------------------------------------------------------------------

Parameters:
selfDSIFT filter object.
Returns:
descriptors.

Definition at line 290 of file dsift.h.

int vl_dsift_get_flat_window ( VlDsiftFilter const *  self)

Get flat window flag.

------------------------------------------------------------------

Parameters:
selfDSIFT filter object.
Returns:
TRUE if the DSIFT filter uses a flat window.

Definition at line 354 of file dsift.h.

Get SIFT descriptor geometry.

------------------------------------------------------------------

Parameters:
selfDSIFT filter object.
Returns:
DSIFT descriptor geometry.

Definition at line 323 of file dsift.h.

Get number of keypoints.

------------------------------------------------------------------

Parameters:
selfDSIFT filter object.

Definition at line 312 of file dsift.h.

Get keypoints.

------------------------------------------------------------------

Parameters:
selfDSIFT filter object.

Definition at line 301 of file dsift.h.

void vl_dsift_get_steps ( VlDsiftFilter const *  self,
int *  stepX,
int *  stepY 
)

Get steps.

------------------------------------------------------------------

Parameters:
selfDSIFT filter object.
stepXsampling step along X.
stepYsampling step along Y.

Definition at line 367 of file dsift.h.

Get SIFT descriptor Gaussian window size.

------------------------------------------------------------------

Parameters:
selfDSIFT filter object.
Returns:
window size.

Definition at line 496 of file dsift.h.

VlDsiftFilter* vl_dsift_new ( int  imWidth,
int  imHeight 
)

Create a new DSIFT filter.

------------------------------------------------------------------

Parameters:
imWidthwidth of the image.
imHeightheight of the image
Returns:
new filter.

Definition at line 424 of file dsift.c.

VlDsiftFilter* vl_dsift_new_basic ( int  imWidth,
int  imHeight,
int  step,
int  binSize 
)

Create a new DSIFT filter (basic interface)

------------------------------------------------------------------

Parameters:
imWidthwidth of the image.
imHeightheight of the image.
stepsampling step.
binSizebin size.
Returns:
new filter.

The descriptor geometry matches the standard SIFT descriptor.

Definition at line 476 of file dsift.c.

void vl_dsift_process ( VlDsiftFilter self,
float const *  im 
)

Compute keypoints and descriptors.

------------------------------------------------------------------

Parameters:
selfDSIFT filter.
imimage data.

Definition at line 673 of file dsift.c.

void vl_dsift_set_bounds ( VlDsiftFilter self,
int  minX,
int  minY,
int  maxX,
int  maxY 
)

Set bounds.

------------------------------------------------------------------

Parameters:
selfDSIFT filter object.
minXbounding box minimum X coordinate.
minYbounding box minimum Y coordinate.
maxXbounding box maximum X coordinate.
maxYbounding box maximum Y coordinate.

Definition at line 402 of file dsift.h.

void vl_dsift_set_flat_window ( VlDsiftFilter self,
vl_bool  useFlatWindow 
)

Set flat window flag.

------------------------------------------------------------------

Parameters:
selfDSIFT filter object.
useFlatWindowtrue if the DSIFT filter should use a flat window.

Definition at line 433 of file dsift.h.

void vl_dsift_set_geometry ( VlDsiftFilter self,
VlDsiftDescriptorGeometry const *  geom 
)

Set SIFT descriptor geometry.

------------------------------------------------------------------

Parameters:
selfDSIFT filter object.
geomdescriptor geometry parameters.

Definition at line 419 of file dsift.h.

void vl_dsift_set_steps ( VlDsiftFilter self,
int  stepX,
int  stepY 
)

Set steps.

------------------------------------------------------------------

Parameters:
selfDSIFT filter object.
stepXsampling step along X.
stepYsampling step along Y.

Definition at line 383 of file dsift.h.

void vl_dsift_set_window_size ( VlDsiftFilter self,
double  windowSize 
)

Set SIFT descriptor Gaussian window size.

------------------------------------------------------------------

Parameters:
selfDSIFT filter object.
windowSizewindow size.

Definition at line 483 of file dsift.h.

VL_INLINE void vl_dsift_transpose_descriptor ( float *  dst,
float const *  src,
int  numBinT,
int  numBinX,
int  numBinY 
)

Transpose descriptor.

------------------------------------------------------------------

Parameters:
dstdestination buffer.
srcsource buffer.
numBinT
numBinX
numBinYThe function writes to dst the transpose of the SIFT descriptor src. Let I be an image. The transpose operator satisfies the equation transpose(dsift(I,x,y)) = dsift(transpose(I),y,x)

Definition at line 455 of file dsift.h.

VL_INLINE float vl_fast_atan2_f ( float  y,
float  x 
)

Definition at line 143 of file dsift.h.

VL_INLINE float vl_fast_resqrt_f ( float  x)

Definition at line 113 of file dsift.h.

VL_INLINE float vl_fast_sqrt_f ( float  x)

Definition at line 137 of file dsift.h.

VL_INLINE long int vl_floor_f ( float  x)

Definition at line 105 of file dsift.h.

void vl_imconvcol_vf ( float *  dst,
int  dst_stride,
float const *  src,
int  src_width,
int  src_height,
int  src_stride,
float const *  filt,
int  filt_begin,
int  filt_end,
int  step,
unsigned int  flags 
)

Definition at line 794 of file dsift.c.

void vl_imconvcoltri_f ( float *  dest,
vl_size  destStride,
float const *  image,
vl_size  imageWidth,
vl_size  imageHeight,
vl_size  imageStride,
vl_size  filterSize,
vl_size  step,
unsigned int  flags 
)

convolution triangular kernel

Definition at line 956 of file dsift.c.

VL_INLINE float vl_mod_2pi_f ( float  x)

Definition at line 97 of file dsift.h.



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