Public Types | Public Member Functions | Protected Member Functions | Private Attributes
pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT > Class Template Reference

SUSANKeypoint implements a RGB-D extension of the SUSAN detector inluding normal directions variation in top of intensity variation. It is different from Harris in that it exploits normals directly so it is faster. Original paper "SUSAN — A New Approach to Low Level Image Processing", Smith, Stephen M. and Brady, J. Michael. More...

#include <susan.h>

Inheritance diagram for pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< const SUSANKeypoint
< PointInT, PointOutT, NormalT,
Intensity > > 
ConstPtr
typedef Keypoint< PointInT,
PointOutT >::KdTree 
KdTree
typedef Keypoint< PointInT,
PointOutT >::PointCloudIn 
PointCloudIn
typedef PointCloudIn::ConstPtr PointCloudInConstPtr
typedef pcl::PointCloud< NormalTPointCloudN
typedef PointCloudN::ConstPtr PointCloudNConstPtr
typedef PointCloudN::Ptr PointCloudNPtr
typedef Keypoint< PointInT,
PointOutT >::PointCloudOut 
PointCloudOut
typedef boost::shared_ptr
< SUSANKeypoint< PointInT,
PointOutT, NormalT, IntensityT > > 
Ptr

Public Member Functions

void setAngularThreshold (float angular_threshold)
 set the angular_threshold value for detecting corners. Normals are considered as parallel if 1 - angular_threshold <= (Ni.Nj) <= 1
void setDistanceThreshold (float distance_threshold)
void setGeometricValidation (bool validate)
 Filetr false positive using geometric criteria. The nucleus and the centroid should at least distance_threshold_ from each other AND all the points belonging to the USAN must be within the segment [nucleus centroid].
void setIntensityThreshold (float intensity_threshold)
 set the intensity_threshold value for detecting corners.
void setNonMaxSupression (bool nonmax)
 Apply non maxima suppression to the responses to keep strongest corners.
void setNormals (const PointCloudNConstPtr &normals)
 set normals if precalculated normals are available.
void setNumberOfThreads (unsigned int nr_threads)
 Initialize the scheduler and set the number of threads to use.
void setRadius (float radius)
 set the radius for normal estimation and non maxima supression.
virtual void setSearchSurface (const PointCloudInConstPtr &cloud)
 SUSANKeypoint (float radius=0.01f, float distance_threshold=0.001f, float angular_threshold=0.0001f, float intensity_threshold=7.0f)
 Constructor.
virtual ~SUSANKeypoint ()
 Empty destructor.

Protected Member Functions

void detectKeypoints (PointCloudOut &output)
 Abstract key point detection method.
bool initCompute ()
 This method should get called before starting the actual computation.
bool isWithinNucleusCentroid (const Eigen::Vector3f &nucleus, const Eigen::Vector3f &centroid, const Eigen::Vector3f &nc, const PointInT &point) const
 return true if a point lies within the line between the nucleus and the centroid

Private Attributes

float angular_threshold_
float distance_threshold_
bool geometric_validation_
IntensityT intensity_
 intensity field accessor
pcl::common::IntensityFieldAccessor
< PointOutT
intensity_out_
float intensity_threshold_
int label_idx_
 Set to a value different than -1 if the output cloud has a "label" field and we have to save the keypoints indices.
bool nonmax_
PointCloudNConstPtr normals_
std::vector< pcl::PCLPointFieldout_fields_
 The list of fields present in the output point cloud data.
unsigned int threads_
float tolerance_

Detailed Description

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
class pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >

SUSANKeypoint implements a RGB-D extension of the SUSAN detector inluding normal directions variation in top of intensity variation. It is different from Harris in that it exploits normals directly so it is faster. Original paper "SUSAN — A New Approach to Low Level Image Processing", Smith, Stephen M. and Brady, J. Michael.

Author:
Nizar Sallem

Definition at line 57 of file susan.h.


Member Typedef Documentation

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
typedef boost::shared_ptr<const SUSANKeypoint<PointInT, PointOutT, NormalT, Intensity> > pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::ConstPtr

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

Definition at line 61 of file susan.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
typedef Keypoint<PointInT, PointOutT>::KdTree pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::KdTree

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

Definition at line 65 of file susan.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
typedef Keypoint<PointInT, PointOutT>::PointCloudIn pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::PointCloudIn

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

Definition at line 63 of file susan.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
typedef PointCloudIn::ConstPtr pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::PointCloudInConstPtr

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

Definition at line 66 of file susan.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
typedef pcl::PointCloud<NormalT> pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::PointCloudN

Definition at line 68 of file susan.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
typedef PointCloudN::ConstPtr pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::PointCloudNConstPtr

Definition at line 70 of file susan.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
typedef PointCloudN::Ptr pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::PointCloudNPtr

Definition at line 69 of file susan.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
typedef Keypoint<PointInT, PointOutT>::PointCloudOut pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::PointCloudOut

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

Definition at line 64 of file susan.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
typedef boost::shared_ptr<SUSANKeypoint<PointInT, PointOutT, NormalT, IntensityT> > pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::Ptr

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

Definition at line 60 of file susan.h.


Constructor & Destructor Documentation

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::SUSANKeypoint ( float  radius = 0.01f,
float  distance_threshold = 0.001f,
float  angular_threshold = 0.0001f,
float  intensity_threshold = 7.0f 
) [inline]

Constructor.

Parameters:
[in]radiusthe radius for normal estimation as well as for non maxima suppression
[in]distance_thresholdto test if the nucleus is far enough from the centroid
[in]angular_thresholdto test if normals are parallel
[in]intensity_thresholdto test if points are of same color

