, including all inherited members.
| addPointFromCloud(const int point_idx_arg, IndicesPtr indices_arg) | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| addPointIdx(const int point_idx_arg) | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [protected, virtual] |
| addPointsFromInputCloud() | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| addPointToCloud(const PointT &point_arg, PointCloudPtr cloud_arg) | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| addPointToCloud(const PointT &point_arg, PointCloudPtr cloud_arg, IndicesPtr indices_arg) | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| adoptBoundingBoxToPoint(const PointT &point_idx_arg) | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [protected] |
| AlignedPointTVector typedef | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | |
| AlignedPointXYZVector typedef | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| approxNearestSearch(const PointCloud &cloud, int query_index, int &result_index, float &sqr_distance) | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | [inline] |
| approxNearestSearch(const PointT &p_q, int &result_index, float &sqr_distance) | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | |
| approxNearestSearch(int query_index, int &result_index, float &sqr_distance) | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | |
| approxNearestSearchRecursive(const PointT &point, const BranchNode *node, const OctreeKey &key, unsigned int tree_depth, int &result_index, float &sqr_distance) | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | [protected] |
| Base typedef | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| begin(unsigned int max_depth_arg=0) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline] |
| bounding_box_defined_ | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [protected] |
| boxSearch(const Eigen::Vector3f &min_pt, const Eigen::Vector3f &max_pt, std::vector< int > &k_indices) const | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | |
| boxSearchRecursive(const Eigen::Vector3f &min_pt, const Eigen::Vector3f &max_pt, const BranchNode *node, const OctreeKey &key, unsigned int tree_depth, std::vector< int > &k_indices) const | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | [protected] |
| branch_count_ | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [protected] |
| BranchContainer typedef | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | |
| branchHasChild(const BranchNode &branch_arg, unsigned char child_idx_arg) const | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline, protected] |
| BranchNode typedef | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | |
| breadth_begin(unsigned int max_depth_arg=0) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline] |
| breadth_end() | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline] |
| BreadthFirstIterator typedef | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| ConstBreadthFirstIterator typedef | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| ConstDepthFirstIterator typedef | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| ConstIterator typedef | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| ConstLeafNodeIterator typedef | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| ConstPtr typedef | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | |
| createBranchChild(BranchNode &branch_arg, unsigned char child_idx_arg) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline, protected] |
| createLeaf(unsigned int idx_x_arg, unsigned int idx_y_arg, unsigned int idx_z_arg) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | |
| createLeaf(const OctreeKey &key_arg) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline, protected] |
| createLeafChild(BranchNode &branch_arg, unsigned char child_idx_arg) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline, protected] |
| createLeafRecursive(const OctreeKey &key_arg, unsigned int depth_mask_arg, BranchNode *branch_arg, LeafNode *&return_leaf_arg, BranchNode *&parent_of_leaf_arg) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [protected] |
| defineBoundingBox() | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| 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) | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| defineBoundingBox(const double max_x_arg, const double max_y_arg, const double max_z_arg) | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| defineBoundingBox(const double cubeLen_arg) | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| deleteBranch(BranchNode &branch_arg) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline, protected] |
| deleteBranchChild(BranchNode &branch_arg, unsigned char child_idx_arg) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline, protected] |
| deleteLeafRecursive(const OctreeKey &key_arg, unsigned int depth_mask_arg, BranchNode *branch_arg) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [protected] |
| deleteTree() | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [inline] |
| deleteVoxelAtPoint(const PointT &point_arg) | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| deleteVoxelAtPoint(const int &point_idx_arg) | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| depth_begin(unsigned int max_depth_arg=0) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline] |
| depth_end() | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline] |
| depth_mask_ | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [protected] |
| DepthFirstIterator typedef | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| deserializeTree(std::vector< char > &binary_tree_input_arg) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | |
| deserializeTree(std::vector< char > &binary_tree_input_arg, std::vector< LeafContainerT * > &leaf_container_vector_arg) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | |
| deserializeTreeCallback(LeafContainerT &, const OctreeKey &) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline, protected, virtual] |
| deserializeTreeRecursive(BranchNode *branch_arg, unsigned int depth_mask_arg, OctreeKey &key_arg, typename std::vector< char >::const_iterator &binary_tree_input_it_arg, typename std::vector< char >::const_iterator &binary_tree_input_it_end_arg, typename std::vector< LeafContainerT * >::const_iterator *leaf_container_vector_it_arg, typename std::vector< LeafContainerT * >::const_iterator *leaf_container_vector_it_end_arg) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [protected] |
| dynamic_depth_enabled_ | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [protected] |
| enableDynamicDepth(size_t maxObjsPerLeaf) | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [inline] |
| end() | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline] |
| epsilon_ | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [protected] |
| existLeaf(unsigned int idx_x_arg, unsigned int idx_y_arg, unsigned int idx_z_arg) const | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | |
| existLeaf(const OctreeKey &key_arg) const | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline, protected] |
| expandLeafNode(LeafNode *leaf_node, BranchNode *parent_branch, unsigned char child_idx, unsigned int depth_mask) | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [protected] |
| findLeaf(unsigned int idx_x_arg, unsigned int idx_y_arg, unsigned int idx_z_arg) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | |
| findLeaf(const OctreeKey &key_arg) const | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline, protected] |
| findLeafAtPoint(const PointT &point_arg) const | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [inline, protected] |
| findLeafRecursive(const OctreeKey &key_arg, unsigned int depth_mask_arg, BranchNode *branch_arg, LeafContainerT *&result_arg) const | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [protected] |
| genLeafNodeCenterFromOctreeKey(const OctreeKey &key_arg, PointT &point_arg) const | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [protected] |
| genOctreeKeyForDataT(const int &data_arg, OctreeKey &key_arg) const | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [protected, virtual] |
| genOctreeKeyforPoint(const PointT &point_arg, OctreeKey &key_arg) const | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [protected] |
| genOctreeKeyforPoint(const double point_x_arg, const double point_y_arg, const double point_z_arg, OctreeKey &key_arg) const | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [protected] |
| genVoxelBoundsFromOctreeKey(const OctreeKey &key_arg, unsigned int tree_depth_arg, Eigen::Vector3f &min_pt, Eigen::Vector3f &max_pt) const | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [protected] |
| genVoxelCenterFromOctreeKey(const OctreeKey &key_arg, unsigned int tree_depth_arg, PointT &point_arg) const | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [protected] |
| getApproxIntersectedVoxelCentersBySegment(const Eigen::Vector3f &origin, const Eigen::Vector3f &end, AlignedPointTVector &voxel_center_list, float precision=0.2) | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| 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 | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| getBranchBitPattern(const BranchNode &branch_arg) const | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline, protected] |
| getBranchChildPtr(const BranchNode &branch_arg, unsigned char child_idx_arg) const | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline, protected] |
| getBranchCount() const | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline] |
| getEpsilon() const | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [inline] |
| getFirstIntersectedNode(double min_x, double min_y, double min_z, double mid_x, double mid_y, double mid_z) const | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | [inline, protected] |
| getIndices() const | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [inline] |
| getInputCloud() const | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [inline] |
| getIntersectedVoxelCenters(Eigen::Vector3f origin, Eigen::Vector3f direction, AlignedPointTVector &voxel_center_list, int max_voxel_count=0) const | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | |
| getIntersectedVoxelCentersRecursive(double min_x, double min_y, double min_z, double max_x, double max_y, double max_z, unsigned char a, const OctreeNode *node, const OctreeKey &key, AlignedPointTVector &voxel_center_list, int max_voxel_count) const | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | [protected] |
| getIntersectedVoxelIndices(Eigen::Vector3f origin, Eigen::Vector3f direction, std::vector< int > &k_indices, int max_voxel_count=0) const | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | |
| getIntersectedVoxelIndicesRecursive(double min_x, double min_y, double min_z, double max_x, double max_y, double max_z, unsigned char a, const OctreeNode *node, const OctreeKey &key, std::vector< int > &k_indices, int max_voxel_count) const | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | [protected] |
| getKeyBitSize() | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [protected] |
| getKNearestNeighborRecursive(const PointT &point, unsigned int K, const BranchNode *node, const OctreeKey &key, unsigned int tree_depth, const double squared_search_radius, std::vector< prioPointQueueEntry > &point_candidates) const | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | [protected] |
| getLeafCount() const | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline] |
| getNeighborsWithinRadiusRecursive(const PointT &point, const double radiusSquared, const BranchNode *node, const OctreeKey &key, unsigned int tree_depth, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances, unsigned int max_nn) const | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | [protected] |
| getNextIntersectedNode(double x, double y, double z, int a, int b, int c) const | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | [inline, protected] |
| getOccupiedVoxelCenters(AlignedPointTVector &voxel_center_list_arg) const | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| getOccupiedVoxelCentersRecursive(const BranchNode *node_arg, const OctreeKey &key_arg, AlignedPointTVector &voxel_center_list_arg) const | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [protected] |
| getPointByIndex(const unsigned int index_arg) const | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [protected] |
| getResolution() const | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [inline] |
| getRootNode() const | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline, protected] |
| getTreeDepth() const | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [inline] |
| getVoxelBounds(OctreeIteratorBase< OctreeBase< LeafContainerT, BranchContainerT > > &iterator, Eigen::Vector3f &min_pt, Eigen::Vector3f &max_pt) | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [inline] |
| getVoxelSquaredDiameter(unsigned int tree_depth_arg) const | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| getVoxelSquaredDiameter() const | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [inline] |
| getVoxelSquaredSideLen(unsigned int tree_depth_arg) const | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| getVoxelSquaredSideLen() const | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [inline] |
| indices_ | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [protected] |
| IndicesConstPtr typedef | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | |
| IndicesPtr typedef | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | |
| initIntersectedVoxel(Eigen::Vector3f &origin, Eigen::Vector3f &direction, double &min_x, double &min_y, double &min_z, double &max_x, double &max_y, double &max_z, unsigned char &a) const | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | [inline, protected] |
| input_ | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [protected] |
| isPointWithinBoundingBox(const PointT &point_idx_arg) const | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [inline, protected] |
| isVoxelOccupiedAtPoint(const PointT &point_arg) const | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| isVoxelOccupiedAtPoint(const double point_x_arg, const double point_y_arg, const double point_z_arg) const | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| isVoxelOccupiedAtPoint(const int &point_idx_arg) const | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| Iterator typedef | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| leaf_begin(unsigned int max_depth_arg=0) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline] |
| leaf_count_ | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [protected] |
| leaf_end() | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline] |
| LeafContainer typedef | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | |
| LeafNode typedef | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | |
| LeafNodeIterator typedef | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| Log2(double n_arg) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline, protected] |
| max_key_ | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [protected] |
| max_objs_per_leaf_ | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [protected] |
| max_x_ | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [protected] |
| max_y_ | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [protected] |
| max_z_ | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [protected] |
| min_x_ | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [protected] |
| min_y_ | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [protected] |
| min_z_ | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [protected] |
| nearestKSearch(const PointCloud &cloud, int index, int k, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances) | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | [inline] |
| nearestKSearch(const PointT &p_q, int k, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances) | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | |
| nearestKSearch(int index, int k, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances) | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | |
| octree_depth_ | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [protected] |
| OctreeBase() | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | |
| OctreeBase(const OctreeBase &source) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline] |
| octreeCanResize() | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline, protected] |
| OctreePointCloud(const double resolution_arg) | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| OctreePointCloudSearch(const double resolution) | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | [inline] |
| OctreeT typedef | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | |
| operator=(const OctreeBase &source) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline] |
| PointCloud typedef | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | |
| PointCloudConstPtr typedef | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | |
| PointCloudPtr typedef | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | |
| pointSquaredDist(const PointT &point_a, const PointT &point_b) const | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | [protected] |
| Ptr typedef | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | |
| 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, LeafContainerT, BranchContainerT > | [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, LeafContainerT, BranchContainerT > | |
| 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, LeafContainerT, BranchContainerT > | |
| removeLeaf(unsigned int idx_x_arg, unsigned int idx_y_arg, unsigned int idx_z_arg) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | |
| removeLeaf(const OctreeKey &key_arg) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline, protected] |
| resolution_ | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [protected] |
| root_node_ | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [protected] |
| serializeLeafs(std::vector< LeafContainerT * > &leaf_container_vector_arg) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | |
| serializeTree(std::vector< char > &binary_tree_out_arg) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | |
| serializeTree(std::vector< char > &binary_tree_out_arg, std::vector< LeafContainerT * > &leaf_container_vector_arg) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | |
| serializeTreeCallback(LeafContainerT &, const OctreeKey &) const | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline, protected, virtual] |
| serializeTreeRecursive(const BranchNode *branch_arg, OctreeKey &key_arg, std::vector< char > *binary_tree_out_arg, typename std::vector< LeafContainerT * > *leaf_container_vector_arg) const | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [protected] |
| setBranchChildPtr(BranchNode &branch_arg, unsigned char child_idx_arg, OctreeNode *new_child_arg) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [inline, protected] |
| setEpsilon(double eps) | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [inline] |
| setInputCloud(const PointCloudConstPtr &cloud_arg, const IndicesConstPtr &indices_arg=IndicesConstPtr()) | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [inline] |
| setMaxVoxelIndex(unsigned int max_voxel_index_arg) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | |
| setResolution(double resolution_arg) | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [inline] |
| setTreeDepth(unsigned int max_depth_arg) | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | |
| SingleBuffer typedef | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | |
| voxelSearch(const PointT &point, std::vector< int > &point_idx_data) | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | |
| voxelSearch(const int index, std::vector< int > &point_idx_data) | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | |
| ~OctreeBase() | pcl::octree::OctreeBase< LeafContainerT, BranchContainerT > | [virtual] |
| ~OctreePointCloud() | pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT > | [virtual] |
| ~OctreePointCloudSearch() | pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > | [inline, virtual] |