Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Friends
pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT > Class Template Reference

Octree pointcloud class More...

#include <octree_pointcloud.h>

Inheritance diagram for pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef std::vector< PointT,
Eigen::aligned_allocator
< PointT > > 
AlignedPointTVector
typedef OctreeT Base
typedef OctreeT::BranchNode BranchNode
typedef
OctreeBreadthFirstIterator
< int, OctreeT > 
BreadthFirstIterator
typedef const
OctreeBreadthFirstIterator
< int, OctreeT > 
ConstBreadthFirstIterator
typedef const
OctreeDepthFirstIterator< int,
OctreeT > 
ConstDepthFirstIterator
typedef const
OctreeDepthFirstIterator< int,
OctreeT > 
ConstIterator
typedef const
OctreeLeafNodeIterator< int,
OctreeT > 
ConstLeafNodeIterator
typedef boost::shared_ptr
< const OctreePointCloud
< PointT, LeafT, OctreeT > > 
ConstPtr
typedef
OctreeDepthFirstIterator< int,
OctreeT > 
DepthFirstIterator
typedef OctreePointCloud
< PointT, LeafT,
Octree2BufBase< int, LeafT > > 
DoubleBuffer
typedef boost::shared_ptr
< const std::vector< int > > 
IndicesConstPtr
typedef boost::shared_ptr
< std::vector< int > > 
IndicesPtr
typedef
OctreeDepthFirstIterator< int,
OctreeT > 
Iterator
typedef OctreeT::LeafNode LeafNode
typedef OctreeLeafNodeIterator
< int, OctreeT > 
LeafNodeIterator
typedef pcl::PointCloud< PointTPointCloud
typedef boost::shared_ptr
< const PointCloud
PointCloudConstPtr
typedef boost::shared_ptr
< PointCloud
PointCloudPtr
typedef boost::shared_ptr
< OctreePointCloud< PointT,
LeafT, OctreeT > > 
Ptr
typedef OctreePointCloud
< PointT, LeafT, OctreeBase
< int, LeafT > > 
SingleBuffer

Public Member Functions

void addPointFromCloud (const int pointIdx_arg, IndicesPtr indices_arg)
 Add point at given index from input point cloud to octree. Index will be also added to indices vector.
void addPointsFromInputCloud ()
 Add points from input point cloud to octree.
void addPointToCloud (const PointT &point_arg, PointCloudPtr cloud_arg)
 Add point simultaneously to octree and input point cloud.
void addPointToCloud (const PointT &point_arg, PointCloudPtr cloud_arg, IndicesPtr indices_arg)
 Add point simultaneously to octree and input point cloud. A corresponding index will be added to the indices vector.
void defineBoundingBox ()
 Investigate dimensions of pointcloud data set and define corresponding bounding box for octree.
void defineBoundingBox (const double minX_arg, const double minY_arg, const double minZ_arg, const double maxX_arg, const double maxY_arg, const double maxZ_arg)
 Define bounding box for octree.
void defineBoundingBox (const double maxX_arg, const double maxY_arg, const double maxZ_arg)
 Define bounding box for octree.
void defineBoundingBox (const double cubeLen_arg)
 Define bounding box cube for octree.
void deleteTree (bool freeMemory_arg=false)
 Delete the octree structure and its leaf nodes.
void deleteVoxelAtPoint (const PointT &point_arg)
 Delete leaf node / voxel at given point.
void deleteVoxelAtPoint (const int &pointIdx_arg)
 Delete leaf node / voxel at given point from input cloud.
int getApproxIntersectedVoxelCentersBySegment (const Eigen::Vector3f &origin, const Eigen::Vector3f &end, AlignedPointTVector &voxel_center_list, float precision=0.2)
 Get a PointT vector of centers of voxels intersected by a line segment. This returns a approximation of the actual intersected voxels by walking along the line with small steps. Voxels are ordered, from closest to furthest w.r.t. the origin.
void getBoundingBox (double &minX_arg, double &minY_arg, double &minZ_arg, double &maxX_arg, double &maxY_arg, double &maxZ_arg) const
 Get bounding box for octree.
double getEpsilon () const
 Get the search epsilon precision (error bound) for nearest neighbors searches.
