Classes | Defines | Typedefs | Functions | Variables
covdet.c File Reference

Covariant feature detectors - Definition. More...

#include "covdet.h"
#include <string.h>
Include dependency graph for covdet.c:

Go to the source code of this file.

Classes

struct  _VlCovDet
 Covariant feature detector. More...
struct  _VlCovDetExtremum2
struct  _VlCovDetExtremum3

Defines

#define Aat(i, j)   (A[(i)+(j)*3])
#define Aat(i, j)   (A[(i)+(j)*2])
#define at(dx, dy, dz)   (*(pt + (dx)*xo + (dy)*yo + (dz)*zo))
#define at(dx, dy)   (*(pt + (dx)*xo + (dy)*yo ))
#define at(x, y)   pt[(x+w)+(y+w)*(2*w+1)]
#define CHECK_NEIGHBORS_2(v, CMP, SGN)
#define CHECK_NEIGHBORS_3(v, CMP, SGN)
#define VL_COVDET_AA_ACCURATE_SMOOTHING   VL_FALSE
#define VL_COVDET_AA_CONVERGENCE_THRESHOLD   1.001
#define VL_COVDET_AA_MAX_ANISOTROPY   5
#define VL_COVDET_AA_MAX_NUM_ITERATIONS   15
#define VL_COVDET_AA_PATCH_EXTENT   (3*VL_COVDET_AA_RELATIVE_INTEGRATION_SIGMA)
#define VL_COVDET_AA_PATCH_RESOLUTION   20
#define VL_COVDET_AA_RELATIVE_DERIVATIVE_SIGMA   1
#define VL_COVDET_AA_RELATIVE_INTEGRATION_SIGMA   3
#define VL_COVDET_DOG_DEF_EDGE_THRESHOLD   10.0
#define VL_COVDET_DOG_DEF_PEAK_THRESHOLD   VL_COVDET_LAP_DEF_PEAK_THRESHOLD
#define VL_COVDET_HARRIS_DEF_EDGE_THRESHOLD   10.0
#define VL_COVDET_HARRIS_DEF_PEAK_THRESHOLD   0.000002
#define VL_COVDET_HESSIAN_DEF_EDGE_THRESHOLD   10.0
#define VL_COVDET_HESSIAN_DEF_PEAK_THRESHOLD   0.003
#define VL_COVDET_LAP_DEF_PEAK_THRESHOLD   0.01
#define VL_COVDET_LAP_NUM_LEVELS   10
#define VL_COVDET_LAP_PATCH_RESOLUTION   16
#define VL_COVDET_MAX_NUM_LAPLACIAN_SCALES   4
#define VL_COVDET_MAX_NUM_ORIENTATIONS   4
#define VL_COVDET_OR_ADDITIONAL_PEAKS_RELATIVE_SIZE   0.8
#define VL_COVDET_OR_NUM_ORIENTATION_HISTOGAM_BINS   36

Typedefs

typedef struct _VlCovDetExtremum2 VlCovDetExtremum2
typedef struct _VlCovDetExtremum3 VlCovDetExtremum3

Functions

vl_bool _vl_covdet_check_frame_inside (VlCovDet *self, VlFrameOrientedEllipse frame, double margin)
static int _vl_covdet_compare_orientations_descending (void const *a_, void const *b_)
static void _vl_det_hessian_response (float *hessian, float const *image, vl_size width, vl_size height, double step, double sigma)
 Scaled derminant of the Hessian filter.
static void _vl_dog_response (float *dog, float const *level1, float const *level2, vl_size width, vl_size height)
 Difference of Gaussian.
static int _vl_enlarge_buffer (void **buffer, vl_size *bufferSize, vl_size targetSize)
 Enlarge buffer.
static void _vl_harris_response (float *harris, float const *image, vl_size width, vl_size height, double step, double sigma, double sigmaI, double alpha)
 Scale-normalised Harris response.
static int _vl_resize_buffer (void **buffer, vl_size *bufferSize, vl_size targetSize)
 Reallocate buffer.
