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>
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< NormalT > | PointCloudN |
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 ¢roid, 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::PCLPointField > | out_fields_ |
The list of fields present in the output point cloud data. | |
unsigned int | threads_ |
float | tolerance_ |
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.
typedef boost::shared_ptr<const SUSANKeypoint<PointInT, PointOutT, NormalT, Intensity> > pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::ConstPtr |
Reimplemented from pcl::Keypoint< PointInT, PointOutT >.
typedef Keypoint<PointInT, PointOutT>::KdTree pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::KdTree |
Reimplemented from pcl::Keypoint< PointInT, PointOutT >.
typedef Keypoint<PointInT, PointOutT>::PointCloudIn pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::PointCloudIn |
Reimplemented from pcl::Keypoint< PointInT, PointOutT >.
typedef PointCloudIn::ConstPtr pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::PointCloudInConstPtr |
Reimplemented from pcl::Keypoint< PointInT, PointOutT >.
typedef pcl::PointCloud<NormalT> pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::PointCloudN |
typedef PointCloudN::ConstPtr pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::PointCloudNConstPtr |
typedef PointCloudN::Ptr pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::PointCloudNPtr |
typedef Keypoint<PointInT, PointOutT>::PointCloudOut pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::PointCloudOut |
Reimplemented from pcl::Keypoint< PointInT, PointOutT >.
typedef boost::shared_ptr<SUSANKeypoint<PointInT, PointOutT, NormalT, IntensityT> > pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::Ptr |
Reimplemented from pcl::Keypoint< PointInT, PointOutT >.
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.
[in] | radius | the radius for normal estimation as well as for non maxima suppression |
[in] | distance_threshold | to test if the nucleus is far enough from the centroid |
[in] | angular_threshold | to test if normals are parallel |
[in] | intensity_threshold | to test if points are of same color |
virtual pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::~SUSANKeypoint | ( | ) | [inline, virtual] |
void pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::detectKeypoints | ( | PointCloudOut & | output | ) | [protected, virtual] |
Abstract key point detection method.
Implements pcl::Keypoint< PointInT, PointOutT >.
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:
Reimplemented from pcl::Keypoint< PointInT, PointOutT >.
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
[in] | nucleus | coordinate of the nucleus |
[in] | centroid | of the USAN [in] nucleus to centroid vector (used to speed up since it is constant for a given neighborhood) |
[in] | point | the query point to test against |
void pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::setAngularThreshold | ( | float | angular_threshold | ) |
void pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::setDistanceThreshold | ( | float | distance_threshold | ) |
void pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::setGeometricValidation | ( | bool | validate | ) |
void pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::setIntensityThreshold | ( | float | intensity_threshold | ) |
void pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::setNonMaxSupression | ( | bool | nonmax | ) |
void pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::setNormals | ( | const PointCloudNConstPtr & | normals | ) |
void pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::setNumberOfThreads | ( | unsigned int | nr_threads | ) |
void pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::setRadius | ( | float | radius | ) |
void pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::setSearchSurface | ( | const PointCloudInConstPtr & | cloud | ) | [virtual] |
float pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::angular_threshold_ [private] |
float pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::distance_threshold_ [private] |
bool pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::geometric_validation_ [private] |
IntensityT pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::intensity_ [private] |
pcl::common::IntensityFieldAccessor<PointOutT> pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::intensity_out_ [private] |
float pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::intensity_threshold_ [private] |
int pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::label_idx_ [private] |
bool pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::nonmax_ [private] |
PointCloudNConstPtr pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::normals_ [private] |
std::vector<pcl::PCLPointField> pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::out_fields_ [private] |
unsigned int pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::threads_ [private] |
float pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >::tolerance_ [private] |