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

Octree pointcloud class More...

#include <octree_pointcloud.h>

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

List of all members.

Public Types

typedef std::vector< PointT,
Eigen::aligned_allocator
< PointT > > 
AlignedPointTVector
typedef std::vector< PointXYZ,
Eigen::aligned_allocator
< PointXYZ > > 
AlignedPointXYZVector
typedef OctreeT Base
typedef OctreeT::BranchNode BranchNode
typedef
OctreeBreadthFirstIterator
< OctreeT
BreadthFirstIterator
typedef const
OctreeBreadthFirstIterator
< OctreeT
ConstBreadthFirstIterator
typedef const
OctreeDepthFirstIterator
< OctreeT
ConstDepthFirstIterator
typedef const
OctreeDepthFirstIterator
< OctreeT
ConstIterator
typedef const
OctreeLeafNodeIterator
< OctreeT
ConstLeafNodeIterator
typedef boost::shared_ptr
< const OctreePointCloud
< PointT, LeafContainerT,
BranchContainerT, OctreeT > > 
ConstPtr
typedef
OctreeDepthFirstIterator
< OctreeT
DepthFirstIterator
typedef boost::shared_ptr
< const std::vector< int > > 
IndicesConstPtr
typedef boost::shared_ptr
< std::vector< int > > 
IndicesPtr
typedef
OctreeDepthFirstIterator
< OctreeT
Iterator
typedef OctreeT::LeafNode LeafNode
typedef OctreeLeafNodeIterator
< 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,
LeafContainerT,
BranchContainerT, OctreeT > > 
Ptr
typedef OctreePointCloud
< PointT, LeafContainerT,
BranchContainerT, OctreeBase
< LeafContainerT > > 
SingleBuffer

Public Member Functions

void addPointFromCloud (const int point_idx_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 min_x_arg, const double min_y_arg, const double min_z_arg, const double max_x_arg, const double max_y_arg, const double max_z_arg)
 Define bounding box for octree.
void defineBoundingBox (const double max_x_arg, const double max_y_arg, const double max_z_arg)
 Define bounding box for octree.
void defineBoundingBox (const double cubeLen_arg)
 Define bounding box cube for octree.
void deleteTree ()
 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 &point_idx_arg)
 Delete leaf node / voxel at given point from input cloud.
void enableDynamicDepth (size_t maxObjsPerLeaf)
 Enable dynamic octree structure.
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 &min_x_arg, double &min_y_arg, double &min_z_arg, double &max_x_arg, double &max_y_arg, double &max_z_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 &voxel_center_list_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< OctreeT > &iterator, Eigen::Vector3f &min_pt, Eigen::Vector3f &max_pt)
 Generate bounds of the current voxel of an octree iterator.
double getVoxelSquaredDiameter (unsigned int tree_depth_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 tree_depth_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 point_x_arg, const double point_y_arg, const double point_z_arg) const
 Check if voxel at given point coordinates exist.
bool isVoxelOccupiedAtPoint (const int &point_idx_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

virtual void addPointIdx (const int point_idx_arg)
 Add point at index from input pointcloud dataset to octree.
void adoptBoundingBoxToPoint (const PointT &point_idx_arg)
 Grow the bounding box/octree until point fits.
void expandLeafNode (LeafNode *leaf_node, BranchNode *parent_branch, unsigned char child_idx, unsigned int depth_mask)
 Add point at index from input pointcloud dataset to octree.
LeafContainerT * 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 point_x_arg, const double point_y_arg, const double point_z_arg, OctreeKey &key_arg) const
 Generate octree key for voxel at a given point.
void genVoxelBoundsFromOctreeKey (const OctreeKey &key_arg, unsigned int tree_depth_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 tree_depth_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 &voxel_center_list_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 &point_idx_arg) const
 Checks if given point is within the bounding box of the octree.

Protected Attributes

bool bounding_box_defined_
 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.
std::size_t max_objs_per_leaf_
 Amount of DataT objects per leafNode before expanding branch.
double max_x_
double max_y_
double max_z_
double min_x_
double min_y_
double min_z_
double resolution_
 Octree resolution.

Friends

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

