Public Types | Public Member Functions | Protected Member Functions | Private Attributes | Friends
pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT > Class Template Reference

Octree pointcloud voxel class used for adjacency calculation More...

#include <octree_pointcloud_adjacency.h>

Inheritance diagram for pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef
OctreePointCloudT::BranchNode 
BranchNode
typedef pcl::PointCloud< PointTCloudT
typedef LeafVectorT::const_iterator const_iterator
typedef const
OctreeDepthFirstIterator
< OctreeAdjacencyT
ConstIterator
typedef const
OctreeLeafNodeIterator
< OctreeAdjacencyT
ConstLeafNodeIterator
typedef boost::shared_ptr
< const OctreeAdjacencyT
ConstPtr
typedef
VoxelAdjacencyList::edge_descriptor 
EdgeID
typedef
OctreeDepthFirstIterator
< OctreeAdjacencyT
Iterator
typedef LeafVectorT::iterator iterator
typedef OctreePointCloudT::LeafNode LeafNode
typedef OctreeLeafNodeIterator
< OctreeAdjacencyT
LeafNodeIterator
typedef std::vector
< LeafContainerT * > 
LeafVectorT
typedef
OctreePointCloudAdjacency
< PointT, LeafContainerT,
BranchContainerT > 
OctreeAdjacencyT
typedef OctreeBase
< LeafContainerT,
BranchContainerT > 
OctreeBaseT
typedef OctreePointCloud
< PointT, LeafContainerT,
BranchContainerT, OctreeBaseT
OctreePointCloudT
typedef boost::shared_ptr
< OctreeAdjacencyT
Ptr
typedef boost::adjacency_list
< boost::setS, boost::setS,
boost::undirectedS, PointT,
float > 
VoxelAdjacencyList
typedef
VoxelAdjacencyList::vertex_descriptor 
VoxelID

Public Member Functions

void addPointsFromInputCloud ()
 Adds points from cloud to the octree.
iterator begin ()
void computeVoxelAdjacencyGraph (VoxelAdjacencyList &voxel_adjacency_graph)
 Computes an adjacency graph of voxel relations.
Iterator depth_begin (unsigned int maxDepth_arg=0)
const Iterator depth_end ()
iterator end ()
LeafContainerT * getLeafContainerAtPoint (const PointT &point_arg) const
 Gets the leaf container for a given point.
LeafNodeIterator leaf_begin (unsigned int maxDepth_arg=0)
const LeafNodeIterator leaf_end ()
 OctreePointCloudAdjacency (const double resolution_arg)
 Constructor.
void setTransformFunction (boost::function< void(PointT &p)> transform_func)
 Sets a point transform (and inverse) used to transform the space of the input cloud This is useful for changing how adjacency is calculated - such as relaxing the adjacency criterion for points further from the camera.
size_t size () const
bool testForOcclusion (const PointT &point_arg, const PointXYZ &camera_pos=PointXYZ(0, 0, 0))
 Tests whether input point is occluded from specified camera point by other voxels.
virtual ~OctreePointCloudAdjacency ()
 Empty class destructor.

Protected Member Functions

virtual void addPointIdx (const int pointIdx_arg)
 Add point at index from input pointcloud dataset to octree.
void computeNeighbors (OctreeKey &key_arg, LeafContainerT *leaf_container)
 Fills in the neighbors fields for new voxels.
void genOctreeKeyforPoint (const PointT &point_arg, OctreeKey &key_arg) const
 Generates octree key for specified point (uses transform if provided)

Private Attributes

LeafVectorT leaf_vector_
StopWatch timer_
boost::function< void(PointT &p)> transform_func_

Friends

class OctreeBreadthFirstIterator< OctreeAdjacencyT >
class OctreeDepthFirstIterator< OctreeAdjacencyT >
class OctreeIteratorBase< OctreeAdjacencyT >
class OctreeLeafNodeIterator< OctreeAdjacencyT >

Detailed Description

template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
class pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >

Octree pointcloud voxel class used for adjacency calculation

Note:
This pointcloud octree class generate an octree from a point cloud (zero-copy).
The octree pointcloud is initialized with its voxel resolution. Its bounding box is automatically adjusted or can be predefined.
This class maintains adjacency information for its voxels
The OctreePointCloudAdjacencyContainer can be used to store data in leaf nodes
An optional transform function can be provided which changes how the voxel grid is computed - this can be used to, for example, make voxel bins larger as they increase in distance from the origin (camera)
See SupervoxelClustering for an example of how to provide a transform function
If used in academic work, please cite:
Author:
Jeremie Papon (jpapon@gmail.com)

