pcl::SIFTKeypoint< PointInT, PointOutT > Class Template Reference

SIFTKeypoint detects the Scale Invariant Feature Transform keypoints for a given point cloud dataset containing points and intensity. This implementation adapts the original algorithm from images to point clouds. For more information about the image-based SIFT interest operator, see: More...

#include <sift_keypoint.h>

Inheritance diagram for pcl::SIFTKeypoint< PointInT, PointOutT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef Keypoint< PointInT,
PointOutT >::KdTree 
KdTree
typedef Keypoint< PointInT,
PointOutT >::PointCloudIn 
PointCloudIn
typedef Keypoint< PointInT,
PointOutT >::PointCloudOut 
PointCloudOut

Public Member Functions

void setMinimumContrast (float min_contrast)
 Provide a threshold to limit detection of keypoints without sufficient contrast.
void setScales (float min_scale, int nr_octaves, int nr_scales_per_octave)
 Specify the range of scales over which to search for keypoints.
 SIFTKeypoint ()
 Empty constructor.

Protected Member Functions

void detectKeypoints (PointCloudOut &output)
 Detect the SIFT keypoints for a set of points given in setInputCloud () using the spatial locator in setSearchMethod ().

Private Member Functions

void computeScaleSpace (const PointCloudIn &input, KdTree &tree, const std::vector< float > &scales, Eigen::MatrixXf &diff_of_gauss)
 Compute the difference-of-Gaussian (DoG) scale space for the given input and scales.
void detectKeypointsForOctave (const PointCloudIn &input, KdTree &tree, float base_scale, int nr_scales_per_octave, PointCloudOut &output)
 Detect the SIFT keypoints for a given point cloud for a single octave.
void findScaleSpaceExtrema (const PointCloudIn &input, KdTree &tree, const Eigen::MatrixXf &diff_of_gauss, std::vector< int > &extrema_indices, std::vector< int > &extrema_scales)
 Find the local minima and maxima in the provided difference-of-Gaussian (DoG) scale space.

Private Attributes

float min_contrast_
 The minimum contrast required for detection.
float min_scale_
 The standard deviation of the smallest scale in the scale space.
int nr_octaves_
 The number of octaves (i.e. doublings of scale) over which to search for keypoints.
int nr_scales_per_octave_
 The number of scales to be computed for each octave.

Detailed Description

template<typename PointInT, typename PointOutT>
class pcl::SIFTKeypoint< PointInT, PointOutT >

SIFTKeypoint detects the Scale Invariant Feature Transform keypoints for a given point cloud dataset containing points and intensity. This implementation adapts the original algorithm from images to point clouds. For more information about the image-based SIFT interest operator, see:

David G. Lowe, "Distinctive image features from scale-invariant keypoints," International Journal of Computer Vision, 60, 2 (2004), pp. 91-110.

Author:
Michael Dixon

Definition at line 55 of file sift_keypoint.h.


Member Typedef Documentation

template<typename PointInT, typename PointOutT>
typedef Keypoint<PointInT, PointOutT>::KdTree pcl::SIFTKeypoint< PointInT, PointOutT >::KdTree

Reimplemented from pcl::Keypoint< PointInT, PointOutT >.

Definition at line 60 of file sift_keypoint.h.

template<typename PointInT, typename PointOutT>
typedef Keypoint<PointInT, PointOutT>::PointCloudIn pcl::SIFTKeypoint< PointInT, PointOutT >::PointCloudIn

Reimplemented from pcl::Keypoint< PointInT, PointOutT >.

Definition at line 58 of file sift_keypoint.h.

template<typename PointInT, typename PointOutT>
typedef Keypoint<PointInT, PointOutT>::PointCloudOut pcl::SIFTKeypoint< PointInT, PointOutT >::PointCloudOut

Reimplemented from pcl::Keypoint< PointInT, PointOutT >.

Definition at line 59 of file sift_keypoint.h.


Constructor & Destructor Documentation

template<typename PointInT, typename PointOutT>
pcl::SIFTKeypoint< PointInT, PointOutT >::SIFTKeypoint (  )  [inline]

Empty constructor.

Definition at line 69 of file sift_keypoint.h.


Member Function Documentation

template<typename PointInT , typename PointOutT >
void pcl::SIFTKeypoint< PointInT, PointOutT >::computeScaleSpace ( const PointCloudIn input,
KdTree tree,
const std::vector< float > &  scales,
Eigen::MatrixXf &  diff_of_gauss 
) [inline, private]

