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

ISSKeypoint3D detects the Intrinsic Shape Signatures keypoints for a given point cloud. This class is based on a particular implementation made by Federico Tombari and Samuele Salti and it has been explicitly adapted to PCL. More...

#include <iss_3d.h>

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

List of all members.

Public Types

typedef boost::shared_ptr
< const ISSKeypoint3D
< PointInT, PointOutT, NormalT > > 
ConstPtr
typedef
pcl::octree::OctreePointCloudSearch
< PointInT > 
OctreeSearchIn
typedef OctreeSearchIn::Ptr OctreeSearchInPtr
typedef Keypoint< PointInT,
PointOutT >::PointCloudIn 
PointCloudIn
typedef pcl::PointCloud< NormalTPointCloudN
typedef PointCloudN::ConstPtr PointCloudNConstPtr
typedef PointCloudN::Ptr PointCloudNPtr
typedef Keypoint< PointInT,
PointOutT >::PointCloudOut 
PointCloudOut
typedef boost::shared_ptr
< ISSKeypoint3D< PointInT,
PointOutT, NormalT > > 
Ptr

Public Member Functions

 ISSKeypoint3D (double salient_radius=0.0001)
 Constructor.
void setAngleThreshold (float angle)
 Set the decision boundary (angle threshold) that marks points as boundary or regular. (default $\pi / 2.0$)
void setBorderRadius (double border_radius)
 Set the radius used for the estimation of the boundary points. If the radius is too large, the temporal performances of the detector may degrade significantly.
void setMinNeighbors (int min_neighbors)
 Set the minimum number of neighbors that has to be found while applying the non maxima suppression algorithm.
void setNonMaxRadius (double non_max_radius)
 Set the radius for the application of the non maxima supression algorithm.
void setNormalRadius (double normal_radius)
 Set the radius used for the estimation of the surface normals of the input cloud. If the radius is too large, the temporal performances of the detector may degrade significantly.
void setNormals (const PointCloudNConstPtr &normals)
 Set the normals if pre-calculated normals are available.
void setNumberOfThreads (unsigned int nr_threads=0)
 Initialize the scheduler and set the number of threads to use.
void setSalientRadius (double salient_radius)
 Set the radius of the spherical neighborhood used to compute the scatter matrix.
void setThreshold21 (double gamma_21)
 Set the upper bound on the ratio between the second and the first eigenvalue.
void setThreshold32 (double gamma_32)
 Set the upper bound on the ratio between the third and the second eigenvalue.

Protected Member Functions

void detectKeypoints (PointCloudOut &output)
 Detect the keypoints by performing the EVD of the scatter matrix.
bool * getBoundaryPoints (PointCloudIn &input, double border_radius, float angle_threshold)
 Compute the boundary points for the given input cloud.
void getScatterMatrix (const int &current_index, Eigen::Matrix3d &cov_m)
 Compute the scatter matrix for a point index.
bool initCompute ()
 Perform the initial checks before computing the keypoints.

Protected Attributes

float angle_threshold_
 The decision boundary (angle threshold) that marks points as boundary or regular. (default $\pi / 2.0$)
double border_radius_
 The radius used to compute the boundary points of the input cloud.
bool * edge_points_
 Store the information about the boundary points of the input cloud.
double gamma_21_
 The upper bound on the ratio between the second and the first eigenvalue returned by the EVD.
double gamma_32_
 The upper bound on the ratio between the third and the second eigenvalue returned by the EVD.
int min_neighbors_
 Minimum number of neighbors that has to be found while applying the non maxima suppression algorithm.
double non_max_radius_
 The non maxima suppression radius.
double normal_radius_
 The radius used to compute the normals of the input cloud.
PointCloudNConstPtr normals_
 The cloud of normals related to the input surface.
double salient_radius_
 The radius of the spherical neighborhood used to compute the scatter matrix.
double * third_eigen_value_
 Store the third eigen value associated to each point in the input cloud.
unsigned int threads_
 The number of threads that has to be used by the scheduler.

Detailed Description

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
class pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >

ISSKeypoint3D detects the Intrinsic Shape Signatures keypoints for a given point cloud. This class is based on a particular implementation made by Federico Tombari and Samuele Salti and it has been explicitly adapted to PCL.

For more information about the original ISS detector, see:

