point_cloud_library / 1.12.1 / classpcl_1_1_i_s_s_keypoint3_d.html /

ISSKeypoint3D detects the Intrinsic Shape Signatures keypoints for a given point cloud. More...

#include <pcl/keypoints/iss_3d.h>

Public Types

using Ptr = shared_ptr< ISSKeypoint3D< PointInT, PointOutT, NormalT > >
using ConstPtr = shared_ptr< const ISSKeypoint3D< PointInT, PointOutT, NormalT > >
using PointCloudIn = typename Keypoint< PointInT, PointOutT >::PointCloudIn
using PointCloudOut = typename Keypoint< PointInT, PointOutT >::PointCloudOut
using PointCloudN = pcl::PointCloud< NormalT >
using PointCloudNPtr = typename PointCloudN::Ptr
using PointCloudNConstPtr = typename PointCloudN::ConstPtr
using OctreeSearchIn = pcl::octree::OctreePointCloudSearch< PointInT >
using OctreeSearchInPtr = typename OctreeSearchIn::Ptr
- Public Types inherited from pcl::Keypoint< PointInT, PointOutT >
using Ptr = shared_ptr< Keypoint< PointInT, PointOutT > >
using ConstPtr = shared_ptr< const Keypoint< PointInT, PointOutT > >
using BaseClass = PCLBase< PointInT >
using KdTree = pcl::search::Search< PointInT >
using KdTreePtr = typename KdTree::Ptr
using PointCloudIn = pcl::PointCloud< PointInT >
using PointCloudInPtr = typename PointCloudIn::Ptr
using PointCloudInConstPtr = typename PointCloudIn::ConstPtr
using PointCloudOut = pcl::PointCloud< PointOutT >
using SearchMethod = std::function< int(pcl::index_t, double, pcl::Indices &, std::vector< float > &)>
using SearchMethodSurface = std::function< int(const PointCloudIn &cloud, pcl::index_t index, double, pcl::Indices &, std::vector< float > &)>

Public Member Functions

ISSKeypoint3D (double salient_radius=0.0001)
Constructor. More...
~ISSKeypoint3D ()
Destructor. More...
void setSalientRadius (double salient_radius)
Set the radius of the spherical neighborhood used to compute the scatter matrix. More...
void setNonMaxRadius (double non_max_radius)
Set the radius for the application of the non maxima supression algorithm. More...
void setNormalRadius (double normal_radius)
Set the radius used for the estimation of the surface normals of the input cloud. More...
void setBorderRadius (double border_radius)
Set the radius used for the estimation of the boundary points. More...
void setThreshold21 (double gamma_21)
Set the upper bound on the ratio between the second and the first eigenvalue. More...
void setThreshold32 (double gamma_32)
Set the upper bound on the ratio between the third and the second eigenvalue. More...
void setMinNeighbors (int min_neighbors)
Set the minimum number of neighbors that has to be found while applying the non maxima suppression algorithm. More...
void setNormals (const PointCloudNConstPtr &normals)
Set the normals if pre-calculated normals are available. More...
void setAngleThreshold (float angle)
Set the decision boundary (angle threshold) that marks points as boundary or regular. More...
void setNumberOfThreads (unsigned int nr_threads=0)
Initialize the scheduler and set the number of threads to use. More...
- Public Member Functions inherited from pcl::Keypoint< PointInT, PointOutT >
Keypoint ()
Keypoint ()
Empty constructor. More...
void harrisCorner (PointInT &output, PointInT &input, const float sigma_d, const float sigma_i, const float alpha, const float thresh)
void hessianBlob (PointInT &output, PointInT &input, const float sigma, bool SCALE)
void hessianBlob (PointInT &output, PointInT &input, const float start_scale, const float scaling_factor, const int num_scales)
void imageElementMultiply (PointInT &output, PointInT &input1, PointInT &input2)
~Keypoint ()
Empty destructor. More...
virtual void setSearchSurface (const PointCloudInConstPtr &cloud)
Provide a pointer to the input dataset that we need to estimate features at every point for. More...
PointCloudInConstPtr getSearchSurface ()
Get a pointer to the surface point cloud dataset. More...
void setSearchMethod (const KdTreePtr &tree)
Provide a pointer to the search object. More...
KdTreePtr getSearchMethod ()
Get a pointer to the search method used. More...
double getSearchParameter ()
Get the internal search parameter. More...
void setKSearch (int k)
Set the number of k nearest neighbors to use for the feature estimation. More...
int getKSearch ()
get the number of k nearest neighbors used for the feature estimation. More...
void setRadiusSearch (double radius)
Set the sphere radius that is to be used for determining the nearest neighbors used for the key point detection. More...
double getRadiusSearch ()
Get the sphere radius used for determining the neighbors. More...
pcl::PointIndicesConstPtr getKeypointsIndices ()
void compute (PointCloudOut &output)
Base method for key point detection for all points given in <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod () More...
int searchForNeighbors (pcl::index_t index, double parameter, pcl::Indices &indices, std::vector< float > &distances) const
Search for k-nearest neighbors using the spatial locator from setSearchmethod, and the given surface from setSearchSurface. More...

