Covariant feature detectors - Definition. More...
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. | |
VlCovDetFeatureLaplacianScale * | vl_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. | |
VlCovDetFeatureOrientation * | vl_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. | |
VlScaleSpace * | vl_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. | |
void * | vl_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. | |
VlScaleSpace * | vl_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. | |
VlCovDet * | vl_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] |
Covariant feature detectors - Definition.
Definition in file covdet.c.
#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_CONVERGENCE_THRESHOLD 1.001 |
#define VL_COVDET_AA_MAX_ANISOTROPY 5 |
#define VL_COVDET_AA_MAX_NUM_ITERATIONS 15 |
#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_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 |
typedef struct _VlCovDetExtremum2 VlCovDetExtremum2 |
typedef struct _VlCovDetExtremum3 VlCovDetExtremum3 |
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] |
static void _vl_det_hessian_response | ( | float * | hessian, |
float const * | image, | ||
vl_size | width, | ||
vl_size | height, | ||
double | step, | ||
double | sigma | ||
) | [static] |
static void _vl_dog_response | ( | float * | dog, |
float const * | level1, | ||
float const * | level2, | ||
vl_size | width, | ||
vl_size | height | ||
) | [static] |
static int _vl_enlarge_buffer | ( | void ** | buffer, |
vl_size * | bufferSize, | ||
vl_size | targetSize | ||
) | [static] |
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.
harris | output image. |
image | input image. |
width | image width. |
height | image height. |
step | image sampling step (pixel size). |
sigma | Gaussian smoothing of the input image. |
sigmaI | integration scale. |
alpha | factor in the definition of the Harris score. |
static int _vl_resize_buffer | ( | void ** | buffer, |
vl_size * | bufferSize, | ||
vl_size | targetSize | ||
) | [static] |
int vl_covdet_append_feature | ( | VlCovDet * | self, |
VlCovDetFeature const * | feature | ||
) |
Append a feature to the internal buffer.
self | object. |
feature | a pointer to the feature to append. |
The feature is copied. The function may fail with status
equal to VL_ERR_ALLOC if there is insufficient memory.
void vl_covdet_delete | ( | VlCovDet * | self | ) |
void vl_covdet_detect | ( | VlCovDet * | self | ) |
Detect scale-space features.
self | object. |
This function runs the configured feature detector on the image that was passed by using vl_covdet_put_image.
void vl_covdet_drop_features_outside | ( | VlCovDet * | self, |
double | margin | ||
) |
Drop features (partially) outside the image.
self | object. |
margin | geometric 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.
void vl_covdet_extract_affine_shape | ( | VlCovDet * | self | ) |
int vl_covdet_extract_affine_shape_for_frame | ( | VlCovDet * | self, |
VlFrameOrientedEllipse * | adapted, | ||
VlFrameOrientedEllipse | frame | ||
) |
Extract the affine shape for a feature frame.
self | object. |
adapted | the shape-adapted frame. |
frame | the input frame. |
This function may fail if adaptation is unsuccessful or if memory is insufficient.
void vl_covdet_extract_laplacian_scales | ( | VlCovDet * | self | ) |
VlCovDetFeatureLaplacianScale* vl_covdet_extract_laplacian_scales_for_frame | ( | VlCovDet * | self, |
vl_size * | numScales, | ||
VlFrameOrientedEllipse | frame | ||
) |
void vl_covdet_extract_orientations | ( | VlCovDet * | self | ) |
VlCovDetFeatureOrientation* vl_covdet_extract_orientations_for_frame | ( | VlCovDet * | self, |
vl_size * | numOrientations, | ||
VlFrameOrientedEllipse | frame | ||
) |
Extract the orientation(s) for a feature.
self | object. |
numOrientations | the number of detected orientations. |
frame | pose of the feature. |
The returned array is a matrix of size where n is the number of detected orientations.
The function returns NULL
if memory is insufficient.
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.
self | object. |
patch | buffer. |
resolution | patch resolution. |
extent | patch extent. |
sigma | desired smoothing in the patch frame. |
frame | feature 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.
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 | ) |
VlScaleSpace* vl_covdet_get_css | ( | VlCovDet const * | self | ) |
Get the cornerness measure scale space.
A cornerness measure scale space exists only after calling vl_covdet_detect. Otherwise the function returns NULL
.
double vl_covdet_get_edge_threshold | ( | VlCovDet const * | self | ) |
void* vl_covdet_get_features | ( | VlCovDet * | self | ) |
vl_index vl_covdet_get_first_octave | ( | VlCovDet const * | self | ) |
VlScaleSpace* vl_covdet_get_gss | ( | VlCovDet const * | self | ) |
Get the Gaussian scale space.
A Gaussian scale space exists only after calling vl_covdet_put_image. Otherwise the function returns NULL
.
double vl_covdet_get_laplacian_peak_threshold | ( | VlCovDet const * | self | ) |
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.
self | object. |
numScales | length of the histogram (out). |
Calling this function makes sense only after running a detector that uses the Laplacian as a secondary measure for scale detection
double vl_covdet_get_non_extrema_suppression_threshold | ( | VlCovDet const * | self | ) |
vl_size vl_covdet_get_num_features | ( | VlCovDet const * | self | ) |
vl_size vl_covdet_get_num_non_extrema_suppressed | ( | VlCovDet const * | self | ) |
vl_size vl_covdet_get_octave_resolution | ( | VlCovDet const * | self | ) |
double vl_covdet_get_peak_threshold | ( | VlCovDet const * | self | ) |
vl_bool vl_covdet_get_transposed | ( | VlCovDet const * | self | ) |
VlCovDet* vl_covdet_new | ( | VlCovDetMethod | method | ) |
int vl_covdet_put_image | ( | VlCovDet * | self, |
float const * | image, | ||
vl_size | width, | ||
vl_size | height | ||
) |
Detect features in an image.
self | object. |
image | image to process. |
width | image width. |
height | image height. |
width and height must be at least one pixel. The function fails by returing VL_ERR_ALLOC if the memory is insufficient.
void vl_covdet_reset | ( | VlCovDet * | self | ) |
void vl_covdet_set_aa_accurate_smoothing | ( | VlCovDet * | self, |
vl_bool | x | ||
) |
void vl_covdet_set_edge_threshold | ( | VlCovDet * | self, |
double | edgeThreshold | ||
) |
void vl_covdet_set_first_octave | ( | VlCovDet * | self, |
vl_index | o | ||
) |
void vl_covdet_set_laplacian_peak_threshold | ( | VlCovDet * | self, |
double | peakThreshold | ||
) |
void vl_covdet_set_non_extrema_suppression_threshold | ( | VlCovDet * | self, |
double | x | ||
) |
void vl_covdet_set_octave_resolution | ( | VlCovDet * | self, |
vl_size | r | ||
) |
void vl_covdet_set_peak_threshold | ( | VlCovDet * | self, |
double | peakThreshold | ||
) |
void vl_covdet_set_transposed | ( | VlCovDet * | self, |
vl_bool | t | ||
) |
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 | ||
) |
{ {"DoG" , (vl_index)VL_COVDET_METHOD_DOG }, {"Hessian", (vl_index)VL_COVDET_METHOD_HESSIAN }, {"HessianLaplace", (vl_index)VL_COVDET_METHOD_HESSIAN_LAPLACE }, {"HarrisLaplace", (vl_index)VL_COVDET_METHOD_HARRIS_LAPLACE }, {"MultiscaleHessian", (vl_index)VL_COVDET_METHOD_MULTISCALE_HESSIAN}, {"MultiscaleHarris", (vl_index)VL_COVDET_METHOD_MULTISCALE_HARRIS }, {0, 0 } }