Octree pointcloud voxel class used for adjacency calculation More...
#include <octree_pointcloud_adjacency.h>
Public Types | |
typedef OctreePointCloudT::BranchNode | BranchNode |
typedef pcl::PointCloud< PointT > | CloudT |
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 > |
Octree pointcloud voxel class used for adjacency calculation
Definition at line 83 of file octree_pointcloud_adjacency.h.
typedef OctreePointCloudT::BranchNode pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::BranchNode |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >.
Definition at line 96 of file octree_pointcloud_adjacency.h.
typedef pcl::PointCloud<PointT> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::CloudT |
Definition at line 98 of file octree_pointcloud_adjacency.h.
typedef LeafVectorT::const_iterator pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::const_iterator |
Definition at line 130 of file octree_pointcloud_adjacency.h.
typedef const OctreeDepthFirstIterator<OctreeAdjacencyT> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::ConstIterator |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >.
Definition at line 112 of file octree_pointcloud_adjacency.h.
typedef const OctreeLeafNodeIterator< OctreeAdjacencyT> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::ConstLeafNodeIterator |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >.
Definition at line 118 of file octree_pointcloud_adjacency.h.
typedef boost::shared_ptr<const OctreeAdjacencyT> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::ConstPtr |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >.
Definition at line 92 of file octree_pointcloud_adjacency.h.
typedef VoxelAdjacencyList::edge_descriptor pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::EdgeID |
Definition at line 124 of file octree_pointcloud_adjacency.h.
typedef OctreeDepthFirstIterator<OctreeAdjacencyT> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::Iterator |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >.
Definition at line 111 of file octree_pointcloud_adjacency.h.
typedef LeafVectorT::iterator pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::iterator |
Definition at line 129 of file octree_pointcloud_adjacency.h.
typedef OctreePointCloudT::LeafNode pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::LeafNode |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >.
Definition at line 95 of file octree_pointcloud_adjacency.h.
typedef OctreeLeafNodeIterator<OctreeAdjacencyT> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::LeafNodeIterator |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >.
Definition at line 114 of file octree_pointcloud_adjacency.h.
typedef std::vector<LeafContainerT*> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::LeafVectorT |
Definition at line 127 of file octree_pointcloud_adjacency.h.
typedef OctreePointCloudAdjacency<PointT, LeafContainerT, BranchContainerT > pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::OctreeAdjacencyT |
Definition at line 90 of file octree_pointcloud_adjacency.h.
typedef OctreeBase<LeafContainerT, BranchContainerT> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::OctreeBaseT |
Definition at line 88 of file octree_pointcloud_adjacency.h.
typedef OctreePointCloud<PointT, LeafContainerT, BranchContainerT,OctreeBaseT > pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::OctreePointCloudT |
Definition at line 94 of file octree_pointcloud_adjacency.h.
typedef boost::shared_ptr<OctreeAdjacencyT> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::Ptr |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >.
Definition at line 91 of file octree_pointcloud_adjacency.h.
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.
typedef VoxelAdjacencyList::vertex_descriptor pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::VoxelID |
Definition at line 123 of file octree_pointcloud_adjacency.h.
pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::OctreePointCloudAdjacency | ( | const double | resolution_arg | ) |
Constructor.
[in] | resolution_arg | octree resolution at lowest octree level (voxel size) |
Definition at line 45 of file octree_pointcloud_adjacency.hpp.
virtual pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::~OctreePointCloudAdjacency | ( | ) | [inline, virtual] |
Empty class destructor.
Definition at line 144 of file octree_pointcloud_adjacency.h.
void pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::addPointIdx | ( | const int | pointIdx_arg | ) | [protected, virtual] |
Add point at index from input pointcloud dataset to octree.
[in] | pointIdx_arg | the index representing the point in the dataset given by setInputCloud to be added |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >.
Definition at line 141 of file octree_pointcloud_adjacency.hpp.
void pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::addPointsFromInputCloud | ( | ) |
Adds points from cloud to the octree.
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >.
Definition at line 54 of file octree_pointcloud_adjacency.hpp.
iterator pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::begin | ( | ) | [inline] |
Definition at line 131 of file octree_pointcloud_adjacency.h.
void pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::computeNeighbors | ( | OctreeKey & | key_arg, |
LeafContainerT * | leaf_container | ||
) | [protected] |
Fills in the neighbors fields for new voxels.
[in] | key_arg | Key of the voxel to check neighbors for |
[in] | leaf_container | Pointer to container of the leaf to check neighbors for |
Definition at line 170 of file octree_pointcloud_adjacency.hpp.
void pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::computeVoxelAdjacencyGraph | ( | VoxelAdjacencyList & | voxel_adjacency_graph | ) |
Computes an adjacency graph of voxel relations.
[out] | voxel_adjacency_graph | Boost 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.
Iterator pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::depth_begin | ( | unsigned int | maxDepth_arg = 0 | ) | [inline] |
Reimplemented from pcl::octree::OctreeBase< LeafContainerT, BranchContainerT >.
Definition at line 113 of file octree_pointcloud_adjacency.h.
const Iterator pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::depth_end | ( | ) | [inline] |
Reimplemented from pcl::octree::OctreeBase< LeafContainerT, BranchContainerT >.
Definition at line 114 of file octree_pointcloud_adjacency.h.
iterator pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::end | ( | ) | [inline] |
Reimplemented from pcl::octree::OctreeBase< LeafContainerT, BranchContainerT >.
Definition at line 132 of file octree_pointcloud_adjacency.h.
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)
[in] | point_arg | Point to generate key for |
[out] | key_arg | Resulting octree key |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >.
Definition at line 118 of file octree_pointcloud_adjacency.hpp.
LeafContainerT * pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::getLeafContainerAtPoint | ( | const PointT & | point_arg | ) | const |
Gets the leaf container for a given point.
[in] | point_arg | Point to search for |
Definition at line 198 of file octree_pointcloud_adjacency.hpp.
LeafNodeIterator pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::leaf_begin | ( | unsigned int | maxDepth_arg = 0 | ) | [inline] |
Reimplemented from pcl::octree::OctreeBase< LeafContainerT, BranchContainerT >.
Definition at line 119 of file octree_pointcloud_adjacency.h.
const LeafNodeIterator pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::leaf_end | ( | ) | [inline] |
Reimplemented from pcl::octree::OctreeBase< LeafContainerT, BranchContainerT >.
Definition at line 120 of file octree_pointcloud_adjacency.h.
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.
[in] | transform_func | A 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.
size_t pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::size | ( | ) | const [inline] |
Definition at line 134 of file octree_pointcloud_adjacency.h.
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.
[in] | point_arg | Point to test for |
[in] | camera_pos | Position of camera, defaults to origin |
Definition at line 260 of file octree_pointcloud_adjacency.hpp.
friend class OctreeBreadthFirstIterator< OctreeAdjacencyT > [friend] |
Definition at line 107 of file octree_pointcloud_adjacency.h.
friend class OctreeDepthFirstIterator< OctreeAdjacencyT > [friend] |
Definition at line 106 of file octree_pointcloud_adjacency.h.
friend class OctreeIteratorBase< OctreeAdjacencyT > [friend] |
Definition at line 105 of file octree_pointcloud_adjacency.h.
friend class OctreeLeafNodeIterator< OctreeAdjacencyT > [friend] |
Definition at line 108 of file octree_pointcloud_adjacency.h.
LeafVectorT pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::leaf_vector_ [private] |
Definition at line 215 of file octree_pointcloud_adjacency.h.
StopWatch pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::timer_ [private] |
Definition at line 212 of file octree_pointcloud_adjacency.h.
boost::function<void (PointT &p)> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::transform_func_ [private] |
Definition at line 217 of file octree_pointcloud_adjacency.h.