, including all inherited members.
addData(unsigned int idxX_arg, unsigned int idxY_arg, unsigned int idxZ_arg, const int &data_arg) | pcl::octree::OctreeBase< int, LeafT, BranchT > | |
addData(const OctreeKey &key_arg, const int &data_arg) | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline, protected] |
addDataToLeafRecursive(const OctreeKey &key_arg, unsigned int depthMask_arg, const int &data_arg, BranchNode *branch_arg) | pcl::octree::OctreeBase< int, LeafT, BranchT > | [protected] |
addPointFromCloud(const int pointIdx_arg, IndicesPtr indices_arg) | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
addPointIdx(const int pointIdx_arg) | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [protected] |
addPointsFromInputCloud() | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
addPointToCloud(const PointT &point_arg, PointCloudPtr cloud_arg) | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
addPointToCloud(const PointT &point_arg, PointCloudPtr cloud_arg, IndicesPtr indices_arg) | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
adoptBoundingBoxToPoint(const PointT &pointIdx_arg) | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [protected] |
AlignedPointTVector typedef | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | |
approxNearestSearch(const PointCloud &cloud, int query_index, int &result_index, float &sqr_distance) | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | [inline] |
approxNearestSearch(const PointT &p_q, int &result_index, float &sqr_distance) | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | |
approxNearestSearch(int query_index, int &result_index, float &sqr_distance) | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | |
approxNearestSearchRecursive(const PointT &point, const BranchNode *node, const OctreeKey &key, unsigned int treeDepth, int &result_index, float &sqr_distance) | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | [protected] |
Base typedef | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
boundingBoxDefined_ | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [protected] |
boxSearch(const Eigen::Vector3f &min_pt, const Eigen::Vector3f &max_pt, std::vector< int > &k_indices) const | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | |
boxSearchRecursive(const Eigen::Vector3f &min_pt, const Eigen::Vector3f &max_pt, const BranchNode *node, const OctreeKey &key, unsigned int treeDepth, std::vector< int > &k_indices) const | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | [protected] |
branchCount_ | pcl::octree::OctreeBase< int, LeafT, BranchT > | [protected] |
branchHasChild(const BranchNode &branch_arg, unsigned char childIdx_arg) const | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline, protected] |
BranchNode typedef | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | |
branchNodePool_ | pcl::octree::OctreeBase< int, LeafT, BranchT > | [protected] |
branchReset(BranchNode &branch_arg) | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline, protected] |
BreadthFirstIterator typedef | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
ConstBreadthFirstIterator typedef | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
ConstDepthFirstIterator typedef | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
ConstIterator typedef | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
ConstLeafNodeIterator typedef | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
ConstPtr typedef | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | |
createBranchChild(BranchNode &branch_arg, unsigned char childIdx_arg, BranchNode *&newBranchChild_arg) | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline, protected] |
createLeafChild(BranchNode &branch_arg, unsigned char childIdx_arg, LeafNode *&newLeafChild_arg) | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline, protected] |
defineBoundingBox() | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
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) | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
defineBoundingBox(const double maxX_arg, const double maxY_arg, const double maxZ_arg) | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
defineBoundingBox(const double cubeLen_arg) | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
deleteBranch(BranchNode &branch_arg) | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline, protected] |
deleteBranchChild(BranchNode &branch_arg, unsigned char childIdx_arg) | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline, protected] |
deleteLeafRecursive(const OctreeKey &key_arg, unsigned int depthMask_arg, BranchNode *branch_arg) | pcl::octree::OctreeBase< int, LeafT, BranchT > | [protected] |
deleteTree(bool freeMemory_arg=false) | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [inline] |
deleteVoxelAtPoint(const PointT &point_arg) | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
deleteVoxelAtPoint(const int &pointIdx_arg) | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
DepthFirstIterator typedef | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
depthMask_ | pcl::octree::OctreeBase< int, LeafT, BranchT > | [protected] |
deserializeTree(std::vector< char > &binaryTreeIn_arg) | pcl::octree::OctreeBase< int, LeafT, BranchT > | |
deserializeTree(std::vector< char > &binaryTreeIn_arg, std::vector< int > &dataVector_arg) | pcl::octree::OctreeBase< int, LeafT, BranchT > | |
deserializeTreeCallback(LeafNode &, const OctreeKey &) | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline, protected, virtual] |
deserializeTreeRecursive(BranchNode *branch_arg, unsigned int depthMask_arg, OctreeKey &key_arg, typename std::vector< char >::const_iterator &binaryTreeIT_arg, typename std::vector< char >::const_iterator &binaryTreeIT_End_arg, typename std::vector< int >::const_iterator *dataVectorIterator_arg, typename std::vector< int >::const_iterator *dataVectorEndIterator_arg) | pcl::octree::OctreeBase< int, LeafT, BranchT > | [protected] |
DoubleBuffer typedef | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
enableDynamicDepth(size_t maxObjsPerLeaf) | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline] |
epsilon_ | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [protected] |
existLeaf(unsigned int idxX_arg, unsigned int idxY_arg, unsigned int idxZ_arg) const | pcl::octree::OctreeBase< int, LeafT, BranchT > | |
existLeaf(const OctreeKey &key_arg) const | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline, protected] |
findLeaf(const OctreeKey &key_arg) const | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline, protected] |
findLeafAtPoint(const PointT &point_arg) const | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [protected] |
findLeafRecursive(const OctreeKey &key_arg, unsigned int depthMask_arg, BranchNode *branch_arg, LeafNode *&result_arg) const | pcl::octree::OctreeBase< int, LeafT, BranchT > | [protected] |
genDataTByOctreeKey(const OctreeKey &, int &) const | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline, protected, virtual] |
genLeafNodeCenterFromOctreeKey(const OctreeKey &key_arg, PointT &point_arg) const | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [protected] |
genOctreeKeyForDataT(const int &data_arg, OctreeKey &key_arg) const | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [protected, virtual] |
genOctreeKeyforPoint(const PointT &point_arg, OctreeKey &key_arg) const | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [protected] |
genOctreeKeyforPoint(const double pointX_arg, const double pointY_arg, const double pointZ_arg, OctreeKey &key_arg) const | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [protected] |
genVoxelBoundsFromOctreeKey(const OctreeKey &key_arg, unsigned int treeDepth_arg, Eigen::Vector3f &min_pt, Eigen::Vector3f &max_pt) const | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [protected] |
genVoxelCenterFromOctreeKey(const OctreeKey &key_arg, unsigned int treeDepth_arg, PointT &point_arg) const | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [protected] |
getApproxIntersectedVoxelCentersBySegment(const Eigen::Vector3f &origin, const Eigen::Vector3f &end, AlignedPointTVector &voxel_center_list, float precision=0.2) | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
getBoundingBox(double &minX_arg, double &minY_arg, double &minZ_arg, double &maxX_arg, double &maxY_arg, double &maxZ_arg) const | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
getBranchBitPattern(const BranchNode &branch_arg) const | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline, protected] |
getBranchChildPtr(const BranchNode &branch_arg, unsigned char childIdx_arg) const | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline, protected] |
getBranchCount() const | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline] |
getData(unsigned int idxX_arg, unsigned int idxY_arg, unsigned int idxZ_arg, int &data_arg) const | pcl::octree::OctreeBase< int, LeafT, BranchT > | |
getDataFromOctreeNode(const OctreeNode *node_arg, int &data_arg) | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline, protected] |
getDataFromOctreeNode(const OctreeNode *node_arg, std::vector< int > &data_arg) | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline, protected] |
getDataSizeFromOctreeNode(const OctreeNode *node_arg) | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline, protected] |
getEpsilon() const | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [inline] |
getFirstIntersectedNode(double minX, double minY, double minZ, double midX, double midY, double midZ) const | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | [inline, protected] |
getIndices() const | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [inline] |
getInputCloud() const | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [inline] |
getIntersectedVoxelCenters(Eigen::Vector3f origin, Eigen::Vector3f direction, AlignedPointTVector &voxelCenterList, int maxVoxelCount=0) const | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | |
getIntersectedVoxelCentersRecursive(double minX, double minY, double minZ, double maxX, double maxY, double maxZ, unsigned char a, const OctreeNode *node, const OctreeKey &key, AlignedPointTVector &voxelCenterList, int maxVoxelCount) const | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | [protected] |
getIntersectedVoxelIndices(Eigen::Vector3f origin, Eigen::Vector3f direction, std::vector< int > &k_indices, int maxVoxelCount=0) const | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | |
getIntersectedVoxelIndicesRecursive(double minX, double minY, double minZ, double maxX, double maxY, double maxZ, unsigned char a, const OctreeNode *node, const OctreeKey &key, std::vector< int > &k_indices, int maxVoxelCount) const | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | [protected] |
getKeyBitSize() | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [protected] |
getKNearestNeighborRecursive(const PointT &point, unsigned int K, const BranchNode *node, const OctreeKey &key, unsigned int treeDepth, const double squaredSearchRadius, std::vector< prioPointQueueEntry > &pointCandidates) const | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | [protected] |
getLeafCount() const | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline] |
getNeighborsWithinRadiusRecursive(const PointT &point, const double radiusSquared, const BranchNode *node, const OctreeKey &key, unsigned int treeDepth, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances, unsigned int max_nn) const | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | [protected] |
getNextIntersectedNode(double x, double y, double z, int a, int b, int c) const | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | [inline, protected] |
getOccupiedVoxelCenters(AlignedPointTVector &voxelCenterList_arg) const | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
getOccupiedVoxelCentersRecursive(const BranchNode *node_arg, const OctreeKey &key_arg, AlignedPointTVector &voxelCenterList_arg) const | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [protected] |
getPointByIndex(const unsigned int index_arg) const | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [protected] |
getResolution() const | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [inline] |
getRootNode() const | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline, protected] |
getTreeDepth() const | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [inline] |
getVoxelBounds(OctreeIteratorBase< int, OctreeBase< int, LeafT, BranchT > > &iterator, Eigen::Vector3f &min_pt, Eigen::Vector3f &max_pt) | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [inline] |
getVoxelSquaredDiameter(unsigned int treeDepth_arg) const | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
getVoxelSquaredDiameter() const | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [inline] |
getVoxelSquaredSideLen(unsigned int treeDepth_arg) const | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
getVoxelSquaredSideLen() const | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [inline] |
indices_ | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [protected] |
IndicesConstPtr typedef | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | |
IndicesPtr typedef | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | |
initIntersectedVoxel(Eigen::Vector3f &origin, Eigen::Vector3f &direction, double &minX, double &minY, double &minZ, double &maxX, double &maxY, double &maxZ, unsigned char &a) const | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | [inline, protected] |
input_ | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [protected] |
isPointWithinBoundingBox(const PointT &pointIdx_arg) const | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [inline, protected] |
isVoxelOccupiedAtPoint(const PointT &point_arg) const | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
isVoxelOccupiedAtPoint(const double pointX_arg, const double pointY_arg, const double pointZ_arg) const | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
isVoxelOccupiedAtPoint(const int &pointIdx_arg) const | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
Iterator typedef | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
leafCount_ | pcl::octree::OctreeBase< int, LeafT, BranchT > | [protected] |
LeafNode typedef | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | |
LeafNodeIterator typedef | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
leafNodePool_ | pcl::octree::OctreeBase< int, LeafT, BranchT > | [protected] |
Log2(double n_arg) | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline, protected] |
maxKey_ | pcl::octree::OctreeBase< int, LeafT, BranchT > | [protected] |
maxObjsPerLeaf_ | pcl::octree::OctreeBase< int, LeafT, BranchT > | [protected] |
maxX_ | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [protected] |
maxY_ | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [protected] |
maxZ_ | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [protected] |
minX_ | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [protected] |
minY_ | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [protected] |
minZ_ | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [protected] |
MultipleObjsLeafContainer typedef | pcl::octree::OctreeBase< int, LeafT, BranchT > | |
nearestKSearch(const PointCloud &cloud, int index, int k, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances) | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | [inline] |
nearestKSearch(const PointT &p_q, int k, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances) | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | |
nearestKSearch(int index, int k, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances) | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | |
objectCount_ | pcl::octree::OctreeBase< int, LeafT, BranchT > | [protected] |
OctreeBase() | pcl::octree::OctreeBase< int, LeafT, BranchT > | |
OctreeBase(const OctreeBase &source) | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline] |
OctreeBreadthFirstIterator< DataT, OctreeT > class | pcl::octree::OctreeBase< int, LeafT, BranchT > | [friend] |
octreeCanResize() | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline, protected] |
octreeDepth_ | pcl::octree::OctreeBase< int, LeafT, BranchT > | [protected] |
OctreeDepthFirstIterator< DataT, OctreeT > class | pcl::octree::OctreeBase< int, LeafT, BranchT > | [friend] |
OctreeIteratorBase< DataT, OctreeT > class | pcl::octree::OctreeBase< int, LeafT, BranchT > | [friend] |
OctreeLeafNodeIterator< DataT, OctreeT > class | pcl::octree::OctreeBase< int, LeafT, BranchT > | [friend] |
OctreePointCloud(const double resolution_arg) | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
OctreePointCloudSearch(const double resolution) | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | [inline] |
OctreeT typedef | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | |
operator=(const OctreeBase &source) | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline] |
PointCloud typedef | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | |
PointCloudConstPtr typedef | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | |
PointCloudPtr typedef | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | |
pointSquaredDist(const PointT &pointA, const PointT &pointB) const | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | [protected] |
poolCleanUp() | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline, protected] |
Ptr typedef | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | |
radiusSearch(const PointCloud &cloud, int index, double radius, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances, unsigned int max_nn=0) | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | [inline] |
radiusSearch(const PointT &p_q, const double radius, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances, unsigned int max_nn=0) const | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | |
radiusSearch(int index, const double radius, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances, unsigned int max_nn=0) const | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | |
removeLeaf(unsigned int idxX_arg, unsigned int idxY_arg, unsigned int idxZ_arg) | pcl::octree::OctreeBase< int, LeafT, BranchT > | |
removeLeaf(const OctreeKey &key_arg) | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline, protected] |
resolution_ | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [protected] |
rootNode_ | pcl::octree::OctreeBase< int, LeafT, BranchT > | [protected] |
serializeLeafs(std::vector< int > &dataVector_arg) | pcl::octree::OctreeBase< int, LeafT, BranchT > | |
serializeTree(std::vector< char > &binaryTreeOut_arg) | pcl::octree::OctreeBase< int, LeafT, BranchT > | |
serializeTree(std::vector< char > &binaryTreeOut_arg, std::vector< int > &dataVector_arg) | pcl::octree::OctreeBase< int, LeafT, BranchT > | |
serializeTreeCallback(const LeafNode &, const OctreeKey &) const | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline, protected, virtual] |
serializeTreeRecursive(const BranchNode *branch_arg, OctreeKey &key_arg, std::vector< char > *binaryTreeOut_arg, typename std::vector< int > *dataVector_arg) const | pcl::octree::OctreeBase< int, LeafT, BranchT > | [protected] |
setBranchChildPtr(BranchNode &branch_arg, unsigned char childIdx_arg, OctreeNode *newChild_arg) | pcl::octree::OctreeBase< int, LeafT, BranchT > | [inline, protected] |
setEpsilon(double eps) | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [inline] |
setInputCloud(const PointCloudConstPtr &cloud_arg, const IndicesConstPtr &indices_arg=IndicesConstPtr()) | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [inline] |
setMaxVoxelIndex(unsigned int maxVoxelIndex_arg) | pcl::octree::OctreeBase< int, LeafT, BranchT > | |
setResolution(double resolution_arg) | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [inline] |
setTreeDepth(unsigned int depth_arg) | pcl::octree::OctreeBase< int, LeafT, BranchT > | |
SingleBuffer typedef | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | |
SingleObjLeafContainer typedef | pcl::octree::OctreeBase< int, LeafT, BranchT > | |
voxelSearch(const PointT &point, std::vector< int > &pointIdx_data) | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | |
voxelSearch(const int index, std::vector< int > &pointIdx_data) | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | |
~OctreeBase() | pcl::octree::OctreeBase< int, LeafT, BranchT > | [virtual] |
~OctreePointCloud() | pcl::octree::OctreePointCloud< PointT, LeafT, BranchT > | [virtual] |
~OctreePointCloudSearch() | pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT > | [inline, virtual] |