int vl_covdet_append_feature (VlCovDet *self, VlCovDetFeature const *feature)
 Append a feature to the internal buffer.
void vl_covdet_delete (VlCovDet *self)
 Delete object instance.
void vl_covdet_detect (VlCovDet *self)
 Detect scale-space features.
void vl_covdet_drop_features_outside (VlCovDet *self, double margin)
 Drop features (partially) outside the image.
void vl_covdet_extract_affine_shape (VlCovDet *self)
 Extract the affine shape for the stored features.
int vl_covdet_extract_affine_shape_for_frame (VlCovDet *self, VlFrameOrientedEllipse *adapted, VlFrameOrientedEllipse frame)
 Extract the affine shape for a feature frame.
void vl_covdet_extract_laplacian_scales (VlCovDet *self)
 Extract the Laplacian scales for the stored features.
VlCovDetFeatureLaplacianScalevl_covdet_extract_laplacian_scales_for_frame (VlCovDet *self, vl_size *numScales, VlFrameOrientedEllipse frame)
 Extract the Laplacian scale(s) for a feature frame.
void vl_covdet_extract_orientations (VlCovDet *self)
 Extract the orientation(s) for the stored features.
VlCovDetFeatureOrientationvl_covdet_extract_orientations_for_frame (VlCovDet *self, vl_size *numOrientations, VlFrameOrientedEllipse frame)
 Extract the orientation(s) for a feature.
vl_bool vl_covdet_extract_patch_for_frame (VlCovDet *self, float *patch, vl_size resolution, double extent, double sigma, VlFrameOrientedEllipse frame)
 Helper for extracting patches.
vl_bool vl_covdet_extract_patch_helper (VlCovDet *self, double *sigma1, double *sigma2, float *patch, vl_size resolution, double extent, double sigma, double A_[4], double T_[2], double d1, double d2)
vl_bool vl_covdet_get_aa_accurate_smoothing (VlCovDet const *self)
 Get whether affine adaptation uses accurate smoothing.
VlScaleSpacevl_covdet_get_css (VlCovDet const *self)
 Get the cornerness measure scale space.
double vl_covdet_get_edge_threshold (VlCovDet const *self)
 Get the edge threshold.
voidvl_covdet_get_features (VlCovDet *self)
 Get the stored frames.
vl_index vl_covdet_get_first_octave (VlCovDet const *self)
 Get the index of the first octave.
VlScaleSpacevl_covdet_get_gss (VlCovDet const *self)
 Get the Gaussian scale space.
double vl_covdet_get_laplacian_peak_threshold (VlCovDet const *self)
 Get the Laplacian peak threshold.
vl_size const * vl_covdet_get_laplacian_scales_statistics (VlCovDet const *self, vl_size *numScales)
 Get the number of features found with a certain number of scales.
double vl_covdet_get_non_extrema_suppression_threshold (VlCovDet const *self)
 Get the non-extrema suppression threshold.
vl_size vl_covdet_get_num_features (VlCovDet const *self)
 Get number of stored frames.
vl_size vl_covdet_get_num_non_extrema_suppressed (VlCovDet const *self)
 Get the number of non-extrema suppressed.
vl_size vl_covdet_get_octave_resolution (VlCovDet const *self)
 Get the octave resolution.
double vl_covdet_get_peak_threshold (VlCovDet const *self)
 Get the peak threshold.
vl_bool vl_covdet_get_transposed (VlCovDet const *self)
 Get wether images are passed in transposed.
VlCovDetvl_covdet_new (VlCovDetMethod method)
 Create a new object instance.
int vl_covdet_put_image (VlCovDet *self, float const *image, vl_size width, vl_size height)
 Detect features in an image.
void vl_covdet_reset (VlCovDet *self)
 Reset object.
void vl_covdet_set_aa_accurate_smoothing (VlCovDet *self, vl_bool x)
 Set whether affine adaptation uses accurate smoothing.
