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

Keypoint represents the base class for key points. More...

#include <keypoint.h>

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

List of all members.

Public Types

typedef PCLBase< PointInT > BaseClass
typedef pcl::search::Search
< PointInT > 
KdTree
typedef pcl::search::Search
< PointInT >::Ptr 
KdTreePtr
typedef pcl::PointCloud< PointInT > PointCloudIn
typedef PointCloudIn::ConstPtr PointCloudInConstPtr
typedef PointCloudIn::Ptr PointCloudInPtr
typedef pcl::PointCloud
< PointOutT > 
PointCloudOut
typedef boost::function< int(int,
double, std::vector< int >
&, std::vector< float > &)> 
SearchMethod
typedef boost::function< int(const
PointCloudIn &cloud, int index,
double, std::vector< int >
&, std::vector< float > &)> 
SearchMethodSurface

Public Member Functions

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 ()
int getKSearch ()
 get the number of k nearest neighbors used for the feature estimation.
double getRadiusSearch ()
 Get the sphere radius used for determining the neighbors.
KdTreePtr getSearchMethod ()
 Get a pointer to the search method used.
double getSearchParameter ()
 Get the internal search parameter.
PointCloudInConstPtr getSearchSurface ()
 Get a pointer to the surface point cloud dataset.
 Keypoint ()
 Empty constructor.
int searchForNeighbors (int index, double parameter, std::vector< int > &indices, std::vector< float > &distances) const
 Search for k-nearest neighbors using the spatial locator from setSearchmethod, and the given surface from setSearchSurface.
void setKSearch (int k)
 Set the number of k nearest neighbors to use for the feature estimation.
void setRadiusSearch (double radius)
 Set the sphere radius that is to be used for determining the nearest neighbors used for the key point detection.
void setSearchMethod (const KdTreePtr &tree)
 Provide a pointer to the search object.
virtual void setSearchSurface (const PointCloudInConstPtr &cloud)
 Provide a pointer to the input dataset that we need to estimate features at every point for.

Protected Member Functions

virtual void detectKeypoints (PointCloudOut &output)=0
 Abstract key point detection method.
const std::string & getClassName () const
 Get a string representation of the name of this class.
virtual bool initCompute ()
 This method should get called before starting the actual computation.

Protected Attributes

int k_
 The number of K nearest neighbors to use for each point.
std::string name_
 The key point detection method's name.
SearchMethod search_method_
 The search method template for indices.
SearchMethodSurface search_method_surface_
 The search method template for points.
double search_parameter_
 The actual search parameter (casted from either search_radius_ or k_).
double search_radius_
 The nearest neighbors search radius for each point.
PointCloudInConstPtr surface_
 An input point cloud describing the surface that is to be used for nearest neighbors estimation.
KdTreePtr tree_
 A pointer to the spatial search object.

Detailed Description

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

Keypoint represents the base class for key points.

Author:
Bastian Steder

Definition at line 55 of file keypoint.h.


Member Typedef Documentation

template<typename PointInT, typename PointOutT>
typedef PCLBase<PointInT> pcl::Keypoint< PointInT, PointOutT >::BaseClass

Reimplemented in pcl::NarfKeypoint.

Definition at line 61 of file keypoint.h.

template<typename PointInT, typename PointOutT>
typedef pcl::search::Search<PointInT> pcl::Keypoint< PointInT, PointOutT >::KdTree
template<typename PointInT, typename PointOutT>
typedef pcl::search::Search<PointInT>::Ptr pcl::Keypoint< PointInT, PointOutT >::KdTreePtr

Reimplemented in pcl::SmoothedSurfacesKeypoint< PointT, PointNT >.

Definition at line 63 of file keypoint.h.

template<typename PointInT, typename PointOutT>
typedef pcl::PointCloud<PointInT> pcl::Keypoint< PointInT, PointOutT >::PointCloudIn
template<typename PointInT, typename PointOutT>
typedef PointCloudIn::ConstPtr pcl::Keypoint< PointInT, PointOutT >::PointCloudInConstPtr

Reimplemented in pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >.

Definition at line 66 of file keypoint.h.

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

Definition at line 65 of file keypoint.h.

template<typename PointInT, typename PointOutT>
typedef pcl::PointCloud<PointOutT> pcl::Keypoint< PointInT, PointOutT >::PointCloudOut
template<typename PointInT, typename PointOutT>
typedef boost::function<int (int, double, std::vector<int> &, std::vector<float> &)> pcl::Keypoint< PointInT, PointOutT >::SearchMethod

Definition at line 68 of file keypoint.h.

template<typename PointInT, typename PointOutT>
typedef boost::function<int (const PointCloudIn &cloud, int index, double, std::vector<int> &, std::vector<float> &)> pcl::Keypoint< PointInT, PointOutT >::SearchMethodSurface

Definition at line 69 of file keypoint.h.


Constructor & Destructor Documentation

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

Empty constructor.

Definition at line 73 of file keypoint.h.


Member Function Documentation

template<typename PointInT , typename PointOutT >
void pcl::Keypoint< PointInT, PointOutT >::compute ( PointCloudOut output) [inline]

Base method for key point detection for all points given in <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ()

Parameters:
outputthe resultant point cloud model dataset containing the estimated features

Definition at line 121 of file keypoint.hpp.

template<typename PointInT, typename PointOutT>
virtual void pcl::Keypoint< PointInT, PointOutT >::detectKeypoints ( PointCloudOut output) [protected, pure virtual]
template<typename PointInT, typename PointOutT>
const std::string& pcl::Keypoint< PointInT, PointOutT >::getClassName ( ) const [inline, protected]