Definition at line 83 of file octree_pointcloud_adjacency.h.


Member Typedef Documentation

template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
typedef OctreePointCloudT::BranchNode pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::BranchNode
template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
typedef pcl::PointCloud<PointT> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::CloudT

Definition at line 98 of file octree_pointcloud_adjacency.h.

template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
typedef LeafVectorT::const_iterator pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::const_iterator

Definition at line 130 of file octree_pointcloud_adjacency.h.

template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
typedef const OctreeDepthFirstIterator<OctreeAdjacencyT> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::ConstIterator
template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
typedef const OctreeLeafNodeIterator< OctreeAdjacencyT> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::ConstLeafNodeIterator
template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
typedef boost::shared_ptr<const OctreeAdjacencyT> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::ConstPtr
template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
typedef VoxelAdjacencyList::edge_descriptor pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::EdgeID

Definition at line 124 of file octree_pointcloud_adjacency.h.

template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
typedef OctreeDepthFirstIterator<OctreeAdjacencyT> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::Iterator
template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
typedef LeafVectorT::iterator pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::iterator

Definition at line 129 of file octree_pointcloud_adjacency.h.

template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
typedef OctreePointCloudT::LeafNode pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::LeafNode
template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
typedef OctreeLeafNodeIterator<OctreeAdjacencyT> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::LeafNodeIterator
template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
typedef std::vector<LeafContainerT*> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::LeafVectorT

Definition at line 127 of file octree_pointcloud_adjacency.h.

template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
typedef OctreePointCloudAdjacency<PointT, LeafContainerT, BranchContainerT > pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::OctreeAdjacencyT

Definition at line 90 of file octree_pointcloud_adjacency.h.

template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
typedef OctreeBase<LeafContainerT, BranchContainerT> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::OctreeBaseT

Definition at line 88 of file octree_pointcloud_adjacency.h.

template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
typedef OctreePointCloud<PointT, LeafContainerT, BranchContainerT,OctreeBaseT > pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::OctreePointCloudT

Definition at line 94 of file octree_pointcloud_adjacency.h.

template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
typedef boost::shared_ptr<OctreeAdjacencyT> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::Ptr
template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
typedef boost::adjacency_list<boost::setS, boost::setS, boost::undirectedS, PointT, float> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::VoxelAdjacencyList

Definition at line 120 of file octree_pointcloud_adjacency.h.

template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
typedef VoxelAdjacencyList::vertex_descriptor pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::VoxelID

Definition at line 123 of file octree_pointcloud_adjacency.h.


Constructor & Destructor Documentation

template<typename PointT , typename LeafContainerT , typename BranchContainerT >
pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::OctreePointCloudAdjacency ( const double  resolution_arg)

Constructor.

Parameters:
[in]resolution_argoctree resolution at lowest octree level (voxel size)

Definition at line 45 of file octree_pointcloud_adjacency.hpp.

template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
virtual pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::~OctreePointCloudAdjacency ( ) [inline, virtual]

Empty class destructor.

Definition at line 144 of file octree_pointcloud_adjacency.h.


Member Function Documentation

template<typename PointT , typename LeafContainerT , typename BranchContainerT >
void pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::addPointIdx ( const int  pointIdx_arg) [protected, virtual]

Add point at index from input pointcloud dataset to octree.

Parameters:
[in]pointIdx_argthe index representing the point in the dataset given by setInputCloud to be added
Note:
This virtual implementation allows the use of a transform function to compute keys

Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >.

Definition at line 141 of file octree_pointcloud_adjacency.hpp.

template<typename PointT , typename LeafContainerT , typename BranchContainerT >
void pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::addPointsFromInputCloud ( )

Adds points from cloud to the octree.

Note:
This overrides the addPointsFromInputCloud from the OctreePointCloud class

Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >.

Definition at line 54 of file octree_pointcloud_adjacency.hpp.

template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
iterator pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::begin ( ) [inline]

Definition at line 131 of file octree_pointcloud_adjacency.h.

template<typename PointT , typename LeafContainerT , typename BranchContainerT >
void pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::computeNeighbors ( OctreeKey key_arg,
LeafContainerT *  leaf_container 
) [protected]