Detailed Description

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
class pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, 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: LeafContainerT: leaf node container (
typename: BranchContainerT: branch node container
typename: OctreeT: octree implementation ()
Author:
Julius Kammerl (julius@kammerl.de)

Definition at line 77 of file octree_pointcloud.h.


Member Typedef Documentation

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
typedef std::vector<PointT, Eigen::aligned_allocator<PointT> > pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::AlignedPointTVector
template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
typedef std::vector<PointXYZ, Eigen::aligned_allocator<PointXYZ> > pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::AlignedPointXYZVector

Definition at line 134 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
typedef OctreeT pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::Base

Definition at line 86 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
typedef OctreeT::BranchNode pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::BranchNode
template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
typedef OctreeBreadthFirstIterator<OctreeT> pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::BreadthFirstIterator

Definition at line 104 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
typedef const OctreeBreadthFirstIterator<OctreeT> pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::ConstBreadthFirstIterator

Definition at line 105 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
typedef const OctreeDepthFirstIterator<OctreeT> pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::ConstDepthFirstIterator

Definition at line 101 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
typedef const OctreeDepthFirstIterator<OctreeT> pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::ConstIterator
template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
typedef const OctreeLeafNodeIterator<OctreeT> pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::ConstLeafNodeIterator
template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
typedef boost::shared_ptr<const OctreePointCloud<PointT, LeafContainerT, BranchContainerT, OctreeT> > pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::ConstPtr
template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
typedef OctreeDepthFirstIterator<OctreeT> pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::DepthFirstIterator

Definition at line 100 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
typedef boost::shared_ptr<const std::vector<int> > pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::IndicesConstPtr
template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
typedef boost::shared_ptr<std::vector<int> > pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::IndicesPtr
template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
typedef OctreeDepthFirstIterator<OctreeT> pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::Iterator
template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
typedef OctreeT::LeafNode pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::LeafNode
template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
typedef OctreeLeafNodeIterator<OctreeT> pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::LeafNodeIterator
template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
typedef pcl::PointCloud<PointT> pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::PointCloud
template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
typedef boost::shared_ptr<const PointCloud> pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::PointCloudConstPtr
template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
typedef boost::shared_ptr<PointCloud> pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::PointCloudPtr
template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
typedef boost::shared_ptr<OctreePointCloud<PointT, LeafContainerT, BranchContainerT, OctreeT> > pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::Ptr
template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
typedef OctreePointCloud<PointT, LeafContainerT, BranchContainerT, OctreeBase<LeafContainerT> > pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::SingleBuffer

Constructor & Destructor Documentation

template<typename PointT , typename LeafContainerT , typename BranchContainerT , typename OctreeT >
OctreePointCloud::OctreePointCloud ( const double  resolution_arg)

Octree pointcloud constructor.

Parameters:
[in]resolution_argoctree resolution at lowest octree level

Definition at line 51 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafContainerT , typename BranchContainerT , typename OctreeT >
OctreePointCloud::~OctreePointCloud ( ) [virtual]

Empty deconstructor.

Definition at line 61 of file octree_pointcloud.hpp.


Member Function Documentation

template<typename PointT , typename LeafContainerT , typename BranchContainerT , typename OctreeT >
void OctreePointCloud::addPointFromCloud ( const int  point_idx_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]point_idx_argindex of point to be added
[in]indices_argpointer to indices vector of the dataset (given by setInputCloud)

Definition at line 99 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafContainerT , typename BranchContainerT , typename OctreeT >
void OctreePointCloud::addPointIdx ( const int  point_idx_arg) [protected, virtual]

Add point at index from input pointcloud dataset to octree.

Parameters:
[in]point_idx_argthe index representing the point in the dataset given by setInputCloud to be added

Reimplemented in pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >, pcl::octree::OctreePointCloudVoxelCentroid< PointT, LeafContainerT, BranchContainerT >, pcl::octree::OctreePointCloudVoxelCentroid< pcl::PointXYZ >, and pcl::io::OctreePointCloudCompression< PointT, LeafT, BranchT, OctreeT >.

Definition at line 558 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafContainerT , typename BranchContainerT , typename OctreeT >
void OctreePointCloud::addPointsFromInputCloud ( )

Add points from input point cloud to octree.

Reimplemented in pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >.

Definition at line 67 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafContainerT , typename BranchContainerT , typename OctreeT >
void OctreePointCloud::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 108 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafContainerT , typename BranchContainerT , typename OctreeT >
void OctreePointCloud::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 119 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafContainerT , typename BranchContainerT , typename OctreeT >
void OctreePointCloud::adoptBoundingBoxToPoint ( const PointT point_idx_arg) [protected]

Grow the bounding box/octree until point fits.

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

Definition at line 419 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafContainerT , typename BranchContainerT , typename OctreeT >
void OctreePointCloud::defineBoundingBox ( )

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

Definition at line 267 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafContainerT , typename BranchContainerT , typename OctreeT >
void OctreePointCloud::defineBoundingBox ( const double  min_x_arg,
const double  min_y_arg,
const double  min_z_arg,
const double  max_x_arg,
const double  max_y_arg,
const double  max_z_arg 
)

Define bounding box for octree.

Note:
Bounding box cannot be changed once the octree contains elements.
Parameters:
[in]min_x_argX coordinate of lower bounding box corner
[in]min_y_argY coordinate of lower bounding box corner
[in]min_z_argZ coordinate of lower bounding box corner
[in]max_x_argX coordinate of upper bounding box corner
[in]max_y_argY coordinate of upper bounding box corner
[in]max_z_argZ coordinate of upper bounding box corner

Definition at line 296 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafContainerT , typename BranchContainerT , typename OctreeT >
void OctreePointCloud::defineBoundingBox ( const double  max_x_arg,
const double  max_y_arg,
const double  max_z_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]max_x_argX coordinate of upper bounding box corner
[in]max_y_argY coordinate of upper bounding box corner
[in]max_z_argZ coordinate of upper bounding box corner

Definition at line 335 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafContainerT , typename BranchContainerT , typename OctreeT >
void OctreePointCloud::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 370 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
void pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::deleteTree ( ) [inline]

Delete the octree structure and its leaf nodes.

Definition at line 241 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT , typename BranchContainerT , typename OctreeT >
void OctreePointCloud::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 169 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafContainerT , typename BranchContainerT , typename OctreeT >
void OctreePointCloud::deleteVoxelAtPoint ( const int &  point_idx_arg)

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

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

Definition at line 181 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
void pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::enableDynamicDepth ( size_t  maxObjsPerLeaf) [inline]

Enable dynamic octree structure.

Note:
Leaf nodes are kept as close to the root as possible and are only expanded if the number of DataT objects within a leaf node exceeds a fixed limit.
Parameters:
maxObjsPerLeaf,:maximum number of DataT objects per leaf

Definition at line 400 of file octree_pointcloud.h.

template<typename PointT , typename LeafContainerT , typename BranchContainerT , typename OctreeT >
void OctreePointCloud::expandLeafNode ( LeafNode leaf_node,
BranchNode parent_branch,
unsigned char  child_idx,
unsigned int  depth_mask 
) [protected]

Add point at index from input pointcloud dataset to octree.

Parameters:
[in]leaf_nodeto be expanded
[in]parent_branchparent of leaf node to be expanded
[in]child_idxchild index of leaf node (in parent branch)
[in]depth_maskof leaf node to be expanded

Definition at line 509 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
LeafContainerT* pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::findLeafAtPoint ( const PointT point_arg) const [inline, 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 438 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT , typename BranchContainerT , typename OctreeT >
void OctreePointCloud::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 709 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafContainerT , typename BranchContainerT , typename OctreeT >
bool OctreePointCloud::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 697 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafContainerT , typename BranchContainerT , typename OctreeT >
void OctreePointCloud::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

Reimplemented in pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >.

Definition at line 670 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafContainerT , typename BranchContainerT , typename OctreeT >
void OctreePointCloud::genOctreeKeyforPoint ( const double  point_x_arg,
const double  point_y_arg,
const double  point_z_arg,
OctreeKey key_arg 
) const [protected]

Generate octree key for voxel at a given point.

Parameters:
[in]point_x_argX coordinate of point addressing a voxel
[in]point_y_argY coordinate of point addressing a voxel
[in]point_z_argZ coordinate of point addressing a voxel
[out]key_argwrite octree key to this reference

Definition at line 681 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafContainerT , typename BranchContainerT , typename OctreeT >
void OctreePointCloud::genVoxelBoundsFromOctreeKey ( const OctreeKey key_arg,
unsigned int  tree_depth_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]tree_depth_argoctree depth of query voxel
[out]min_ptlower bound of voxel
[out]max_ptupper bound of voxel

Definition at line 732 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafContainerT , typename BranchContainerT , typename OctreeT >
void OctreePointCloud::genVoxelCenterFromOctreeKey ( const OctreeKey key_arg,
unsigned int  tree_depth_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]tree_depth_argoctree depth of query voxel
[out]point_argwrite leaf node center point to this reference

Definition at line 719 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafContainerT , typename BranchContainerT , typename OctreeT >
int OctreePointCloud::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 206 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafContainerT , typename BranchContainerT , typename OctreeT >
void OctreePointCloud::getBoundingBox ( double &  min_x_arg,
double &  min_y_arg,
double &  min_z_arg,
double &  max_x_arg,
double &  max_y_arg,
double &  max_z_arg 
) const

Get bounding box for octree.

Note:
Bounding box cannot be changed once the octree contains elements.
Parameters:
[in]min_x_argX coordinate of lower bounding box corner
[in]min_y_argY coordinate of lower bounding box corner
[in]min_z_argZ coordinate of lower bounding box corner
[in]max_x_argX coordinate of upper bounding box corner
[in]max_y_argY coordinate of upper bounding box corner
[in]max_z_argZ coordinate of upper bounding box corner

Definition at line 402 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
double pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, 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 LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
IndicesConstPtr const pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, 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 LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
PointCloudConstPtr pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, 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 LeafContainerT , typename BranchContainerT , typename OctreeT >
void OctreePointCloud::getKeyBitSize ( ) [protected]

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

Definition at line 611 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafContainerT , typename BranchContainerT , typename OctreeT >
int OctreePointCloud::getOccupiedVoxelCenters ( AlignedPointTVector voxel_center_list_arg) const

Get a PointT vector of centers of all occupied voxels.

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

Definition at line 192 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafContainerT , typename BranchContainerT , typename OctreeT >
int OctreePointCloud::getOccupiedVoxelCentersRecursive ( const BranchNode node_arg,
const OctreeKey key_arg,
AlignedPointTVector voxel_center_list_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]voxel_center_list_argresults are written to this vector of PointT elements
Returns:
number of voxels found

Definition at line 776 of file octree_pointcloud.hpp.

template<typename PointT , typename LeafContainerT , typename BranchContainerT , typename OctreeT >
const PointT & OctreePointCloud::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 602 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
double pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, 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 LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
unsigned int pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, 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 LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
void pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::getVoxelBounds ( OctreeIteratorBase< 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 389 of file octree_pointcloud.h.

template<typename PointT , typename LeafContainerT , typename BranchContainerT , typename OctreeT >
double OctreePointCloud::getVoxelSquaredDiameter ( unsigned int  tree_depth_arg) const

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

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

Definition at line 768 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
double pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::getVoxelSquaredDiameter ( ) const [inline]

Calculates the squared diameter of a voxel at leaf depth.

Returns:
squared diameter

Definition at line 363 of file octree_pointcloud.h.

template<typename PointT , typename LeafContainerT , typename BranchContainerT , typename OctreeT >
double OctreePointCloud::getVoxelSquaredSideLen ( unsigned int  tree_depth_arg) const

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

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

Definition at line 753 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
double pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::getVoxelSquaredSideLen ( ) const [inline]

Calculates the squared voxel cube side length at leaf level.

Returns:
squared voxel cube side length

Definition at line 378 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
bool pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::isPointWithinBoundingBox ( const PointT point_idx_arg) const [inline, protected]

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

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

Definition at line 466 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT , typename BranchContainerT , typename OctreeT >
bool OctreePointCloud::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 132 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafContainerT , typename BranchContainerT , typename OctreeT >
bool OctreePointCloud::isVoxelOccupiedAtPoint ( const double  point_x_arg,
const double  point_y_arg,
const double  point_z_arg 
) const

Check if voxel at given point coordinates exist.

Parameters:
[in]point_x_argX coordinate of point to be checked
[in]point_y_argY coordinate of point to be checked
[in]point_z_argZ coordinate of point to be checked
Returns:
"true" if voxel exist; "false" otherwise

Definition at line 156 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafContainerT , typename BranchContainerT , typename OctreeT >
bool OctreePointCloud::isVoxelOccupiedAtPoint ( const int &  point_idx_arg) const

Check if voxel at given point from input cloud exist.

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

Definition at line 145 of file octree_pointcloud.hpp.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
void pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, 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 LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
void pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, 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 140 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
void pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, 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 LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
friend class OctreeBreadthFirstIterator< OctreeT > [friend]

Definition at line 82 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
friend class OctreeDepthFirstIterator< OctreeT > [friend]

Definition at line 81 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
friend class OctreeIteratorBase< OctreeT > [friend]

Definition at line 80 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
friend class OctreeLeafNodeIterator< OctreeT > [friend]

Definition at line 83 of file octree_pointcloud.h.


Member Data Documentation

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
bool pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::bounding_box_defined_ [protected]

Flag indicating if octree has defined bounding box.

Definition at line 565 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
double pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::epsilon_ [protected]

Epsilon precision (error bound) for nearest neighbors searches.

Definition at line 549 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
IndicesConstPtr pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::indices_ [protected]

A pointer to the vector of point indices to use.

Definition at line 546 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
PointCloudConstPtr pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::input_ [protected]

Pointer to input point cloud dataset.

Definition at line 543 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
std::size_t pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::max_objs_per_leaf_ [protected]

Amount of DataT objects per leafNode before expanding branch.

Note:
zero indicates a fixed/maximum depth octree structure

Definition at line 570 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
double pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::max_x_ [protected]

Definition at line 556 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
double pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::max_y_ [protected]

Definition at line 559 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
double pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::max_z_ [protected]

Definition at line 562 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
double pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::min_x_ [protected]

Definition at line 555 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
double pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::min_y_ [protected]

Definition at line 558 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
double pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::min_z_ [protected]

Definition at line 561 of file octree_pointcloud.h.

template<typename PointT, typename LeafContainerT = OctreeContainerPointIndices, typename BranchContainerT = OctreeContainerEmpty, typename OctreeT = OctreeBase<LeafContainerT, BranchContainerT>>
double pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::resolution_ [protected]

Octree resolution.

Definition at line 552 of file octree_pointcloud.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