void vl_covdet_set_edge_threshold (VlCovDet *self, double edgeThreshold)
 Set the edge threshold.
void vl_covdet_set_first_octave (VlCovDet *self, vl_index o)
 Set the index of the first octave.
void vl_covdet_set_laplacian_peak_threshold (VlCovDet *self, double peakThreshold)
 Set the Laplacian peak threshold.
void vl_covdet_set_non_extrema_suppression_threshold (VlCovDet *self, double x)
 Set the non-extrema suppression threshod.
void vl_covdet_set_octave_resolution (VlCovDet *self, vl_size r)
 Set the octave resolutuon.
void vl_covdet_set_peak_threshold (VlCovDet *self, double peakThreshold)
 Set the peak threshold.
void vl_covdet_set_transposed (VlCovDet *self, vl_bool t)
 Set the index of the first octave.
VL_EXPORT vl_size vl_find_local_extrema_2 (vl_index **extrema, vl_size *bufferSize, float const *map, vl_size width, vl_size height, double threshold)
VL_EXPORT vl_size vl_find_local_extrema_3 (vl_index **extrema, vl_size *bufferSize, float const *map, vl_size width, vl_size height, vl_size depth, double threshold)
VL_EXPORT vl_bool vl_refine_local_extreum_2 (VlCovDetExtremum2 *refined, float const *map, vl_size width, vl_size height, vl_index x, vl_index y)
VL_EXPORT vl_bool vl_refine_local_extreum_3 (VlCovDetExtremum3 *refined, float const *map, vl_size width, vl_size height, vl_size depth, vl_index x, vl_index y, vl_index z)

Variables

VlEnumerator vlCovdetMethods [VL_COVDET_METHOD_NUM]

Detailed Description

Covariant feature detectors - Definition.

Author:
Karel Lenc
Andrea Vedaldi
Michal Perdoch

Definition in file covdet.c.


Define Documentation

#define Aat (   i,
 
)    (A[(i)+(j)*3])
#define Aat (   i,
 
)    (A[(i)+(j)*2])
#define at (   dx,
  dy,
  dz 
)    (*(pt + (dx)*xo + (dy)*yo + (dz)*zo))
#define at (   dx,
  dy 
)    (*(pt + (dx)*xo + (dy)*yo ))
#define at (   x,
 
)    pt[(x+w)+(y+w)*(2*w+1)]
#define CHECK_NEIGHBORS_2 (   v,
  CMP,
  SGN 
)
Value:
(\
v CMP ## = SGN threshold &&               \
v CMP *(pt + xo) &&                       \
v CMP *(pt - xo) &&                       \
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) )
#define CHECK_NEIGHBORS_3 (   v,
  CMP,
  SGN 
)

Definition at line 1441 of file covdet.c.

Definition at line 1440 of file covdet.c.

Definition at line 1439 of file covdet.c.

Definition at line 1435 of file covdet.c.

Definition at line 1442 of file covdet.c.

Definition at line 1434 of file covdet.c.

Definition at line 1438 of file covdet.c.

Definition at line 1437 of file covdet.c.

Definition at line 1448 of file covdet.c.

Definition at line 1447 of file covdet.c.

Definition at line 1450 of file covdet.c.

#define VL_COVDET_HARRIS_DEF_PEAK_THRESHOLD   0.000002

Definition at line 1449 of file covdet.c.

Definition at line 1452 of file covdet.c.

Definition at line 1451 of file covdet.c.

Definition at line 1446 of file covdet.c.

#define VL_COVDET_LAP_NUM_LEVELS   10

Definition at line 1444 of file covdet.c.

Definition at line 1445 of file covdet.c.

Definition at line 1433 of file covdet.c.

Definition at line 1432 of file covdet.c.

Definition at line 1443 of file covdet.c.

Definition at line 1436 of file covdet.c.


Typedef Documentation


Function Documentation

vl_bool _vl_covdet_check_frame_inside ( VlCovDet self,
VlFrameOrientedEllipse  frame,
double  margin 
)

