#include "sift.h"
#include "imopv.h"
#include "mathop.h"
#include <assert.h>
#include <stdlib.h>
#include <string.h>
#include <math.h>
#include <stdio.h>
Go to the source code of this file.
Defines | |
#define | Aat(i, j) (A[(i)+(j)*3]) |
#define | at(dx, dy, ds) (*( pt + (dx)*xo + (dy)*yo + (ds)*so)) |
#define | at(dx, dy) (*(pt + xo * (dx) + yo * (dy))) |
#define | atd(dbinx, dbiny, dbint) *(dpt + (dbint)*binto + (dbiny)*binyo + (dbinx)*binxo) |
#define | atd(dbinx, dbiny, dbint) *(dpt + (dbint)*binto + (dbiny)*binyo + (dbinx)*binxo) |
#define | CHECK_NEIGHBORS(CMP, SGN) |
#define | EXPN_MAX 25.0 |
#define | EXPN_SZ 256 |
#define | log2(x) (log(x)/VL_LOG_OF_2) |
#define | NBO 8 |
#define | NBP 4 |
#define | SAVE_BACK |
#define | VL_SIFT_BILINEAR_ORIENTATIONS 1 |
Functions | |
static void | _vl_sift_smooth (VlSiftFilt *self, vl_sift_pix *outputImage, vl_sift_pix *tempImage, vl_sift_pix const *inputImage, vl_size width, vl_size height, double sigma) |
static void | copy_and_downsample (vl_sift_pix *dst, vl_sift_pix const *src, int width, int height, int d) |
static void | copy_and_upsample_rows (vl_sift_pix *dst, vl_sift_pix const *src, int width, int height) |
VL_INLINE double | fast_expn (double x) |
VL_INLINE void | fast_expn_init () |
VL_INLINE vl_sift_pix | normalize_histogram (vl_sift_pix *begin, vl_sift_pix *end) |
static void | update_gradient (VlSiftFilt *f) |
VL_EXPORT void | vl_sift_calc_keypoint_descriptor (VlSiftFilt *f, vl_sift_pix *descr, VlSiftKeypoint const *k, double angle0) |
Compute the descriptor of a keypoint. | |
VL_EXPORT int | vl_sift_calc_keypoint_orientations (VlSiftFilt *f, double angles[4], VlSiftKeypoint const *k) |
Calculate the keypoint orientation(s) | |
VL_EXPORT void | vl_sift_calc_raw_descriptor (VlSiftFilt const *f, vl_sift_pix const *grad, vl_sift_pix *descr, int width, int height, double x, double y, double sigma, double angle0) |
Run the SIFT descriptor on raw data. | |
VL_EXPORT void | vl_sift_delete (VlSiftFilt *f) |
Delete SIFT filter. | |
VL_EXPORT void | vl_sift_detect (VlSiftFilt *f) |
Detect keypoints. | |
VL_EXPORT void | vl_sift_keypoint_init (VlSiftFilt const *f, VlSiftKeypoint *k, double x, double y, double sigma) |
Initialize a keypoint from its position and scale. | |
VL_EXPORT VlSiftFilt * | vl_sift_new (int width, int height, int noctaves, int nlevels, int o_min) |
Create a new SIFT filter. | |
VL_EXPORT int | vl_sift_process_first_octave (VlSiftFilt *f, vl_sift_pix const *im) |
Start processing a new image. | |
VL_EXPORT int | vl_sift_process_next_octave (VlSiftFilt *f) |
Process next octave. | |
Variables | |
double | expn_tab [EXPN_SZ+1] |
#define Aat | ( | i, | |
j | |||
) | (A[(i)+(j)*3]) |
#define at | ( | dx, | |
dy, | |||
ds | |||
) | (*( pt + (dx)*xo + (dy)*yo + (ds)*so)) |
#define at | ( | dx, | |
dy | |||
) | (*(pt + xo * (dx) + yo * (dy))) |
#define atd | ( | dbinx, | |
dbiny, | |||
dbint | |||
) | *(dpt + (dbint)*binto + (dbiny)*binyo + (dbinx)*binxo) |
#define atd | ( | dbinx, | |
dbiny, | |||
dbint | |||
) | *(dpt + (dbint)*binto + (dbiny)*binyo + (dbinx)*binxo) |
#define CHECK_NEIGHBORS | ( | CMP, | |
SGN | |||
) |
( v CMP ## = SGN 0.8 * tp && \ v CMP *(pt + xo) && \ v CMP *(pt - xo) && \ v CMP *(pt + so) && \ v CMP *(pt - so) && \ v CMP *(pt + yo) && \ v CMP *(pt - yo) && \ \ v CMP *(pt + yo + xo) && \ v CMP *(pt + yo - xo) && \ v CMP *(pt - yo + xo) && \ v CMP *(pt - yo - xo) && \ \ v CMP *(pt + xo + so) && \ v CMP *(pt - xo + so) && \ v CMP *(pt + yo + so) && \ v CMP *(pt - yo + so) && \ v CMP *(pt + yo + xo + so) && \ v CMP *(pt + yo - xo + so) && \ v CMP *(pt - yo + xo + so) && \ v CMP *(pt - yo - xo + so) && \ \ v CMP *(pt + xo - so) && \ v CMP *(pt - xo - so) && \ v CMP *(pt + yo - so) && \ v CMP *(pt - yo - so) && \ v CMP *(pt + yo + xo - so) && \ v CMP *(pt + yo - xo - so) && \ v CMP *(pt - yo + xo - so) && \ v CMP *(pt - yo - xo - so) )
#define log2 | ( | x | ) | (log(x)/VL_LOG_OF_2) |
#define SAVE_BACK |
*grad++ = vl_fast_sqrt_f (gx*gx + gy*gy) ; \ *grad++ = vl_mod_2pi_f (vl_fast_atan2_f (gy, gx) + 2*VL_PI) ; \ ++src ; \
#define VL_SIFT_BILINEAR_ORIENTATIONS 1 |
static void _vl_sift_smooth | ( | VlSiftFilt * | self, |
vl_sift_pix * | outputImage, | ||
vl_sift_pix * | tempImage, | ||
vl_sift_pix const * | inputImage, | ||
vl_size | width, | ||
vl_size | height, | ||
double | sigma | ||
) | [static] |
static void copy_and_downsample | ( | vl_sift_pix * | dst, |
vl_sift_pix const * | src, | ||
int | width, | ||
int | height, | ||
int | d | ||
) | [static] |
static void copy_and_upsample_rows | ( | vl_sift_pix * | dst, |
vl_sift_pix const * | src, | ||
int | width, | ||
int | height | ||
) | [static] |
VL_INLINE double fast_expn | ( | double | x | ) |
VL_INLINE void fast_expn_init | ( | ) |
VL_INLINE vl_sift_pix normalize_histogram | ( | vl_sift_pix * | begin, |
vl_sift_pix * | end | ||
) |
static void update_gradient | ( | VlSiftFilt * | f | ) | [static] |
VL_EXPORT void vl_sift_calc_keypoint_descriptor | ( | VlSiftFilt * | f, |
vl_sift_pix * | descr, | ||
VlSiftKeypoint const * | k, | ||
double | angle0 | ||
) |
Compute the descriptor of a keypoint.
------------------------------------------------------------------
f | SIFT filter. |
descr | SIFT descriptor (output) |
k | keypoint. |
angle0 | keypoint direction. |
The function computes the SIFT descriptor of the keypoint k of orientation angle0. The function fills the buffer descr which must be large enough to hold the descriptor.
The function assumes that the keypoint is on the current octave. If not, it does not do anything.
VL_EXPORT int vl_sift_calc_keypoint_orientations | ( | VlSiftFilt * | f, |
double | angles[4], | ||
VlSiftKeypoint const * | k | ||
) |
Calculate the keypoint orientation(s)
------------------------------------------------------------------
f | SIFT filter. |
angles | orientations (output). |
k | keypoint. |
The function computes the orientation(s) of the keypoint k. The function returns the number of orientations found (up to four). The orientations themselves are written to the vector angles.
k->s
to be in the range s_min+1
and s_max-2
(where usually s_min=0
and s_max=S+2
). If this is not the case, the function returns zero orientations.VL_EXPORT void vl_sift_calc_raw_descriptor | ( | VlSiftFilt const * | f, |
vl_sift_pix const * | grad, | ||
vl_sift_pix * | descr, | ||
int | width, | ||
int | height, | ||
double | x, | ||
double | y, | ||
double | sigma, | ||
double | angle0 | ||
) |
Run the SIFT descriptor on raw data.
------------------------------------------------------------------
f | SIFT filter. |
grad | image gradients. |
descr | SIFT descriptor (output). |
width | image width. |
height | image height. |
x | keypoint x coordinate. |
y | keypoint y coordinate. |
sigma | keypoint scale. |
angle0 | keypoint orientation. |
The function runs the SIFT descriptor on raw data. Here image is a 2 x width x height array (by convention, the memory layout is a s such the first index is the fastest varying one). The first width x height layer of the array contains the gradient magnitude and the second the gradient angle (in radians, between 0 and ). x, y and sigma give the keypoint center and scale respectively.
In order to be equivalent to a standard SIFT descriptor the image gradient must be computed at a smoothing level equal to the scale of the keypoint. In practice, the actual SIFT algorithm makes the following additional approximation, which influence the result:
S
levels.VL_EXPORT void vl_sift_delete | ( | VlSiftFilt * | f | ) |
Delete SIFT filter.
-------------------------------------------------------------------
f | SIFT filter to delete. |
The function frees the resources allocated by vl_sift_new().
VL_EXPORT void vl_sift_detect | ( | VlSiftFilt * | f | ) |
Detect keypoints.
------------------------------------------------------------------ The function detect keypoints in the current octave filling the internal keypoint buffer. Keypoints can be retrieved by vl_sift_get_keypoints().
f | SIFT filter. |
Index GSS
Index matrix A
VL_EXPORT void vl_sift_keypoint_init | ( | VlSiftFilt const * | f, |
VlSiftKeypoint * | k, | ||
double | x, | ||
double | y, | ||
double | sigma | ||
) |
Initialize a keypoint from its position and scale.
------------------------------------------------------------------
f | SIFT filter. |
k | SIFT keypoint (output). |
x | x coordinate of the keypoint center. |
y | y coordinate of the keypoint center. |
sigma | keypoint scale. |
The function initializes a keypoint structure k from the location x and y and the scale sigma of the keypoint. The keypoint structure maps the keypoint to an octave and scale level of the discretized Gaussian scale space, which is required for instance to compute the keypoint SIFT descriptor.
The formula linking the keypoint scale sigma to the octave and scale indexes is
In addition to the scale index s (which can be fractional due to scale interpolation) a keypoint has an integer scale index is too (which is the index of the scale level where it was detected in the DoG scale space). We have the constraints (Detector see also the "SIFT detector"):
Thus octave o represents scales . Note that some scales may be represented more than once. For each scale, we select the largest possible octave that contains it, i.e.
and then
In practice, both and are clamped to their feasible range as determined by the SIFT filter parameters.
VL_EXPORT VlSiftFilt* vl_sift_new | ( | int | width, |
int | height, | ||
int | noctaves, | ||
int | nlevels, | ||
int | o_min | ||
) |
Create a new SIFT filter.
------------------------------------------------------------------
width | image width. |
height | image height. |
noctaves | number of octaves. |
nlevels | number of levels per octave. |
o_min | first octave index. |
The function allocates and returns a new SIFT filter for the specified image and scale space geometry.
Setting O to a negative value sets the number of octaves to the maximum possible value depending on the size of the image.
VL_EXPORT int vl_sift_process_first_octave | ( | VlSiftFilt * | f, |
vl_sift_pix const * | im | ||
) |
Start processing a new image.
------------------------------------------------------------------
f | SIFT filter. |
im | image data. |
The function starts processing a new image by computing its Gaussian scale space at the lower octave. It also empties the internal keypoint buffer.
VL_EXPORT int vl_sift_process_next_octave | ( | VlSiftFilt * | f | ) |
Process next octave.
------------------------------------------------------------------
f | SIFT filter. |
The function computes the next octave of the Gaussian scale space. Notice that this clears the record of any feature detected in the previous octave.