, including all inherited members.
BaseClass typedef | pcl::Feature< PointInT, PointOutT > | |
compute(PointCloudOut &output) | pcl::GFPFHEstimation< PointInT, PointLT, PointOutT > | |
computeDistanceHistogram(const std::vector< float > &distances, std::vector< float > &histogram) | pcl::GFPFHEstimation< PointInT, PointLT, PointOutT > | [protected] |
computeDistancesToMean(const std::vector< std::vector< int > > &transition_histograms, std::vector< float > &distances) | pcl::GFPFHEstimation< PointInT, PointLT, PointOutT > | [protected] |
computeFeature(PointCloudOut &output) | pcl::GFPFHEstimation< PointInT, PointLT, PointOutT > | [protected, virtual] |
computeHIKDistance(const std::vector< int > &histogram, const std::vector< float > &mean_histogram) | pcl::GFPFHEstimation< PointInT, PointLT, PointOutT > | [protected] |
computeMeanHistogram(const std::vector< std::vector< int > > &histograms, std::vector< float > &mean_histogram) | pcl::GFPFHEstimation< PointInT, PointLT, PointOutT > | [protected] |
computeTransitionHistograms(const std::vector< std::vector< int > > &label_histograms, std::vector< std::vector< int > > &transition_histograms) | pcl::GFPFHEstimation< PointInT, PointLT, PointOutT > | [protected] |
ConstPtr typedef | pcl::GFPFHEstimation< PointInT, PointLT, PointOutT > | |
deinitCompute() | pcl::Feature< PointInT, PointOutT > | [protected, virtual] |
descriptor_size_ | pcl::GFPFHEstimation< PointInT, PointLT, PointOutT > | [private] |
descriptorSize() const | pcl::GFPFHEstimation< PointInT, PointLT, PointOutT > | [inline] |
emptyLabel() const | pcl::GFPFHEstimation< PointInT, PointLT, PointOutT > | [inline] |
fake_indices_ | pcl::PCLBase< PointInT > | [protected] |
fake_surface_ | pcl::Feature< PointInT, PointOutT > | [protected] |
Feature() | pcl::Feature< PointInT, PointOutT > | [inline] |
feature_name_ | pcl::Feature< PointInT, PointOutT > | [protected] |
FeatureFromLabels() | pcl::FeatureFromLabels< PointInT, PointLT, PointOutT > | [inline] |
getClassName() const | pcl::Feature< PointInT, PointOutT > | [inline, protected] |
getDominantLabel(const std::vector< int > &indices) | pcl::GFPFHEstimation< PointInT, PointLT, PointOutT > | [protected] |
getIndices() | pcl::PCLBase< PointInT > | [inline] |
getInputCloud() | pcl::PCLBase< PointInT > | [inline] |
getInputLabels() const | pcl::FeatureFromLabels< PointInT, PointLT, PointOutT > | [inline] |
getKSearch() const | pcl::Feature< PointInT, PointOutT > | [inline] |
getNumberOfClasses() const | pcl::GFPFHEstimation< PointInT, PointLT, PointOutT > | [inline] |
getOctreeLeafSize() | pcl::GFPFHEstimation< PointInT, PointLT, PointOutT > | [inline] |
getRadiusSearch() const | pcl::Feature< PointInT, PointOutT > | [inline] |
getSearchMethod() const | pcl::Feature< PointInT, PointOutT > | [inline] |
getSearchParameter() const | pcl::Feature< PointInT, PointOutT > | [inline] |
getSearchSurface() const | pcl::Feature< PointInT, PointOutT > | [inline] |
GFPFHEstimation() | pcl::GFPFHEstimation< PointInT, PointLT, PointOutT > | [inline] |
indices_ | pcl::PCLBase< PointInT > | [protected] |
initCompute() | pcl::FeatureFromLabels< PointInT, PointLT, PointOutT > | [protected, virtual] |
input_ | pcl::PCLBase< PointInT > | [protected] |
k_ | pcl::Feature< PointInT, PointOutT > | [protected] |
KdTree typedef | pcl::Feature< PointInT, PointOutT > | |
KdTreePtr typedef | pcl::Feature< PointInT, PointOutT > | |
labels_ | pcl::FeatureFromLabels< PointInT, PointLT, PointOutT > | [protected] |
number_of_classes_ | pcl::GFPFHEstimation< PointInT, PointLT, PointOutT > | [private] |
octree_leaf_size_ | pcl::GFPFHEstimation< PointInT, PointLT, PointOutT > | [private] |
operator[](size_t pos) | pcl::PCLBase< PointInT > | [inline] |
PCLBase() | pcl::PCLBase< PointInT > | |
PCLBase(const PCLBase &base) | pcl::PCLBase< PointInT > | |
PointCloud typedef | pcl::PCLBase< PointInT > | |
PointCloudConstPtr typedef | pcl::PCLBase< PointInT > | |
PointCloudIn typedef | pcl::GFPFHEstimation< PointInT, PointLT, PointOutT > | |
PointCloudOut typedef | pcl::GFPFHEstimation< PointInT, PointLT, PointOutT > | |
PointCloudPtr typedef | pcl::PCLBase< PointInT > | |
PointIndicesConstPtr typedef | pcl::PCLBase< PointInT > | |
PointIndicesPtr typedef | pcl::PCLBase< PointInT > | |
Ptr typedef | pcl::GFPFHEstimation< PointInT, PointLT, PointOutT > | |
search_method_surface_ | pcl::Feature< PointInT, PointOutT > | [protected] |
search_parameter_ | pcl::Feature< PointInT, PointOutT > | [protected] |
search_radius_ | pcl::Feature< PointInT, PointOutT > | [protected] |
searchForNeighbors(size_t index, double parameter, std::vector< int > &indices, std::vector< float > &distances) const | pcl::Feature< PointInT, PointOutT > | [inline, protected] |
searchForNeighbors(const PointCloudIn &cloud, size_t index, double parameter, std::vector< int > &indices, std::vector< float > &distances) const | pcl::Feature< PointInT, PointOutT > | [inline, protected] |
SearchMethod typedef | pcl::Feature< PointInT, PointOutT > | |
SearchMethodSurface typedef | pcl::Feature< PointInT, PointOutT > | |
setIndices(const IndicesPtr &indices) | pcl::PCLBase< PointInT > | [virtual] |
setIndices(const IndicesConstPtr &indices) | pcl::PCLBase< PointInT > | [virtual] |
setIndices(const PointIndicesConstPtr &indices) | pcl::PCLBase< PointInT > | [virtual] |
setIndices(size_t row_start, size_t col_start, size_t nb_rows, size_t nb_cols) | pcl::PCLBase< PointInT > | [virtual] |
setInputCloud(const PointCloudConstPtr &cloud) | pcl::PCLBase< PointInT > | [virtual] |
setInputLabels(const PointCloudLConstPtr &labels) | pcl::FeatureFromLabels< PointInT, PointLT, PointOutT > | [inline] |
setKSearch(int k) | pcl::Feature< PointInT, PointOutT > | [inline] |
setNumberOfClasses(uint32_t n) | pcl::GFPFHEstimation< PointInT, PointLT, PointOutT > | [inline] |
setOctreeLeafSize(double size) | pcl::GFPFHEstimation< PointInT, PointLT, PointOutT > | [inline] |
setRadiusSearch(double radius) | pcl::Feature< PointInT, PointOutT > | [inline] |
setSearchMethod(const KdTreePtr &tree) | pcl::Feature< PointInT, PointOutT > | [inline] |
setSearchSurface(const PointCloudInConstPtr &cloud) | pcl::Feature< PointInT, PointOutT > | [inline] |
surface_ | pcl::Feature< PointInT, PointOutT > | [protected] |
tree_ | pcl::Feature< PointInT, PointOutT > | [protected] |
use_indices_ | pcl::PCLBase< PointInT > | [protected] |
~Feature() | pcl::Feature< PointInT, PointOutT > | [inline, virtual] |
~FeatureFromLabels() | pcl::FeatureFromLabels< PointInT, PointLT, PointOutT > | [inline, virtual] |
~PCLBase() | pcl::PCLBase< PointInT > | [inline, virtual] |