Public Types | Public Member Functions | Private Attributes
pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT > Class Template Reference

Octree adjacency leaf container class- stores set of pointers to neighbors, number of points added, and a DataT value More...

#include <octree_pointcloud_adjacency_container.h>

Inheritance diagram for pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef
NeighborSetT::const_iterator 
const_iterator
typedef NeighborSetT::iterator iterator
typedef std::set
< OctreePointCloudAdjacencyContainer * > 
NeighborSetT

Public Member Functions

void addNeighbor (OctreePointCloudAdjacencyContainer *neighbor)
 Add new neighbor to voxel.
void addPoint (const PointInT &new_point)
 Add new point to container- this just counts points.
template<>
void addPoint (const pcl::PointXYZRGB &new_point)
template<>
void addPoint (const pcl::PointXYZRGBA &new_point)
iterator begin ()
const_iterator begin () const
void computeData ()
 Function for working on data added. Base implementation does nothing.
template<>
void computeData ()
template<>
void computeData ()
virtual
OctreePointCloudAdjacencyContainer
deepCopy () const
 deep copy function
iterator end ()
const_iterator end () const
DataT & getData ()
 Returns a reference to the data member to access it without copying.
size_t getNumNeighbors () const
 Returns the number of neighbors this leaf has.
int getPointCounter () const
 Gets the number of points contributing to this leaf.
virtual size_t getSize ()
 virtual method to get size of container
std::pair< iterator, bool > insert (OctreePointCloudAdjacencyContainer *neighbor)
 OctreePointCloudAdjacencyContainer ()
 Class initialization.
void removeNeighbor (OctreePointCloudAdjacencyContainer *neighbor)
 Remove neighbor from neighbor set.
virtual void reset ()
 Clear the voxel centroid.
void setData (const DataT &data_arg)
 Sets the data member.
void setNeighbors (const NeighborSetT &neighbor_arg)
 Sets the whole neighbor set.
void setPointCounter (int points_arg)
 Sets the number of points contributing to this leaf.
size_t size () const
virtual ~OctreePointCloudAdjacencyContainer ()
 Empty class deconstructor.

Private Attributes

DataT data_
NeighborSetT neighbors_
int num_points_

Detailed Description

template<typename PointInT, typename DataT = PointInT>
class pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >

Octree adjacency leaf container class- stores set of pointers to neighbors, number of points added, and a DataT value

Note:
This class implements a leaf node that stores pointers to neighboring leaves
This class also has a virtual computeData function, which is called by octreePointCloudAdjacency::addPointsFromInputCloud.
You should make explicit instantiations of it for your pointtype/datatype combo (if needed) see supervoxel_clustering.hpp for an example of this

Definition at line 54 of file octree_pointcloud_adjacency_container.h.


Member Typedef Documentation

template<typename PointInT, typename DataT = PointInT>
typedef NeighborSetT::const_iterator pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::const_iterator

Definition at line 60 of file octree_pointcloud_adjacency_container.h.

template<typename PointInT, typename DataT = PointInT>
typedef NeighborSetT::iterator pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::iterator

Definition at line 59 of file octree_pointcloud_adjacency_container.h.

template<typename PointInT, typename DataT = PointInT>
typedef std::set<OctreePointCloudAdjacencyContainer*> pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::NeighborSetT

Definition at line 57 of file octree_pointcloud_adjacency_container.h.


Constructor & Destructor Documentation

template<typename PointInT, typename DataT = PointInT>
pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::OctreePointCloudAdjacencyContainer ( ) [inline]

Class initialization.

Definition at line 71 of file octree_pointcloud_adjacency_container.h.

template<typename PointInT, typename DataT = PointInT>
virtual pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::~OctreePointCloudAdjacencyContainer ( ) [inline, virtual]

Empty class deconstructor.

Definition at line 78 of file octree_pointcloud_adjacency_container.h.


Member Function Documentation

template<typename PointInT, typename DataT = PointInT>
void pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::addNeighbor ( OctreePointCloudAdjacencyContainer< PointInT, DataT > *  neighbor) [inline]

Add new neighbor to voxel.

Parameters:
[in]neighborthe new neighbor to add

Definition at line 132 of file octree_pointcloud_adjacency_container.h.

template<typename PointInT, typename DataT = PointInT>
void pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::addPoint ( const PointInT &  new_point) [inline]

Add new point to container- this just counts points.

Note:
To actually store data in the leaves, need to specialize this for your point and data type as in supervoxel_clustering.hpp
Parameters:
[in]new_pointthe new point to add

Definition at line 98 of file octree_pointcloud_adjacency_container.h.

Definition at line 704 of file supervoxel_clustering.hpp.

Definition at line 719 of file supervoxel_clustering.hpp.