Definition at line 3064 of file covdet.c.

static int _vl_covdet_compare_orientations_descending ( void const *  a_,
void const *  b_ 
) [static]

Definition at line 2667 of file covdet.c.

static void _vl_det_hessian_response ( float *  hessian,
float const *  image,
vl_size  width,
vl_size  height,
double  step,
double  sigma 
) [static]

Scaled derminant of the Hessian filter.

Parameters:
hessianoutput image.
imageinput image.
widthimage width.
heightimage height.
stepimage sampling step (pixel size).
sigmaGaussian smoothing of the input image.

Definition at line 1746 of file covdet.c.

static void _vl_dog_response ( float *  dog,
float const *  level1,
float const *  level2,
vl_size  width,
vl_size  height 
) [static]

Difference of Gaussian.

Parameters:
dogoutput image.
level1input image at the smaller Gaussian scale.
level2input image at the larger Gaussian scale.
widthimage width.
heightimage height.

Definition at line 1898 of file covdet.c.

static int _vl_enlarge_buffer ( void **  buffer,
vl_size bufferSize,
vl_size  targetSize 
) [static]

Enlarge buffer.

Parameters:
buffer
bufferSize
targetSize
Returns:
error code

Definition at line 986 of file covdet.c.

static void _vl_harris_response ( float *  harris,
float const *  image,
vl_size  width,
vl_size  height,
double  step,
double  sigma,
double  sigmaI,
double  alpha 
) [static]

Scale-normalised Harris response.

Parameters:
harrisoutput image.
imageinput image.
widthimage width.
heightimage height.
stepimage sampling step (pixel size).
sigmaGaussian smoothing of the input image.
sigmaIintegration scale.
alphafactor in the definition of the Harris score.

Definition at line 1837 of file covdet.c.

static int _vl_resize_buffer ( void **  buffer,
vl_size bufferSize,
vl_size  targetSize 
) [static]

Reallocate buffer.

Parameters:
buffer
bufferSize
targetSize
Returns:
error code

Definition at line 956 of file covdet.c.

int vl_covdet_append_feature ( VlCovDet self,
VlCovDetFeature const *  feature 
)

Append a feature to the internal buffer.

Parameters:
selfobject.
featurea pointer to the feature to append.
Returns:
status.

The feature is copied. The function may fail with status equal to VL_ERR_ALLOC if there is insufficient memory.

Definition at line 1648 of file covdet.c.

Delete object instance.

Parameters:
selfobject.

Definition at line 1631 of file covdet.c.

Detect scale-space features.

Parameters:
selfobject.

This function runs the configured feature detector on the image that was passed by using vl_covdet_put_image.

Definition at line 1921 of file covdet.c.

void vl_covdet_drop_features_outside ( VlCovDet self,
double  margin 
)

Drop features (partially) outside the image.

Parameters:
selfobject.
margingeometric marging.

The feature extent is defined by maring. A bounding box in the normalised feature frame containin a circle of radius maring is created and mapped to the image by the feature frame transformation. Then the feature is dropped if the bounding box is not contained in the image.

For example, setting margin to zero drops a feature only if its center is not contained.

Typically a valua of margin equal to 1 or 2 is used.

Definition at line 3108 of file covdet.c.

Extract the affine shape for the stored features.

Parameters:
selfobject.

This function may discard features for which no affine shape can reliably be detected.

Definition at line 2644 of file covdet.c.

Extract the affine shape for a feature frame.

Parameters:
selfobject.
adaptedthe shape-adapted frame.
framethe input frame.
Returns:
VL_ERR_OK if affine adaptation is successful.

This function may fail if adaptation is unsuccessful or if memory is insufficient.

Definition at line 2455 of file covdet.c.

Extract the Laplacian scales for the stored features.

Parameters:
selfobject.

Note that, since more than one orientation can be detected for each feature, this function may create copies of them, one for each orientation.

Definition at line 3009 of file covdet.c.

Extract the Laplacian scale(s) for a feature frame.