Fills in the neighbors fields for new voxels.

Parameters:
[in]key_argKey of the voxel to check neighbors for
[in]leaf_containerPointer to container of the leaf to check neighbors for

Definition at line 170 of file octree_pointcloud_adjacency.hpp.

template<typename PointT , typename LeafContainerT , typename BranchContainerT >
void pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::computeVoxelAdjacencyGraph ( VoxelAdjacencyList voxel_adjacency_graph)

Computes an adjacency graph of voxel relations.

Note:
WARNING: This slows down rapidly as cloud size increases due number of edges
Parameters:
[out]voxel_adjacency_graphBoost Graph Library Adjacency graph of the voxel touching relationships - vertices are pointT, edges represent touching, and edge lengths are the distance between the points

Definition at line 213 of file octree_pointcloud_adjacency.hpp.

template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
Iterator pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::depth_begin ( unsigned int  maxDepth_arg = 0) [inline]
template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
const Iterator pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::depth_end ( ) [inline]
template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
iterator pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::end ( ) [inline]
template<typename PointT , typename LeafContainerT , typename BranchContainerT >
void pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::genOctreeKeyforPoint ( const PointT point_arg,
OctreeKey key_arg 
) const [protected]

Generates octree key for specified point (uses transform if provided)

Parameters:
[in]point_argPoint to generate key for
[out]key_argResulting octree key

Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >.

Definition at line 118 of file octree_pointcloud_adjacency.hpp.

template<typename PointT , typename LeafContainerT , typename BranchContainerT >
LeafContainerT * pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::getLeafContainerAtPoint ( const PointT point_arg) const

Gets the leaf container for a given point.

Parameters:
[in]point_argPoint to search for
Returns:
Pointer to the leaf container - null if no leaf container found

Definition at line 198 of file octree_pointcloud_adjacency.hpp.

template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
LeafNodeIterator pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::leaf_begin ( unsigned int  maxDepth_arg = 0) [inline]
template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
const LeafNodeIterator pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::leaf_end ( ) [inline]
template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
void pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::setTransformFunction ( boost::function< void(PointT &p)>  transform_func) [inline]

Sets a point transform (and inverse) used to transform the space of the input cloud This is useful for changing how adjacency is calculated - such as relaxing the adjacency criterion for points further from the camera.

Parameters:
[in]transform_funcA boost:function pointer to the transform to be used. The transform must have one parameter (a point) which it modifies in place

Definition at line 174 of file octree_pointcloud_adjacency.h.

template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
size_t pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::size ( ) const [inline]

Definition at line 134 of file octree_pointcloud_adjacency.h.

template<typename PointT , typename LeafContainerT , typename BranchContainerT >
bool pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::testForOcclusion ( const PointT point_arg,
const PointXYZ camera_pos = PointXYZ (0,0,0) 
)

Tests whether input point is occluded from specified camera point by other voxels.

Parameters:
[in]point_argPoint to test for
[in]camera_posPosition of camera, defaults to origin
Returns:
True if path to camera is blocked by a voxel, false otherwise

Definition at line 260 of file octree_pointcloud_adjacency.hpp.


Friends And Related Function Documentation

template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
friend class OctreeBreadthFirstIterator< OctreeAdjacencyT > [friend]

Definition at line 107 of file octree_pointcloud_adjacency.h.

template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
friend class OctreeDepthFirstIterator< OctreeAdjacencyT > [friend]

Definition at line 106 of file octree_pointcloud_adjacency.h.

template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
friend class OctreeIteratorBase< OctreeAdjacencyT > [friend]

Definition at line 105 of file octree_pointcloud_adjacency.h.

template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
friend class OctreeLeafNodeIterator< OctreeAdjacencyT > [friend]

Definition at line 108 of file octree_pointcloud_adjacency.h.


Member Data Documentation

template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
LeafVectorT pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::leaf_vector_ [private]

Definition at line 215 of file octree_pointcloud_adjacency.h.

template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
StopWatch pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::timer_ [private]

Definition at line 212 of file octree_pointcloud_adjacency.h.

template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer <PointT>, typename BranchContainerT = OctreeContainerEmpty>
boost::function<void (PointT &p)> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::transform_func_ [private]

Definition at line 217 of file octree_pointcloud_adjacency.h.


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


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