Compute the difference-of-Gaussian (DoG) scale space for the given input and scales.

Parameters:
input the point cloud for which the DoG scale space will be computed
tree a k-D tree of the points in input
scales a vector containing the scales over which to compute the DoG scale space
diff_of_gauss the resultant DoG scale space (in a number-of-points by number-of-scales matrix)

Definition at line 163 of file sift_keypoint.hpp.

template<typename PointInT , typename PointOutT >
void pcl::SIFTKeypoint< PointInT, PointOutT >::detectKeypoints ( PointCloudOut output  )  [inline, protected, virtual]

Detect the SIFT keypoints for a set of points given in setInputCloud () using the spatial locator in setSearchMethod ().

Parameters:
output the resultant cloud of keypoints

Implements pcl::Keypoint< PointInT, PointOutT >.

Definition at line 78 of file sift_keypoint.hpp.

template<typename PointInT , typename PointOutT >
void pcl::SIFTKeypoint< PointInT, PointOutT >::detectKeypointsForOctave ( const PointCloudIn input,
KdTree tree,
float  base_scale,
int  nr_scales_per_octave,
PointCloudOut output 
) [inline, private]

Detect the SIFT keypoints for a given point cloud for a single octave.

Parameters:
input the point cloud to detect keypoints in
tree a k-D tree of the points in input
base_scale the first (smallest) scale in the octave
nr_scales_per_octave the number of scales to to compute
output the resultant point cloud containing the SIFT keypoints

Definition at line 128 of file sift_keypoint.hpp.

template<typename PointInT , typename PointOutT >
void pcl::SIFTKeypoint< PointInT, PointOutT >::findScaleSpaceExtrema ( const PointCloudIn input,
KdTree tree,
const Eigen::MatrixXf &  diff_of_gauss,
std::vector< int > &  extrema_indices,
std::vector< int > &  extrema_scales 
) [inline, private]

Find the local minima and maxima in the provided difference-of-Gaussian (DoG) scale space.

Parameters:
input the input point cloud
tree a k-D tree of the points in input
diff_of_gauss the DoG scale space (in a number-of-points by number-of-scales matrix)
extrema_indices the resultant vector containing the point indices of each keypoint
extrema_scales the resultant vector containing the scale indices of each keypoint

Definition at line 217 of file sift_keypoint.hpp.

template<typename PointInT , typename PointOutT >
void pcl::SIFTKeypoint< PointInT, PointOutT >::setMinimumContrast ( float  min_contrast  )  [inline]

Provide a threshold to limit detection of keypoints without sufficient contrast.

Parameters:
min_contrast the minimum contrast required for detection

Definition at line 66 of file sift_keypoint.hpp.

template<typename PointInT , typename PointOutT >
void pcl::SIFTKeypoint< PointInT, PointOutT >::setScales ( float  min_scale,
int  nr_octaves,
int  nr_scales_per_octave 
) [inline]

Specify the range of scales over which to search for keypoints.

Parameters:
min_scale the standard deviation of the smallest scale in the scale space
nr_octaves the number of octaves (i.e. doublings of scale) to compute
nr_scales_per_octave the number of scales to compute within each octave

Definition at line 37 of file sift_keypoint.hpp.


Member Data Documentation

template<typename PointInT, typename PointOutT>
float pcl::SIFTKeypoint< PointInT, PointOutT >::min_contrast_ [private]

The minimum contrast required for detection.

Definition at line 138 of file sift_keypoint.h.

template<typename PointInT, typename PointOutT>
float pcl::SIFTKeypoint< PointInT, PointOutT >::min_scale_ [private]

The standard deviation of the smallest scale in the scale space.

Definition at line 129 of file sift_keypoint.h.

template<typename PointInT, typename PointOutT>
int pcl::SIFTKeypoint< PointInT, PointOutT >::nr_octaves_ [private]

The number of octaves (i.e. doublings of scale) over which to search for keypoints.

Definition at line 132 of file sift_keypoint.h.

template<typename PointInT, typename PointOutT>
int pcl::SIFTKeypoint< PointInT, PointOutT >::nr_scales_per_octave_ [private]

The number of scales to be computed for each octave.

Definition at line 135 of file sift_keypoint.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


pcl
Author(s): See http://pcl.ros.org/authors for the complete list of authors.
autogenerated on Fri Jan 11 09:57:23 2013