Definition at line 88 of file susan.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
virtual pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::~SUSANKeypoint ( ) [inline, virtual]

Empty destructor.

Definition at line 107 of file susan.h.


Member Function Documentation

template<typename PointInT , typename PointOutT , typename NormalT , typename IntensityT >
void pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::detectKeypoints ( PointCloudOut output) [protected, virtual]

Abstract key point detection method.

Implements pcl::Keypoint< PointInT, PointOutT >.

Definition at line 302 of file susan.hpp.

template<typename PointInT , typename PointOutT , typename NormalT , typename IntensityT >
bool pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::initCompute ( ) [protected, virtual]

This method should get called before starting the actual computation.

Internally, initCompute() does the following:

  • checks if an input dataset is given, and returns false otherwise
  • checks whether a set of input indices has been given. Returns true if yes.
  • if no input indices have been given, a fake set is created, which will be used until:
    • either a new set is given via setIndices(), or
    • a new cloud is given that has a different set of points. This will trigger an update on the set of fake indices

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

Definition at line 215 of file susan.hpp.

template<typename PointInT , typename PointOutT , typename NormalT , typename IntensityT >
bool pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::isWithinNucleusCentroid ( const Eigen::Vector3f &  nucleus,
const Eigen::Vector3f &  centroid,
const Eigen::Vector3f &  nc,
const PointInT &  point 
) const [protected]

return true if a point lies within the line between the nucleus and the centroid

Parameters:
[in]nucleuscoordinate of the nucleus
[in]centroidof the USAN [in] nucleus to centroid vector (used to speed up since it is constant for a given neighborhood)
[in]pointthe query point to test against
Returns:
true if the point lies within [nucleus centroid]

Definition at line 254 of file susan.hpp.

template<typename PointInT , typename PointOutT , typename NormalT , typename IntensityT >
void pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::setAngularThreshold ( float  angular_threshold)

set the angular_threshold value for detecting corners. Normals are considered as parallel if 1 - angular_threshold <= (Ni.Nj) <= 1

Parameters:
[in]angular_threshold

Definition at line 75 of file susan.hpp.

template<typename PointInT , typename PointOutT , typename NormalT , typename IntensityT >
void pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::setDistanceThreshold ( float  distance_threshold)

Definition at line 68 of file susan.hpp.

template<typename PointInT , typename PointOutT , typename NormalT , typename IntensityT >
void pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::setGeometricValidation ( bool  validate)

Filetr false positive using geometric criteria. The nucleus and the centroid should at least distance_threshold_ from each other AND all the points belonging to the USAN must be within the segment [nucleus centroid].

Parameters:
[in]validate

Definition at line 54 of file susan.hpp.

template<typename PointInT , typename PointOutT , typename NormalT , typename IntensityT >
void pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::setIntensityThreshold ( float  intensity_threshold)

set the intensity_threshold value for detecting corners.

Parameters:
[in]intensity_threshold

Definition at line 82 of file susan.hpp.

template<typename PointInT , typename PointOutT , typename NormalT , typename IntensityT >
void pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::setNonMaxSupression ( bool  nonmax)

Apply non maxima suppression to the responses to keep strongest corners.

Note:
in SUSAN points with less response or stronger corners

Definition at line 47 of file susan.hpp.

template<typename PointInT , typename PointOutT , typename NormalT , typename IntensityT >
void pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::setNormals ( const PointCloudNConstPtr normals)

set normals if precalculated normals are available.

Parameters:
normals

Definition at line 89 of file susan.hpp.

template<typename PointInT , typename PointOutT , typename NormalT , typename IntensityT >
void pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::setNumberOfThreads ( unsigned int  nr_threads)

Initialize the scheduler and set the number of threads to use.

Parameters:
nr_threadsthe number of hardware threads to use (0 sets the value back to automatic)

Definition at line 104 of file susan.hpp.

template<typename PointInT , typename PointOutT , typename NormalT , typename IntensityT >
void pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::setRadius ( float  radius)

set the radius for normal estimation and non maxima supression.

Parameters:
[in]radius

Definition at line 61 of file susan.hpp.

template<typename PointInT , typename PointOutT , typename NormalT , typename IntensityT >
void pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::setSearchSurface ( const PointCloudInConstPtr cloud) [virtual]

Definition at line 96 of file susan.hpp.


Member Data Documentation

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
float pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::angular_threshold_ [private]

Definition at line 182 of file susan.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
float pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::distance_threshold_ [private]

Definition at line 181 of file susan.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
bool pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::geometric_validation_ [private]

Definition at line 187 of file susan.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
IntensityT pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::intensity_ [private]

intensity field accessor

Definition at line 190 of file susan.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
pcl::common::IntensityFieldAccessor<PointOutT> pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::intensity_out_ [private]

Definition at line 197 of file susan.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
float pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::intensity_threshold_ [private]

Definition at line 183 of file susan.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
int pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::label_idx_ [private]

Set to a value different than -1 if the output cloud has a "label" field and we have to save the keypoints indices.

Definition at line 194 of file susan.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
bool pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::nonmax_ [private]

Definition at line 188 of file susan.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
PointCloudNConstPtr pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::normals_ [private]

Definition at line 185 of file susan.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
std::vector<pcl::PCLPointField> pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::out_fields_ [private]

The list of fields present in the output point cloud data.

Definition at line 196 of file susan.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
unsigned int pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::threads_ [private]

Definition at line 186 of file susan.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal, typename IntensityT = pcl::common::IntensityFieldAccessor<PointInT>>
float pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::tolerance_ [private]

Definition at line 184 of file susan.h.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:43:37