Protected Member Functions

bool * getBoundaryPoints (PointCloudIn &input, double border_radius, float angle_threshold)
Compute the boundary points for the given input cloud. More...
void getScatterMatrix (const int &current_index, Eigen::Matrix3d &cov_m)
Compute the scatter matrix for a point index. More...
bool initCompute () override
Perform the initial checks before computing the keypoints. More...
void detectKeypoints (PointCloudOut &output) override
Detect the keypoints by performing the EVD of the scatter matrix. More...
- Protected Member Functions inherited from pcl::Keypoint< PointInT, PointOutT >
const std::string & getClassName () const
Get a string representation of the name of this class. More...
virtual void detectKeypoints (PointCloudOut &output)=0
Abstract key point detection method. More...

Protected Attributes

double salient_radius_
The radius of the spherical neighborhood used to compute the scatter matrix. More...
double non_max_radius_
The non maxima suppression radius. More...
double normal_radius_
The radius used to compute the normals of the input cloud. More...
double border_radius_
The radius used to compute the boundary points of the input cloud. More...
double gamma_21_
The upper bound on the ratio between the second and the first eigenvalue returned by the EVD. More...
double gamma_32_
The upper bound on the ratio between the third and the second eigenvalue returned by the EVD. More...
double * third_eigen_value_
Store the third eigen value associated to each point in the input cloud. More...
bool * edge_points_
Store the information about the boundary points of the input cloud. More...
int min_neighbors_
Minimum number of neighbors that has to be found while applying the non maxima suppression algorithm. More...
PointCloudNConstPtr normals_
The cloud of normals related to the input surface. More...
float angle_threshold_
The decision boundary (angle threshold) that marks points as boundary or regular. More...
unsigned int threads_
The number of threads that has to be used by the scheduler. More...
- Protected Attributes inherited from pcl::Keypoint< PointInT, PointOutT >
std::string name_
The key point detection method's name. More...
SearchMethod search_method_
The search method template for indices. More...
SearchMethodSurface search_method_surface_
The search method template for points. More...
PointCloudInConstPtr surface_
An input point cloud describing the surface that is to be used for nearest neighbors estimation. More...
KdTreePtr tree_
A pointer to the spatial search object. More...
double search_parameter_
The actual search parameter (casted from either search_radius_ or k_). More...
double search_radius_
The nearest neighbors search radius for each point. More...
int k_
The number of K nearest neighbors to use for each point. More...
pcl::PointIndicesPtr keypoints_indices_
Indices of the keypoints in the input cloud. More...

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:

// Fill in the model cloud
double model_resolution;
// Compute model_resolution
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

ConstPtr

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

Definition at line 89 of file iss_3d.h.

OctreeSearchIn

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

Definition at line 98 of file iss_3d.h.

OctreeSearchInPtr

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

Definition at line 99 of file iss_3d.h.

PointCloudIn

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

Definition at line 91 of file iss_3d.h.

PointCloudN

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