Parameters:
selfobject.
numScalesthe number of detected scales.
framepose of the feature.
Returns:
an array of detected scales.

The function returns NULL if memory is insufficient.

Definition at line 2900 of file covdet.c.

Extract the orientation(s) for the stored features.

Parameters:
selfobject.

Note that, since more than one orientation can be detected for each feature, this function may create copies of them, one for each orientation.

Definition at line 2850 of file covdet.c.

Extract the orientation(s) for a feature.

Parameters:
selfobject.
numOrientationsthe number of detected orientations.
framepose of the feature.
Returns:
an array of detected orientations with their scores.

The returned array is a matrix of size $ 2 \times n $ where n is the number of detected orientations.

The function returns NULL if memory is insufficient.

Definition at line 2690 of file covdet.c.

vl_bool vl_covdet_extract_patch_for_frame ( VlCovDet self,
float *  patch,
vl_size  resolution,
double  extent,
double  sigma,
VlFrameOrientedEllipse  frame 
)

Helper for extracting patches.

Parameters:
selfobject.
patchbuffer.
resolutionpatch resolution.
extentpatch extent.
sigmadesired smoothing in the patch frame.
framefeature frame.

The function considers a patch of extent [-extent,extent] on each side, with a side counting 2*resolution+1 pixels. In attempts to extract from the scale space a patch based on the affine warping specified by frame in such a way that the resulting smoothing of the image is sigma (in the patch frame).

The transformation is specified by the matrices A and T embedded in the feature frame. Note that this transformation maps pixels from the patch frame to the image frame.

Definition at line 2423 of file covdet.c.

vl_bool vl_covdet_extract_patch_helper ( VlCovDet self,
double *  sigma1,
double *  sigma2,
float *  patch,
vl_size  resolution,
double  extent,
double  sigma,
double  A_[4],
double  T_[2],
double  d1,
double  d2 
)

Definition at line 2158 of file covdet.c.

Get whether affine adaptation uses accurate smoothing.

Parameters:
selfobject.
Returns:
true if accurate smoothing is used.

Definition at line 3280 of file covdet.c.

Get the cornerness measure scale space.

Returns:
cornerness measure scale space.

A cornerness measure scale space exists only after calling vl_covdet_detect. Otherwise the function returns NULL.

Definition at line 3371 of file covdet.c.

double vl_covdet_get_edge_threshold ( VlCovDet const *  self)

Get the edge threshold.

Parameters:
selfobject.
Returns:
the edge threshold.

Definition at line 3154 of file covdet.c.

Get the stored frames.

Returns:
frames stored in the detector.

Definition at line 3345 of file covdet.c.

Get the index of the first octave.

Parameters:
selfobject.
Returns:
index of the first octave.

Definition at line 3229 of file covdet.c.

Get the Gaussian scale space.

Returns:
Gaussian scale space.

A Gaussian scale space exists only after calling vl_covdet_put_image. Otherwise the function returns NULL.

Definition at line 3358 of file covdet.c.

Get the Laplacian peak threshold.

Parameters:
selfobject.
Returns:
the Laplacian peak threshold.

This parameter affects only the detecors using the Laplacian scale selectino method such as Harris-Laplace.

Definition at line 3205 of file covdet.c.

vl_size const* vl_covdet_get_laplacian_scales_statistics ( VlCovDet const *  self,
vl_size numScales 
)

Get the number of features found with a certain number of scales.

Parameters:
selfobject.
numScaleslength of the histogram (out).
Returns:
histogram.

Calling this function makes sense only after running a detector that uses the Laplacian as a secondary measure for scale detection

Definition at line 3387 of file covdet.c.

Get the non-extrema suppression threshold.

Parameters:
selfobject.
Returns:
threshold.

Definition at line 3303 of file covdet.c.

Get number of stored frames.

Returns:
number of frames stored in the detector.

Definition at line 3336 of file covdet.c.

Get the number of non-extrema suppressed.

Parameters:
selfobject.
Returns:
number.