IndicesConstPtr const getIndices () const
 Get a pointer to the vector of indices used.
PointCloudConstPtr getInputCloud () const
 Get a pointer to the input point cloud dataset.
int getOccupiedVoxelCenters (AlignedPointTVector &voxelCenterList_arg) const
 Get a PointT vector of centers of all occupied voxels.
double getResolution () const
 Get octree voxel resolution.
unsigned int getTreeDepth () const
 Get the maximum depth of the octree.
void getVoxelBounds (OctreeIteratorBase< int, OctreeT > &iterator, Eigen::Vector3f &min_pt, Eigen::Vector3f &max_pt)
 Generate bounds of the current voxel of an octree iterator.
double getVoxelSquaredDiameter (unsigned int treeDepth_arg) const
 Calculates the squared diameter of a voxel at given tree depth.
double getVoxelSquaredDiameter () const
 Calculates the squared diameter of a voxel at leaf depth.
double getVoxelSquaredSideLen (unsigned int treeDepth_arg) const
 Calculates the squared voxel cube side length at given tree depth.
double getVoxelSquaredSideLen () const
 Calculates the squared voxel cube side length at leaf level.
bool isVoxelOccupiedAtPoint (const PointT &point_arg) const
 Check if voxel at given point exist.
bool isVoxelOccupiedAtPoint (const double pointX_arg, const double pointY_arg, const double pointZ_arg) const
 Check if voxel at given point coordinates exist.
bool isVoxelOccupiedAtPoint (const int &pointIdx_arg) const
 Check if voxel at given point from input cloud exist.
 OctreePointCloud (const double resolution_arg)
 Octree pointcloud constructor.
void setEpsilon (double eps)
 Set the search epsilon precision (error bound) for nearest neighbors searches.
void setInputCloud (const PointCloudConstPtr &cloud_arg, const IndicesConstPtr &indices_arg=IndicesConstPtr())
 Provide a pointer to the input data set.
void setResolution (double resolution_arg)
 Set/change the octree voxel resolution.
virtual ~OctreePointCloud ()
 Empty deconstructor.

Protected Member Functions

void addPointIdx (const int pointIdx_arg)
 Add point at index from input pointcloud dataset to octree.
void adoptBoundingBoxToPoint (const PointT &pointIdx_arg)
 Grow the bounding box/octree until point fits.
LeafT * findLeafAtPoint (const PointT &point_arg) const
 Find octree leaf node at a given point.
void genLeafNodeCenterFromOctreeKey (const OctreeKey &key_arg, PointT &point_arg) const
 Generate a point at center of leaf node voxel.
virtual bool genOctreeKeyForDataT (const int &data_arg, OctreeKey &key_arg) const
 Virtual method for generating octree key for a given point index.
void genOctreeKeyforPoint (const PointT &point_arg, OctreeKey &key_arg) const
 Generate octree key for voxel at a given point.
void genOctreeKeyforPoint (const double pointX_arg, const double pointY_arg, const double pointZ_arg, OctreeKey &key_arg) const
 Generate octree key for voxel at a given point.
void genVoxelBoundsFromOctreeKey (const OctreeKey &key_arg, unsigned int treeDepth_arg, Eigen::Vector3f &min_pt, Eigen::Vector3f &max_pt) const
 Generate bounds of an octree voxel using octree key and tree depth arguments.
void genVoxelCenterFromOctreeKey (const OctreeKey &key_arg, unsigned int treeDepth_arg, PointT &point_arg) const
 Generate a point at center of octree voxel at given tree level.
void getKeyBitSize ()
 Define octree key setting and octree depth based on defined bounding box.
int getOccupiedVoxelCentersRecursive (const BranchNode *node_arg, const OctreeKey &key_arg, AlignedPointTVector &voxelCenterList_arg) const
 Recursively search the tree for all leaf nodes and return a vector of voxel centers.
const PointTgetPointByIndex (const unsigned int index_arg) const
 Get point at index from input pointcloud dataset.
bool isPointWithinBoundingBox (const PointT &pointIdx_arg) const
 Checks if given point is within the bounding box of the octree.

