Public Types | Public Member Functions | Private Attributes
pcl::SupervoxelClustering< PointT >::SupervoxelHelper Class Reference

Internal storage class for supervoxels. More...

List of all members.

Public Types

typedef float(SupervoxelClustering::* DistFuncPtr )(const VoxelData &v1, const VoxelData &v2)

Public Member Functions

void addLeaf (LeafContainerT *leaf_arg)
void expand ()
VoxelData getCentroid () const
uint32_t getLabel () const
void getNeighborLabels (std::set< uint32_t > &neighbor_labels) const
Eigen::Vector4f getNormal () const
void getNormal (pcl::Normal &normal_arg) const
void getNormals (typename pcl::PointCloud< Normal >::Ptr &normals) const
Eigen::Vector3f getRGB () const
void getRGB (uint32_t &rgba) const
void getVoxels (typename pcl::PointCloud< PointT >::Ptr &voxels) const
Eigen::Vector3f getXYZ () const
void getXYZ (float &x, float &y, float &z) const
void refineNormals ()
void removeAllLeaves ()
void removeLeaf (LeafContainerT *leaf_arg)
size_t size () const
 SupervoxelHelper (uint32_t label, SupervoxelClustering *parent_arg)
void updateCentroid ()

Private Attributes

VoxelData centroid_
uint32_t label_
std::set< LeafContainerT * > leaves_
SupervoxelClusteringparent_

Detailed Description

template<typename PointT>
class pcl::SupervoxelClustering< PointT >::SupervoxelHelper

Internal storage class for supervoxels.

Note:
Stores pointers to leaves of clustering internal octree,
so should not be used outside of clustering class

Definition at line 372 of file supervoxel_clustering.h.


Member Typedef Documentation

template<typename PointT>
typedef float(SupervoxelClustering::* pcl::SupervoxelClustering< PointT >::SupervoxelHelper::DistFuncPtr)(const VoxelData &v1, const VoxelData &v2)

Definition at line 404 of file supervoxel_clustering.h.


Constructor & Destructor Documentation

template<typename PointT>
pcl::SupervoxelClustering< PointT >::SupervoxelHelper::SupervoxelHelper ( uint32_t  label,
SupervoxelClustering parent_arg 
) [inline]

Definition at line 375 of file supervoxel_clustering.h.


Member Function Documentation

template<typename PointT >
void pcl::SupervoxelClustering< PointT >::SupervoxelHelper::addLeaf ( LeafContainerT leaf_arg)

Definition at line 812 of file supervoxel_clustering.hpp.

template<typename PointT >
void pcl::SupervoxelClustering< PointT >::SupervoxelHelper::expand ( )

Definition at line 842 of file supervoxel_clustering.hpp.

template<typename PointT>
VoxelData pcl::SupervoxelClustering< PointT >::SupervoxelHelper::getCentroid ( ) const [inline]

Definition at line 447 of file supervoxel_clustering.h.

template<typename PointT>
uint32_t pcl::SupervoxelClustering< PointT >::SupervoxelHelper::getLabel ( ) const [inline]

Definition at line 407 of file supervoxel_clustering.h.

template<typename PointT >
void pcl::SupervoxelClustering< PointT >::SupervoxelHelper::getNeighborLabels ( std::set< uint32_t > &  neighbor_labels) const

Definition at line 1003 of file supervoxel_clustering.hpp.

template<typename PointT>
Eigen::Vector4f pcl::SupervoxelClustering< PointT >::SupervoxelHelper::getNormal ( ) const [inline]

Definition at line 411 of file supervoxel_clustering.h.

template<typename PointT>
void pcl::SupervoxelClustering< PointT >::SupervoxelHelper::getNormal ( pcl::Normal normal_arg) const [inline]

Definition at line 435 of file supervoxel_clustering.h.

template<typename PointT >
void pcl::SupervoxelClustering< PointT >::SupervoxelHelper::getNormals ( typename pcl::PointCloud< Normal >::Ptr &  normals) const

Definition at line 987 of file supervoxel_clustering.hpp.

template<typename PointT>
Eigen::Vector3f pcl::SupervoxelClustering< PointT >::SupervoxelHelper::getRGB ( ) const [inline]

Definition at line 415 of file supervoxel_clustering.h.

template<typename PointT>
void pcl::SupervoxelClustering< PointT >::SupervoxelHelper::getRGB ( uint32_t &  rgba) const [inline]

Definition at line 427 of file supervoxel_clustering.h.

template<typename PointT >
void pcl::SupervoxelClustering< PointT >::SupervoxelHelper::getVoxels ( typename pcl::PointCloud< PointT >::Ptr &  voxels) const

Definition at line 971 of file supervoxel_clustering.hpp.

template<typename PointT>
Eigen::Vector3f pcl::SupervoxelClustering< PointT >::SupervoxelHelper::getXYZ ( ) const [inline]

Definition at line 419 of file supervoxel_clustering.h.

template<typename PointT>
void pcl::SupervoxelClustering< PointT >::SupervoxelHelper::getXYZ ( float &  x,
float &  y,
float &  z 
) const [inline]

Definition at line 423 of file supervoxel_clustering.h.

template<typename PointT >
void pcl::SupervoxelClustering< PointT >::SupervoxelHelper::refineNormals ( )

Definition at line 888 of file supervoxel_clustering.hpp.

template<typename PointT >
void pcl::SupervoxelClustering< PointT >::SupervoxelHelper::removeAllLeaves ( )

Definition at line 828 of file supervoxel_clustering.hpp.

template<typename PointT >
void pcl::SupervoxelClustering< PointT >::SupervoxelHelper::removeLeaf ( LeafContainerT leaf_arg)

Definition at line 821 of file supervoxel_clustering.hpp.

template<typename PointT>
size_t pcl::SupervoxelClustering< PointT >::SupervoxelHelper::size ( ) const [inline]

Definition at line 452 of file supervoxel_clustering.h.

template<typename PointT >
void pcl::SupervoxelClustering< PointT >::SupervoxelHelper::updateCentroid ( )

Definition at line 928 of file supervoxel_clustering.hpp.


Member Data Documentation

template<typename PointT>
VoxelData pcl::SupervoxelClustering< PointT >::SupervoxelHelper::centroid_ [private]

Definition at line 457 of file supervoxel_clustering.h.

template<typename PointT>
uint32_t pcl::SupervoxelClustering< PointT >::SupervoxelHelper::label_ [private]

Definition at line 456 of file supervoxel_clustering.h.

template<typename PointT>
std::set<LeafContainerT*> pcl::SupervoxelClustering< PointT >::SupervoxelHelper::leaves_ [private]

Definition at line 455 of file supervoxel_clustering.h.

Definition at line 458 of file supervoxel_clustering.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:43:35