template<typename PointInT, typename DataT = PointInT>
iterator pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::begin ( ) [inline]

Definition at line 61 of file octree_pointcloud_adjacency_container.h.

template<typename PointInT, typename DataT = PointInT>
const_iterator pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::begin ( ) const [inline]

Definition at line 63 of file octree_pointcloud_adjacency_container.h.

template<typename PointInT, typename DataT = PointInT>
void pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::computeData ( ) [inline]

Function for working on data added. Base implementation does nothing.

Definition at line 107 of file octree_pointcloud_adjacency_container.h.

Definition at line 736 of file supervoxel_clustering.hpp.

Definition at line 747 of file supervoxel_clustering.hpp.

template<typename PointInT, typename DataT = PointInT>
virtual OctreePointCloudAdjacencyContainer* pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::deepCopy ( ) const [inline, virtual]

deep copy function

Definition at line 84 of file octree_pointcloud_adjacency_container.h.

template<typename PointInT, typename DataT = PointInT>
iterator pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::end ( ) [inline]

Definition at line 62 of file octree_pointcloud_adjacency_container.h.

template<typename PointInT, typename DataT = PointInT>
const_iterator pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::end ( ) const [inline]

Definition at line 64 of file octree_pointcloud_adjacency_container.h.

template<typename PointInT, typename DataT = PointInT>
DataT& pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::getData ( ) [inline]

Returns a reference to the data member to access it without copying.

Definition at line 167 of file octree_pointcloud_adjacency_container.h.

template<typename PointInT, typename DataT = PointInT>
size_t pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::getNumNeighbors ( ) const [inline]

Returns the number of neighbors this leaf has.

Returns:
number of neighbors

Definition at line 151 of file octree_pointcloud_adjacency_container.h.

template<typename PointInT, typename DataT = PointInT>
int pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::getPointCounter ( ) const [inline]

Gets the number of points contributing to this leaf.

Definition at line 113 of file octree_pointcloud_adjacency_container.h.

template<typename PointInT, typename DataT = PointInT>
virtual size_t pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::getSize ( ) [inline, virtual]

virtual method to get size of container

Returns:
number of points added to leaf node container.

Reimplemented from pcl::octree::OctreeContainerBase.

Definition at line 179 of file octree_pointcloud_adjacency_container.h.

template<typename PointInT, typename DataT = PointInT>
std::pair<iterator, bool> pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::insert ( OctreePointCloudAdjacencyContainer< PointInT, DataT > *  neighbor) [inline]

Definition at line 68 of file octree_pointcloud_adjacency_container.h.

template<typename PointInT, typename DataT = PointInT>
void pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::removeNeighbor ( OctreePointCloudAdjacencyContainer< PointInT, DataT > *  neighbor) [inline]

Remove neighbor from neighbor set.

Parameters:
[in]neighborthe neighbor to remove

Definition at line 141 of file octree_pointcloud_adjacency_container.h.

template<typename PointInT, typename DataT = PointInT>
virtual void pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::reset ( ) [inline, virtual]

Clear the voxel centroid.

Implements pcl::octree::OctreeContainerBase.

Definition at line 121 of file octree_pointcloud_adjacency_container.h.

template<typename PointInT, typename DataT = PointInT>
void pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::setData ( const DataT &  data_arg) [inline]

Sets the data member.

Parameters:
[in]data_argNew value for data

Definition at line 173 of file octree_pointcloud_adjacency_container.h.

template<typename PointInT, typename DataT = PointInT>
void pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::setNeighbors ( const NeighborSetT neighbor_arg) [inline]

Sets the whole neighbor set.

Parameters:
[in]neighbor_argthe new set

Definition at line 160 of file octree_pointcloud_adjacency_container.h.

template<typename PointInT, typename DataT = PointInT>
void pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::setPointCounter ( int  points_arg) [inline]

Sets the number of points contributing to this leaf.

Definition at line 117 of file octree_pointcloud_adjacency_container.h.

template<typename PointInT, typename DataT = PointInT>
size_t pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::size ( ) const [inline]

Definition at line 66 of file octree_pointcloud_adjacency_container.h.


Member Data Documentation

template<typename PointInT, typename DataT = PointInT>
DataT pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::data_ [private]

Definition at line 188 of file octree_pointcloud_adjacency_container.h.

template<typename PointInT, typename DataT = PointInT>
NeighborSetT pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::neighbors_ [private]

Definition at line 187 of file octree_pointcloud_adjacency_container.h.

template<typename PointInT, typename DataT = PointInT>
int pcl::octree::OctreePointCloudAdjacencyContainer< PointInT, DataT >::num_points_ [private]

Definition at line 186 of file octree_pointcloud_adjacency_container.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:44:31