Protected Attributes

bool boundingBoxDefined_
 Flag indicating if octree has defined bounding box.
double epsilon_
 Epsilon precision (error bound) for nearest neighbors searches.
IndicesConstPtr indices_
 A pointer to the vector of point indices to use.
PointCloudConstPtr input_
 Pointer to input point cloud dataset.
double maxX_
double maxY_
double maxZ_
double minX_
double minY_
double minZ_
double resolution_
 Octree resolution.

Friends

class OctreeBreadthFirstIterator< int, OctreeT >
class OctreeDepthFirstIterator< int, OctreeT >
class OctreeIteratorBase< int, OctreeT >
class OctreeLeafNodeIterator< int, OctreeT >

Detailed Description

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
class pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >

Octree pointcloud class

Note:
Octree implementation for pointclouds. Only indices are stored by the octree leaf nodes (zero-copy).
The octree pointcloud class needs to be initialized with its voxel resolution. Its bounding box is automatically adjusted
according to the pointcloud dimension or it can be predefined.
Note: The tree depth equates to the resolution and the bounding box dimensions of the octree.
typename: PointT: type of point used in pointcloud
typename: LeafT: leaf node container (
typename: BranchT: branch node container
typename: OctreeT: octree implementation ()
Author:
Julius Kammerl (julius@kammerl.de)

Definition at line 80 of file octree_pointcloud.h.


Member Typedef Documentation

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
typedef std::vector<PointT, Eigen::aligned_allocator<PointT> > pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::AlignedPointTVector
template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
typedef OctreeT pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::Base

Definition at line 89 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
typedef OctreeT::BranchNode pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::BranchNode
template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
typedef OctreeBreadthFirstIterator<int, OctreeT> pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::BreadthFirstIterator

Definition at line 103 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
typedef const OctreeBreadthFirstIterator<int, OctreeT> pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::ConstBreadthFirstIterator

Definition at line 104 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
typedef const OctreeDepthFirstIterator<int, OctreeT> pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::ConstDepthFirstIterator

Definition at line 102 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
typedef const OctreeDepthFirstIterator<int, OctreeT> pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::ConstIterator

Definition at line 96 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
typedef const OctreeLeafNodeIterator<int, OctreeT> pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::ConstLeafNodeIterator

Definition at line 99 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
typedef boost::shared_ptr<const OctreePointCloud<PointT, LeafT, OctreeT> > pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::ConstPtr
template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
typedef OctreeDepthFirstIterator<int, OctreeT> pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::DepthFirstIterator

Definition at line 101 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
typedef OctreePointCloud<PointT, LeafT, Octree2BufBase<int, LeafT> > pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::DoubleBuffer
template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
typedef boost::shared_ptr<const std::vector<int> > pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::IndicesConstPtr
template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
typedef boost::shared_ptr<std::vector<int> > pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::IndicesPtr
template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
typedef OctreeDepthFirstIterator<int, OctreeT> pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::Iterator

Definition at line 95 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
typedef OctreeT::LeafNode pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::LeafNode
template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
typedef OctreeLeafNodeIterator<int, OctreeT> pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::LeafNodeIterator

Definition at line 98 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
typedef pcl::PointCloud<PointT> pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::PointCloud
template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
typedef boost::shared_ptr<const PointCloud> pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::PointCloudConstPtr
template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
typedef boost::shared_ptr<PointCloud> pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::PointCloudPtr
template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
typedef boost::shared_ptr<OctreePointCloud<PointT, LeafT, OctreeT> > pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::Ptr
template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
typedef OctreePointCloud<PointT, LeafT, OctreeBase<int, LeafT> > pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::SingleBuffer

Constructor & Destructor Documentation

template<typename PointT , typename LeafT , typename BranchT , typename OctreeT >
pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::OctreePointCloud ( const double  resolution_arg)

Octree pointcloud constructor.

Parameters:
[in]resolution_argoctree resolution at lowest octree level

Definition at line 49 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafT , typename BranchT , typename OctreeT >
pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::~OctreePointCloud ( ) [virtual]

Empty deconstructor.

Definition at line 59 of file octree_pointcloud.hpp.


Member Function Documentation

template<typename PointT , typename LeafT , typename BranchT , typename OctreeT >
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::addPointFromCloud ( const int  pointIdx_arg,
IndicesPtr  indices_arg 
)

Add point at given index from input point cloud to octree. Index will be also added to indices vector.

Parameters:
[in]pointIdx_argindex of point to be added
[in]indices_argpointer to indices vector of the dataset (given by setInputCloud)

Definition at line 98 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafT , typename BranchT , typename OctreeT >
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::addPointIdx ( const int  pointIdx_arg) [protected]

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

Definition at line 507 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafT , typename BranchT , typename OctreeT >
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::addPointsFromInputCloud ( )

Add points from input point cloud to octree.

Definition at line 65 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafT , typename BranchT , typename OctreeT >
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::addPointToCloud ( const PointT point_arg,
PointCloudPtr  cloud_arg 
)

Add point simultaneously to octree and input point cloud.

Parameters:
[in]point_argpoint to be added
[in]cloud_argpointer to input point cloud dataset (given by setInputCloud)

Definition at line 107 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafT , typename BranchT , typename OctreeT >
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::addPointToCloud ( const PointT point_arg,
PointCloudPtr  cloud_arg,
IndicesPtr  indices_arg 
)

Add point simultaneously to octree and input point cloud. A corresponding index will be added to the indices vector.

Parameters:
[in]point_argpoint to be added
[in]cloud_argpointer to input point cloud dataset (given by setInputCloud)
[in]indices_argpointer to indices vector of the dataset (given by setInputCloud)

Definition at line 118 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafT , typename BranchT , typename OctreeT >
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::adoptBoundingBoxToPoint ( const PointT pointIdx_arg) [protected]

Grow the bounding box/octree until point fits.

Parameters:
[in]pointIdx_argpoint that should be within bounding box;

Definition at line 417 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafT , typename BranchT , typename OctreeT >
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::defineBoundingBox ( )

Investigate dimensions of pointcloud data set and define corresponding bounding box for octree.

Definition at line 266 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafT , typename BranchT , typename OctreeT >
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::defineBoundingBox ( const double  minX_arg,
const double  minY_arg,
const double  minZ_arg,
const double  maxX_arg,
const double  maxY_arg,
const double  maxZ_arg 
)

Define bounding box for octree.

Note:
Bounding box cannot be changed once the octree contains elements.
Parameters:
[in]minX_argX coordinate of lower bounding box corner
[in]minY_argY coordinate of lower bounding box corner
[in]minZ_argZ coordinate of lower bounding box corner
[in]maxX_argX coordinate of upper bounding box corner
[in]maxY_argY coordinate of upper bounding box corner
[in]maxZ_argZ coordinate of upper bounding box corner

Definition at line 295 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafT , typename BranchT , typename OctreeT >
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::defineBoundingBox ( const double  maxX_arg,
const double  maxY_arg,
const double  maxZ_arg 
)

Define bounding box for octree.

Note:
Lower bounding box point is set to (0, 0, 0)
Bounding box cannot be changed once the octree contains elements.
Parameters:
[in]maxX_argX coordinate of upper bounding box corner
[in]maxY_argY coordinate of upper bounding box corner
[in]maxZ_argZ coordinate of upper bounding box corner

Definition at line 334 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafT , typename BranchT , typename OctreeT >
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::defineBoundingBox ( const double  cubeLen_arg)

Define bounding box cube for octree.

Note:
Lower bounding box corner is set to (0, 0, 0)
Bounding box cannot be changed once the octree contains elements.
Parameters:
[in]cubeLen_argside length of bounding box cube.

Definition at line 369 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::deleteTree ( bool  freeMemory_arg = false) [inline]

Delete the octree structure and its leaf nodes.

Parameters:
freeMemory_arg,:if "true", allocated octree nodes are deleted, otherwise they are pushed to the octree node pool

Definition at line 243 of file octree_pointcloud.h.

template<typename PointT, typename LeafT , typename BranchT , typename OctreeT >
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::deleteVoxelAtPoint ( const PointT point_arg)

Delete leaf node / voxel at given point.

Parameters:
[in]point_argpoint addressing the voxel to be deleted.

Definition at line 168 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafT , typename BranchT , typename OctreeT >
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::deleteVoxelAtPoint ( const int &  pointIdx_arg)

Delete leaf node / voxel at given point from input cloud.

Parameters:
[in]pointIdx_argindex of point addressing the voxel to be deleted.

Definition at line 180 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafT , typename BranchT , typename OctreeT >
LeafT * pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::findLeafAtPoint ( const PointT point_arg) const [protected]

Find octree leaf node at a given point.

Parameters:
[in]point_argquery point
Returns:
pointer to leaf node. If leaf node does not exist, pointer is 0.

Definition at line 536 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafT , typename BranchT , typename OctreeT >
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::genLeafNodeCenterFromOctreeKey ( const OctreeKey key_arg,
PointT point_arg 
) const [protected]

Generate a point at center of leaf node voxel.

Parameters:
[in]key_argoctree key addressing a leaf node.
[out]point_argwrite leaf node voxel center to this point reference

Definition at line 646 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafT , typename BranchT , typename OctreeT >
bool pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::genOctreeKeyForDataT ( const int &  data_arg,
OctreeKey key_arg 
) const [protected, virtual]

Virtual method for generating octree key for a given point index.

Note:
This method enables to assign indices to leaf nodes during octree deserialization.
Parameters:
[in]data_argindex value representing a point in the dataset given by setInputCloud
[out]key_argwrite octree key to this reference
Returns:
"true" - octree keys are assignable

Definition at line 634 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafT , typename BranchT , typename OctreeT >
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::genOctreeKeyforPoint ( const PointT point_arg,
OctreeKey key_arg 
) const [protected]

Generate octree key for voxel at a given point.

Parameters:
[in]point_argthe point addressing a voxel
[out]key_argwrite octree key to this reference

Definition at line 607 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafT , typename BranchT , typename OctreeT >
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::genOctreeKeyforPoint ( const double  pointX_arg,
const double  pointY_arg,
const double  pointZ_arg,
OctreeKey key_arg 
) const [protected]

Generate octree key for voxel at a given point.

Parameters:
[in]pointX_argX coordinate of point addressing a voxel
[in]pointY_argY coordinate of point addressing a voxel
[in]pointZ_argZ coordinate of point addressing a voxel
[out]key_argwrite octree key to this reference

Definition at line 618 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafT , typename BranchT , typename OctreeT >
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::genVoxelBoundsFromOctreeKey ( const OctreeKey key_arg,
unsigned int  treeDepth_arg,
Eigen::Vector3f &  min_pt,
Eigen::Vector3f &  max_pt 
) const [protected]

Generate bounds of an octree voxel using octree key and tree depth arguments.

Parameters:
[in]key_argoctree key addressing an octree node.
[in]treeDepth_argoctree depth of query voxel
[out]min_ptlower bound of voxel
[out]max_ptupper bound of voxel

Definition at line 669 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafT , typename BranchT , typename OctreeT >
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::genVoxelCenterFromOctreeKey ( const OctreeKey key_arg,
unsigned int  treeDepth_arg,
PointT point_arg 
) const [protected]

Generate a point at center of octree voxel at given tree level.

Parameters:
[in]key_argoctree key addressing an octree node.
[in]treeDepth_argoctree depth of query voxel
[out]point_argwrite leaf node center point to this reference

Definition at line 656 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafT , typename BranchT , typename OctreeT >
int pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getApproxIntersectedVoxelCentersBySegment ( const Eigen::Vector3f &  origin,
const Eigen::Vector3f &  end,
AlignedPointTVector voxel_center_list,
float  precision = 0.2 
)

Get a PointT vector of centers of voxels intersected by a line segment. This returns a approximation of the actual intersected voxels by walking along the line with small steps. Voxels are ordered, from closest to furthest w.r.t. the origin.

Parameters:
[in]originorigin of the line segment
[in]endend of the line segment
[out]voxel_center_listresults are written to this vector of PointT elements
[in]precisiondetermines the size of the steps: step_size = octree_resolution x precision
Returns:
number of intersected voxels

Definition at line 205 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafT , typename BranchT , typename OctreeT >
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getBoundingBox ( double &  minX_arg,
double &  minY_arg,
double &  minZ_arg,
double &  maxX_arg,
double &  maxY_arg,
double &  maxZ_arg 
) const

Get bounding box for octree.

Note:
Bounding box cannot be changed once the octree contains elements.
Parameters:
[in]minX_argX coordinate of lower bounding box corner
[in]minY_argY coordinate of lower bounding box corner
[in]minZ_argZ coordinate of lower bounding box corner
[in]maxX_argX coordinate of upper bounding box corner
[in]maxY_argY coordinate of upper bounding box corner
[in]maxZ_argZ coordinate of upper bounding box corner

Definition at line 401 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getEpsilon ( ) const [inline]

Get the search epsilon precision (error bound) for nearest neighbors searches.

Definition at line 172 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
IndicesConstPtr const pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getIndices ( ) const [inline]

Get a pointer to the vector of indices used.

Returns:
pointer to vector of indices used.

Definition at line 150 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
PointCloudConstPtr pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getInputCloud ( ) const [inline]

Get a pointer to the input point cloud dataset.

Returns:
pointer to pointcloud input class.

Definition at line 158 of file octree_pointcloud.h.

template<typename PointT , typename LeafT , typename BranchT , typename OctreeT >
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getKeyBitSize ( ) [protected]

Define octree key setting and octree depth based on defined bounding box.

Definition at line 548 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafT , typename BranchT , typename OctreeT >
int pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getOccupiedVoxelCenters ( AlignedPointTVector voxelCenterList_arg) const

Get a PointT vector of centers of all occupied voxels.

Parameters:
[out]voxelCenterList_argresults are written to this vector of PointT elements
Returns:
number of occupied voxels

Definition at line 191 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafT , typename BranchT , typename OctreeT >
int pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getOccupiedVoxelCentersRecursive ( const BranchNode node_arg,
const OctreeKey key_arg,
AlignedPointTVector voxelCenterList_arg 
) const [protected]

Recursively search the tree for all leaf nodes and return a vector of voxel centers.

Parameters:
[in]node_argcurrent octree node to be explored
[in]key_argoctree key addressing a leaf node.
[out]voxelCenterList_argresults are written to this vector of PointT elements
Returns:
number of voxels found

Definition at line 713 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafT , typename BranchT , typename OctreeT >
const PointT & pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getPointByIndex ( const unsigned int  index_arg) const [protected]

Get point at index from input pointcloud dataset.

Parameters:
[in]index_argindex representing the point in the dataset given by setInputCloud
Returns:
PointT from input pointcloud dataset

Definition at line 527 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getResolution ( ) const [inline]

Get octree voxel resolution.

Returns:
voxel resolution at lowest tree level

Definition at line 193 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
unsigned int pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getTreeDepth ( ) const [inline]

Get the maximum depth of the octree.

Returns:
depth_arg: maximum depth of octree

Definition at line 201 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getVoxelBounds ( OctreeIteratorBase< int, OctreeT > &  iterator,
Eigen::Vector3f &  min_pt,
Eigen::Vector3f &  max_pt 
) [inline]

Generate bounds of the current voxel of an octree iterator.

Parameters:
[in]iterator,:octree iterator
[out]min_ptlower bound of voxel
[out]max_ptupper bound of voxel

Definition at line 393 of file octree_pointcloud.h.

template<typename PointT , typename LeafT , typename BranchT , typename OctreeT >
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getVoxelSquaredDiameter ( unsigned int  treeDepth_arg) const

Calculates the squared diameter of a voxel at given tree depth.

Parameters:
[in]treeDepth_argdepth/level in octree
Returns:
squared diameter

Definition at line 705 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getVoxelSquaredDiameter ( ) const [inline]

Calculates the squared diameter of a voxel at leaf depth.

Returns:
squared diameter

Definition at line 368 of file octree_pointcloud.h.

template<typename PointT , typename LeafT , typename BranchT , typename OctreeT >
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getVoxelSquaredSideLen ( unsigned int  treeDepth_arg) const

Calculates the squared voxel cube side length at given tree depth.

Parameters:
[in]treeDepth_argdepth/level in octree
Returns:
squared voxel cube side length

Definition at line 690 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getVoxelSquaredSideLen ( ) const [inline]

Calculates the squared voxel cube side length at leaf level.

Returns:
squared voxel cube side length

Definition at line 383 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
bool pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::isPointWithinBoundingBox ( const PointT pointIdx_arg) const [inline, protected]

Checks if given point is within the bounding box of the octree.

Parameters:
[in]pointIdx_argpoint to be checked for bounding box violations
Returns:
"true" - no bound violation

Definition at line 440 of file octree_pointcloud.h.

template<typename PointT, typename LeafT , typename BranchT , typename OctreeT >
bool pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::isVoxelOccupiedAtPoint ( const PointT point_arg) const

Check if voxel at given point exist.

Parameters:
[in]point_argpoint to be checked
Returns:
"true" if voxel exist; "false" otherwise

Definition at line 131 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafT , typename BranchT , typename OctreeT >
bool pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::isVoxelOccupiedAtPoint ( const double  pointX_arg,
const double  pointY_arg,
const double  pointZ_arg 
) const

Check if voxel at given point coordinates exist.

Parameters:
[in]pointX_argX coordinate of point to be checked
[in]pointY_argY coordinate of point to be checked
[in]pointZ_argZ coordinate of point to be checked
Returns:
"true" if voxel exist; "false" otherwise

Definition at line 155 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafT , typename BranchT , typename OctreeT >
bool pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::isVoxelOccupiedAtPoint ( const int &  pointIdx_arg) const

Check if voxel at given point from input cloud exist.

Parameters:
[in]pointIdx_argpoint to be checked
Returns:
"true" if voxel exist; "false" otherwise

Definition at line 144 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::setEpsilon ( double  eps) [inline]

Set the search epsilon precision (error bound) for nearest neighbors searches.

Parameters:
[in]epsprecision (error bound) for nearest neighbors searches

Definition at line 166 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::setInputCloud ( const PointCloudConstPtr cloud_arg,
const IndicesConstPtr indices_arg = IndicesConstPtr () 
) [inline]

Provide a pointer to the input data set.

Parameters:
[in]cloud_argthe const boost shared pointer to a PointCloud message
[in]indices_argthe point indices subset that is to be used from cloud - if 0 the whole point cloud is used

Definition at line 138 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::setResolution ( double  resolution_arg) [inline]

Set/change the octree voxel resolution.

Parameters:
[in]resolution_argside length of voxels at lowest tree level

Definition at line 180 of file octree_pointcloud.h.


Friends And Related Function Documentation

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
friend class OctreeBreadthFirstIterator< int, OctreeT > [friend]

Definition at line 85 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
friend class OctreeDepthFirstIterator< int, OctreeT > [friend]

Definition at line 84 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
friend class OctreeIteratorBase< int, OctreeT > [friend]

Definition at line 83 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
friend class OctreeLeafNodeIterator< int, OctreeT > [friend]

Definition at line 86 of file octree_pointcloud.h.


Member Data Documentation

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
bool pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::boundingBoxDefined_ [protected]

Flag indicating if octree has defined bounding box.

Definition at line 539 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::epsilon_ [protected]

Epsilon precision (error bound) for nearest neighbors searches.

Definition at line 523 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
IndicesConstPtr pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::indices_ [protected]

A pointer to the vector of point indices to use.

Definition at line 520 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
PointCloudConstPtr pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::input_ [protected]

Pointer to input point cloud dataset.

Definition at line 517 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::maxX_ [protected]

Definition at line 530 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::maxY_ [protected]

Definition at line 533 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::maxZ_ [protected]

Definition at line 536 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::minX_ [protected]

Definition at line 529 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::minY_ [protected]

Definition at line 532 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::minZ_ [protected]

Definition at line 535 of file octree_pointcloud.h.

template<typename PointT, typename LeafT = OctreeContainerDataTVector<int>, typename BranchT = OctreeContainerEmpty<int>, typename OctreeT = OctreeBase<int, LeafT, BranchT>>
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::resolution_ [protected]

Octree resolution.

Definition at line 526 of file octree_pointcloud.h.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:20:18