Yu Zhong, “Intrinsic shape signatures: A shape descriptor for 3D object recognition,” Computer Vision Workshops (ICCV Workshops), 2009 IEEE 12th International Conference on , vol., no., pp.689-696, Sept. 27 2009-Oct. 4 2009

Code example:

 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr model (new pcl::PointCloud<pcl::PointXYZRGBA> ());;
 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr model_keypoints (new pcl::PointCloud<pcl::PointXYZRGBA> ());
 pcl::search::KdTree<pcl::PointXYZRGBA>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZRGBA> ());

 // Fill in the model cloud

 double model_resolution;

 // Compute model_resolution

 pcl::ISSKeypoint3D<pcl::PointXYZRGBA, pcl::PointXYZRGBA> iss_detector;

 iss_detector.setSearchMethod (tree);
 iss_detector.setSalientRadius (6 * model_resolution);
 iss_detector.setNonMaxRadius (4 * model_resolution);
 iss_detector.setThreshold21 (0.975);
 iss_detector.setThreshold32 (0.975);
 iss_detector.setMinNeighbors (5);
 iss_detector.setNumberOfThreads (4);
 iss_detector.setInputCloud (model);
 iss_detector.compute (*model_keypoints);
Author:
Gioia Ballin

Definition at line 85 of file iss_3d.h.


Member Typedef Documentation

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
typedef boost::shared_ptr<const ISSKeypoint3D<PointInT, PointOutT, NormalT> > pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::ConstPtr

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

Definition at line 89 of file iss_3d.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
typedef pcl::octree::OctreePointCloudSearch<PointInT> pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::OctreeSearchIn

Definition at line 98 of file iss_3d.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
typedef OctreeSearchIn::Ptr pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::OctreeSearchInPtr

Definition at line 99 of file iss_3d.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
typedef Keypoint<PointInT, PointOutT>::PointCloudIn pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::PointCloudIn

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

Definition at line 91 of file iss_3d.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
typedef pcl::PointCloud<NormalT> pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::PointCloudN

Definition at line 94 of file iss_3d.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
typedef PointCloudN::ConstPtr pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::PointCloudNConstPtr

Definition at line 96 of file iss_3d.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
typedef PointCloudN::Ptr pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::PointCloudNPtr

Definition at line 95 of file iss_3d.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
typedef Keypoint<PointInT, PointOutT>::PointCloudOut pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::PointCloudOut

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

Definition at line 92 of file iss_3d.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
typedef boost::shared_ptr<ISSKeypoint3D<PointInT, PointOutT, NormalT> > pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::Ptr

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

Definition at line 88 of file iss_3d.h.


Constructor & Destructor Documentation

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::ISSKeypoint3D ( double  salient_radius = 0.0001) [inline]

Constructor.

Parameters:
[in]salient_radiusthe radius of the spherical neighborhood used to compute the scatter matrix.

Definition at line 111 of file iss_3d.h.


Member Function Documentation

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

Detect the keypoints by performing the EVD of the scatter matrix.

Parameters:
[out]outputthe resultant cloud of keypoints

Implements pcl::Keypoint< PointInT, PointOutT >.

Definition at line 293 of file iss_3d.hpp.

template<typename PointInT , typename PointOutT , typename NormalT >
bool * pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::getBoundaryPoints ( PointCloudIn input,
double  border_radius,
float  angle_threshold 
) [protected]

Compute the boundary points for the given input cloud.

Parameters:
[in]inputthe input cloud
[in]border_radiusthe radius used to compute the boundary points
[in]thedecision boundary that marks the points as boundary
Returns:
the vector of boolean values in which the information about the boundary points is stored

Definition at line 105 of file iss_3d.hpp.

template<typename PointInT , typename PointOutT , typename NormalT >
void pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::getScatterMatrix ( const int &  current_index,
Eigen::Matrix3d &  cov_m 
) [protected]

Compute the scatter matrix for a point index.

Parameters:
[in]indexthe index of the point
[out]cov_mthe point scatter matrix

Definition at line 149 of file iss_3d.hpp.

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

Perform the initial checks before computing the keypoints.

Returns:
true if all the checks are passed, false otherwise

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

Definition at line 199 of file iss_3d.hpp.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
void pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::setAngleThreshold ( float  angle) [inline]

Set the decision boundary (angle threshold) that marks points as boundary or regular. (default $\pi / 2.0$)

Parameters:
[in]anglethe angle threshold

Definition at line 184 of file iss_3d.h.

template<typename PointInT , typename PointOutT , typename NormalT >
void pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::setBorderRadius ( double  border_radius)