Definition at line 94 of file iss_3d.h.

PointCloudNConstPtr

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

Definition at line 96 of file iss_3d.h.

PointCloudNPtr

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

Definition at line 95 of file iss_3d.h.

PointCloudOut

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

Definition at line 92 of file iss_3d.h.

Ptr

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

Definition at line 88 of file iss_3d.h.

Constructor & Destructor Documentation

ISSKeypoint3D()

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

~ISSKeypoint3D()

template<typename PointInT , typename PointOutT , typename NormalT = pcl::Normal>
pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::~ISSKeypoint3D ( )
inline

Member Function Documentation

detectKeypoints()

template<typename PointInT , typename PointOutT , typename NormalT >
void pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::detectKeypoints ( PointCloudOut & output )
overrideprotected

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

Parameters
[out] output the resultant cloud of keypoints

Definition at line 307 of file iss_3d.hpp.

References pcl::isFinite().

getBoundaryPoints()

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] input the input cloud
[in] border_radius the radius used to compute the boundary points
[in] angle_threshold the decision 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 120 of file iss_3d.hpp.

References pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::getCoordinateSystemOnPlane(), pcl::BoundaryEstimation< PointInT, PointNT, PointOutT >::isBoundaryPoint(), pcl::isFinite(), and pcl::PCLBase< PointInT >::setInputCloud().

getScatterMatrix()

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] current_index the index of the point
[out] cov_m the point scatter matrix

Definition at line 165 of file iss_3d.hpp.

initCompute()

template<typename PointInT , typename PointOutT , typename NormalT >
bool pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::initCompute
overrideprotectedvirtual

setAngleThreshold()

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] angle the angle threshold

Definition at line 193 of file iss_3d.h.

References pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::angle_threshold_.

setBorderRadius()

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_radius the radius used to compute the boundary points

Definition at line 71 of file iss_3d.hpp.

setMinNeighbors()

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_neighbors the minimum number of neighbors required

Definition at line 92 of file iss_3d.hpp.

setNonMaxRadius()

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_radius the non maxima suppression radius

Definition at line 57 of file iss_3d.hpp.

setNormalRadius()

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] normal_radius the radius used to estimate surface normals

Definition at line 64 of file iss_3d.hpp.

setNormals()

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] normals the given cloud of normals

Definition at line 99 of file iss_3d.hpp.

setNumberOfThreads()

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

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

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

Definition at line 106 of file iss_3d.hpp.

Referenced by pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::ISSKeypoint3D().

setSalientRadius()

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_radius the radius of the spherical neighborhood

Definition at line 50 of file iss_3d.hpp.

setThreshold21()

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_21 the upper bound on the ratio between the second and the first eigenvalue

Definition at line 78 of file iss_3d.hpp.

setThreshold32()

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_32 the upper bound on the ratio between the third and the second eigenvalue

Definition at line 85 of file iss_3d.hpp.

Member Data Documentation

angle_threshold_

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 266 of file iss_3d.h.

Referenced by pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::setAngleThreshold().

border_radius_

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 245 of file iss_3d.h.

edge_points_

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 257 of file iss_3d.h.

Referenced by pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::~ISSKeypoint3D().

gamma_21_

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 248 of file iss_3d.h.

gamma_32_

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 251 of file iss_3d.h.

min_neighbors_

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 260 of file iss_3d.h.

non_max_radius_

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 239 of file iss_3d.h.

normal_radius_

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 242 of file iss_3d.h.

normals_

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 263 of file iss_3d.h.

salient_radius_

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 236 of file iss_3d.h.

Referenced by pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::ISSKeypoint3D().

third_eigen_value_

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 254 of file iss_3d.h.

Referenced by pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::~ISSKeypoint3D().

threads_

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 269 of file iss_3d.h.

Referenced by pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::ISSKeypoint3D().


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

© 2009–2012, Willow Garage, Inc.
© 2012–, Open Perception, Inc.
Licensed under the BSD License.
https://pointclouds.org/documentation/classpcl_1_1_i_s_s_keypoint3_d.html