Definition at line 3325 of file covdet.c.

Get the octave resolution.

Parameters:
selfobject.
Returns:
octave resolution.

Definition at line 3254 of file covdet.c.

double vl_covdet_get_peak_threshold ( VlCovDet const *  self)

Get the peak threshold.

Parameters:
selfobject.
Returns:
the peak threshold.

Definition at line 3178 of file covdet.c.

Get wether images are passed in transposed.

Parameters:
selfobject.
Returns:
whether images are transposed.

Definition at line 3133 of file covdet.c.

Create a new object instance.

Parameters:
methodmethod for covariant feature detection.
Returns:
new covariant detector.

Definition at line 1507 of file covdet.c.

int vl_covdet_put_image ( VlCovDet self,
float const *  image,
vl_size  width,
vl_size  height 
)

Detect features in an image.

Parameters:
selfobject.
imageimage to process.
widthimage width.
heightimage height.
Returns:
status.

width and height must be at least one pixel. The function fails by returing VL_ERR_ALLOC if the memory is insufficient.

Definition at line 1683 of file covdet.c.

Reset object.

Parameters:
selfobject.

This function removes any buffered features and frees other internal buffers.

Definition at line 1610 of file covdet.c.

Set whether affine adaptation uses accurate smoothing.

Parameters:
selfobject.
xwhether accurate smoothing should be usd.

Definition at line 3291 of file covdet.c.

void vl_covdet_set_edge_threshold ( VlCovDet self,
double  edgeThreshold 
)

Set the edge threshold.

Parameters:
selfobject.
edgeThresholdthe edge threshold.

The edge threshold must be non-negative.

Definition at line 3166 of file covdet.c.

Set the index of the first octave.

Parameters:
selfobject.
oindex of the first octave.

Calling this function resets the detector.

Definition at line 3241 of file covdet.c.

void vl_covdet_set_laplacian_peak_threshold ( VlCovDet self,
double  peakThreshold 
)

Set the Laplacian peak threshold.

Parameters:
selfobject.
peakThresholdthe Laplacian peak threshold.

The peak threshold must be non-negative.

Definition at line 3217 of file covdet.c.

Set the non-extrema suppression threshod.

Parameters:
selfobject.
xthreshold.

Definition at line 3314 of file covdet.c.

Set the octave resolutuon.

Parameters:
selfobject.
roctave resoltuion.

Calling this function resets the detector.

Definition at line 3267 of file covdet.c.

void vl_covdet_set_peak_threshold ( VlCovDet self,
double  peakThreshold 
)

Set the peak threshold.

Parameters:
selfobject.
peakThresholdthe peak threshold.

The peak threshold must be non-negative.

Definition at line 3190 of file covdet.c.

Set the index of the first octave.

Parameters:
selfobject.
twhether images are transposed.

Definition at line 3143 of file covdet.c.

vl_size vl_find_local_extrema_2 ( vl_index **  extrema,
vl_size bufferSize,
float const *  map,
vl_size  width,
vl_size  height,
double  threshold 
)

Definition at line 1147 of file covdet.c.

vl_size vl_find_local_extrema_3 ( vl_index **  extrema,
vl_size bufferSize,
float const *  map,
vl_size  width,
vl_size  height,
vl_size  depth,
double  threshold 
)

Definition at line 1057 of file covdet.c.

VL_EXPORT vl_bool vl_refine_local_extreum_2 ( VlCovDetExtremum2 refined,
float const *  map,
vl_size  width,
vl_size  height,
vl_index  x,
vl_index  y 
)

Definition at line 1332 of file covdet.c.

VL_EXPORT vl_bool vl_refine_local_extreum_3 ( VlCovDetExtremum3 refined,
float const *  map,
vl_size  width,
vl_size  height,
vl_size  depth,
vl_index  x,
vl_index  y,
vl_index  z 
)

Definition at line 1206 of file covdet.c.


Variable Documentation

Initial value:

Definition at line 1491 of file covdet.c.



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