Set the radius used for the estimation of the boundary points. If the radius is too large, the temporal performances of the detector may degrade significantly.

Parameters:
[in]border_radiusthe radius used to compute the boundary points

Definition at line 70 of file iss_3d.hpp.

template<typename PointInT , typename PointOutT , typename NormalT >
void pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::setMinNeighbors ( int  min_neighbors)

Set the minimum number of neighbors that has to be found while applying the non maxima suppression algorithm.

Parameters:
[in]min_neighborsthe minimum number of neighbors required

Definition at line 91 of file iss_3d.hpp.

template<typename PointInT , typename PointOutT , typename NormalT >
void pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::setNonMaxRadius ( double  non_max_radius)

Set the radius for the application of the non maxima supression algorithm.

Parameters:
[in]non_max_radiusthe non maxima suppression radius

Definition at line 56 of file iss_3d.hpp.

template<typename PointInT , typename PointOutT , typename NormalT >
void pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::setNormalRadius ( double  normal_radius)

Set the radius used for the estimation of the surface normals of the input cloud. If the radius is too large, the temporal performances of the detector may degrade significantly.

Parameters:
[in]normals_radiusthe radius used to estimate surface normals

Definition at line 63 of file iss_3d.hpp.

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

Set the normals if pre-calculated normals are available.

Parameters:
[in]normalsthe given cloud of normals

Definition at line 98 of file iss_3d.hpp.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
void pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::setNumberOfThreads ( unsigned int  nr_threads = 0) [inline]

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

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

Definition at line 193 of file iss_3d.h.

template<typename PointInT , typename PointOutT , typename NormalT >
void pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::setSalientRadius ( double  salient_radius)

Set the radius of the spherical neighborhood used to compute the scatter matrix.

Parameters:
[in]salient_radiusthe radius of the spherical neighborhood

Definition at line 49 of file iss_3d.hpp.

template<typename PointInT , typename PointOutT , typename NormalT >
void pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::setThreshold21 ( double  gamma_21)

Set the upper bound on the ratio between the second and the first eigenvalue.

Parameters:
[in]gamma_21the upper bound on the ratio between the second and the first eigenvalue

Definition at line 77 of file iss_3d.hpp.

template<typename PointInT , typename PointOutT , typename NormalT >
void pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::setThreshold32 ( double  gamma_32)

Set the upper bound on the ratio between the third and the second eigenvalue.

Parameters:
[in]gamma_32the upper bound on the ratio between the third and the second eigenvalue

Definition at line 84 of file iss_3d.hpp.


Member Data Documentation

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
float pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::angle_threshold_ [protected]

The decision boundary (angle threshold) that marks points as boundary or regular. (default $\pi / 2.0$)

Definition at line 257 of file iss_3d.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
double pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::border_radius_ [protected]

The radius used to compute the boundary points of the input cloud.

Definition at line 236 of file iss_3d.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
bool* pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::edge_points_ [protected]

Store the information about the boundary points of the input cloud.

Definition at line 248 of file iss_3d.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
double pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::gamma_21_ [protected]

The upper bound on the ratio between the second and the first eigenvalue returned by the EVD.

Definition at line 239 of file iss_3d.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
double pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::gamma_32_ [protected]

The upper bound on the ratio between the third and the second eigenvalue returned by the EVD.

Definition at line 242 of file iss_3d.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
int pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::min_neighbors_ [protected]

Minimum number of neighbors that has to be found while applying the non maxima suppression algorithm.

Definition at line 251 of file iss_3d.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
double pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::non_max_radius_ [protected]

The non maxima suppression radius.

Definition at line 230 of file iss_3d.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
double pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::normal_radius_ [protected]

The radius used to compute the normals of the input cloud.

Definition at line 233 of file iss_3d.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
PointCloudNConstPtr pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::normals_ [protected]

The cloud of normals related to the input surface.

Definition at line 254 of file iss_3d.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
double pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::salient_radius_ [protected]

The radius of the spherical neighborhood used to compute the scatter matrix.

Definition at line 227 of file iss_3d.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
double* pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::third_eigen_value_ [protected]

Store the third eigen value associated to each point in the input cloud.

Definition at line 245 of file iss_3d.h.

template<typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
unsigned int pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::threads_ [protected]

The number of threads that has to be used by the scheduler.

Definition at line 260 of file iss_3d.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:41:57