Get a string representation of the name of this class.

Definition at line 186 of file keypoint.h.

template<typename PointInT, typename PointOutT>
int pcl::Keypoint< PointInT, PointOutT >::getKSearch ( ) [inline]

get the number of k nearest neighbors used for the feature estimation.

Definition at line 117 of file keypoint.h.

template<typename PointInT, typename PointOutT>
double pcl::Keypoint< PointInT, PointOutT >::getRadiusSearch ( ) [inline]

Get the sphere radius used for determining the neighbors.

Definition at line 128 of file keypoint.h.

template<typename PointInT, typename PointOutT>
KdTreePtr pcl::Keypoint< PointInT, PointOutT >::getSearchMethod ( ) [inline]

Get a pointer to the search method used.

Definition at line 103 of file keypoint.h.

template<typename PointInT, typename PointOutT>
double pcl::Keypoint< PointInT, PointOutT >::getSearchParameter ( ) [inline]

Get the internal search parameter.

Definition at line 107 of file keypoint.h.

template<typename PointInT, typename PointOutT>
PointCloudInConstPtr pcl::Keypoint< PointInT, PointOutT >::getSearchSurface ( ) [inline]

Get a pointer to the surface point cloud dataset.

Definition at line 93 of file keypoint.h.

template<typename PointInT , typename PointOutT >
bool pcl::Keypoint< PointInT, PointOutT >::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::PCLBase< PointInT >.

Reimplemented in pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >, pcl::SIFTKeypoint< PointInT, PointOutT >, and pcl::SmoothedSurfacesKeypoint< PointT, PointNT >.

Definition at line 43 of file keypoint.hpp.

template<typename PointInT, typename PointOutT>
int pcl::Keypoint< PointInT, PointOutT >::searchForNeighbors ( int  index,
double  parameter,
std::vector< int > &  indices,
std::vector< float > &  distances 
) const [inline]

Search for k-nearest neighbors using the spatial locator from setSearchmethod, and the given surface from setSearchSurface.

Parameters:
indexthe index of the query point
parameterthe search parameter (either k or radius)
indicesthe resultant vector of indices representing the k-nearest neighbors
distancesthe resultant vector of distances representing the distances from the query point to the k-nearest neighbors

Definition at line 146 of file keypoint.h.

template<typename PointInT, typename PointOutT>
void pcl::Keypoint< PointInT, PointOutT >::setKSearch ( int  k) [inline]

Set the number of k nearest neighbors to use for the feature estimation.

Parameters:
kthe number of k-nearest neighbors

Definition at line 113 of file keypoint.h.

template<typename PointInT, typename PointOutT>
void pcl::Keypoint< PointInT, PointOutT >::setRadiusSearch ( double  radius) [inline]

Set the sphere radius that is to be used for determining the nearest neighbors used for the key point detection.

Parameters:
radiusthe sphere radius used as the maximum distance to consider a point a neighbor

Reimplemented in pcl::UniformSampling< PointInT >, and pcl::UniformSampling< pcl::PointXYZRGBA >.

Definition at line 124 of file keypoint.h.

template<typename PointInT, typename PointOutT>
void pcl::Keypoint< PointInT, PointOutT >::setSearchMethod ( const KdTreePtr tree) [inline]

Provide a pointer to the search object.

Parameters:
treea pointer to the spatial search object.

Definition at line 99 of file keypoint.h.

template<typename PointInT, typename PointOutT>
virtual void pcl::Keypoint< PointInT, PointOutT >::setSearchSurface ( const PointCloudInConstPtr cloud) [inline, virtual]

Provide a pointer to the input dataset that we need to estimate features at every point for.

Parameters:
cloudthe const boost shared pointer to a PointCloud message

Definition at line 89 of file keypoint.h.


Member Data Documentation

template<typename PointInT, typename PointOutT>
int pcl::Keypoint< PointInT, PointOutT >::k_ [protected]

The number of K nearest neighbors to use for each point.

Definition at line 182 of file keypoint.h.

template<typename PointInT, typename PointOutT>
std::string pcl::Keypoint< PointInT, PointOutT >::name_ [protected]

The key point detection method's name.

Definition at line 161 of file keypoint.h.

template<typename PointInT, typename PointOutT>
SearchMethod pcl::Keypoint< PointInT, PointOutT >::search_method_ [protected]

The search method template for indices.

Definition at line 164 of file keypoint.h.

template<typename PointInT, typename PointOutT>
SearchMethodSurface pcl::Keypoint< PointInT, PointOutT >::search_method_surface_ [protected]

The search method template for points.

Definition at line 167 of file keypoint.h.

template<typename PointInT, typename PointOutT>
double pcl::Keypoint< PointInT, PointOutT >::search_parameter_ [protected]

The actual search parameter (casted from either search_radius_ or k_).

Definition at line 176 of file keypoint.h.

template<typename PointInT, typename PointOutT>
double pcl::Keypoint< PointInT, PointOutT >::search_radius_ [protected]

The nearest neighbors search radius for each point.

Definition at line 179 of file keypoint.h.

template<typename PointInT, typename PointOutT>
PointCloudInConstPtr pcl::Keypoint< PointInT, PointOutT >::surface_ [protected]

An input point cloud describing the surface that is to be used for nearest neighbors estimation.

Definition at line 170 of file keypoint.h.

template<typename PointInT, typename PointOutT>
KdTreePtr pcl::Keypoint< PointInT, PointOutT >::tree_ [protected]

A pointer to the spatial search object.

Definition at line 173 of file keypoint.h.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:31