, including all inherited members.
addDataToLeaf(const AlignedPointTVector &p) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
addDataToLeaf_and_genLOD(AlignedPointTVector &p) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
addPointCloud(PointCloudConstPtr point_cloud) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
addPointCloud(pcl::PCLPointCloud2::Ptr &input_cloud, const bool skip_bb_check=false) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
addPointCloud(pcl::PCLPointCloud2::Ptr &input_cloud) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
addPointCloud_and_genLOD(pcl::PCLPointCloud2::Ptr &input_cloud) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
addPointCloud_and_genLOD(PointCloudConstPtr point_cloud) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
AlignedPointTVector typedef | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
BranchNode typedef | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
BreadthFirstConstIterator typedef | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
BreadthFirstIterator typedef | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
buildLOD() | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
buildLODRecursive(const std::vector< BranchNode * > ¤t_branch) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [protected] |
calculateDepth(const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb, const double leaf_resolution) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [private] |
checkExtension(const boost::filesystem::path &path_name) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [protected] |
ConstIterator typedef | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
ConstPtr typedef | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
convertToXYZ() | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
DeAllocEmptyNodeCache(OutofcoreNodeType *current) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [protected] |
DeAllocEmptyNodeCache() | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [protected] |
DepthFirstConstIterator typedef | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
DepthFirstIterator typedef | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
enlargeToCube(Eigen::Vector3d &bb_min, Eigen::Vector3d &bb_max) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [private] |
flushToDisk() | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [protected] |
flushToDiskLazy() | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [protected] |
getBinDimension(double &x, double &y) const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
getBoundingBox(Eigen::Vector3d &min, Eigen::Vector3d &max) const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
getBranchChildPtr(const BranchNode &branch_arg, unsigned char childIdx_arg) const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
getCoordSystem() const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [inline] |
getDepth() const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [inline] |
getLODFilter() | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
getLODFilter() const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
getNumPointsAtDepth(const boost::uint64_t &depth_index) const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [inline] |
getNumPointsVector() const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [inline] |
getOccupiedVoxelCenters(AlignedPointTVector &voxel_centers, size_t query_depth) const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
getOccupiedVoxelCenters(std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > &voxel_centers, size_t query_depth) const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
getOccupiedVoxelCenters(AlignedPointTVector &voxel_centers) const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [inline] |
getOccupiedVoxelCenters(std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > &voxel_centers) const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [inline] |
getRootNode() | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [inline, protected] |
getSamplePercent() const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [inline] |
getTreeDepth() const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [inline] |
getVoxelSideLength(const boost::uint64_t &depth) const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
getVoxelSideLength() const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [inline] |
incrementPointsInLOD(boost::uint64_t depth, boost::uint64_t inc) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [inline, protected] |
IndicesConstPtr typedef | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
IndicesPtr typedef | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
init(const boost::uint64_t &depth, const Eigen::Vector3d &min, const Eigen::Vector3d &max, const boost::filesystem::path &root_name, const std::string &coord_sys) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [protected] |
Iterator typedef | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
LeafNode typedef | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
LOAD_COUNT_ | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [protected, static] |
lod_filter_ptr_ | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [private] |
metadata_ | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [protected] |
octree_disk typedef | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
octree_disk_node typedef | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
octree_ram typedef | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
octree_ram_node typedef | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
operator=(OutofcoreOctreeBase &rval) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [protected] |
operator=(const OutofcoreOctreeBase &rval) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [protected] |
OUTOFCORE_VERSION_ | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [protected, static] |
OutofcoreNodeType typedef | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
OutofcoreOctreeBase(const boost::filesystem::path &root_node_name, const bool load_all) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
OutofcoreOctreeBase(const Eigen::Vector3d &min, const Eigen::Vector3d &max, const double resolution_arg, const boost::filesystem::path &root_node_name, const std::string &coord_sys) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
OutofcoreOctreeBase(const boost::uint64_t max_depth, const Eigen::Vector3d &min, const Eigen::Vector3d &max, const boost::filesystem::path &root_node_name, const std::string &coord_sys) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
OutofcoreOctreeBase(OutofcoreOctreeBase &rval) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [protected] |
OutofcoreOctreeBase(const OutofcoreOctreeBase &rval) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [protected] |
OutofcoreOctreeBaseNode< ContainerT, PointT > class | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [friend] |
pcl::outofcore::OutofcoreIteratorBase< PointT, ContainerT > class | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [friend] |
PointCloud typedef | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
PointCloudConstPtr typedef | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
PointCloudPtr typedef | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
printBoundingBox(const size_t query_depth) const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
printBoundingBox(OutofcoreNodeType &node) const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
printBoundingBox() const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [inline] |
Ptr typedef | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
queryBBIncludes(const Eigen::Vector3d &min, const Eigen::Vector3d &max, const boost::uint64_t query_depth, AlignedPointTVector &dst) const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
queryBBIncludes(const Eigen::Vector3d &min, const Eigen::Vector3d &max, const boost::uint64_t query_depth, const pcl::PCLPointCloud2::Ptr &dst_blob) const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
queryBBIncludes_subsample(const Eigen::Vector3d &min, const Eigen::Vector3d &max, uint64_t query_depth, const double percent, AlignedPointTVector &dst) const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
queryBBIntersects(const Eigen::Vector3d &min, const Eigen::Vector3d &max, const boost::uint32_t query_depth, std::list< std::string > &bin_name) const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
queryBoundingBox(const Eigen::Vector3d &min, const Eigen::Vector3d &max, const int query_depth, const pcl::PCLPointCloud2::Ptr &dst_blob, double percent=1.0) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [virtual] |
queryBoundingBox(const Eigen::Vector3d &min, const Eigen::Vector3d &max, const int query_depth, std::list< std::string > &filenames) const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [inline, virtual] |
queryBoundingBoxNumPoints(const Eigen::Vector3d &min, const Eigen::Vector3d &max, const int query_depth, bool load_from_disk=true) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
queryFrustum(const double *planes, std::list< std::string > &file_names) const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
queryFrustum(const double *planes, std::list< std::string > &file_names, const boost::uint32_t query_depth) const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
queryFrustum(const double *planes, const Eigen::Vector3d &eye, const Eigen::Matrix4d &view_projection_matrix, std::list< std::string > &file_names, const boost::uint32_t query_depth) const | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
read_write_mutex_ | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [mutable, protected] |
root_node_ | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [protected] |
sample_percent_ | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [private] |
saveToFile() | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [protected] |
setLODFilter(const pcl::Filter< pcl::PCLPointCloud2 >::Ptr &filter_arg) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
setSamplePercent(const double sample_percent_arg) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [inline] |
TREE_EXTENSION_ | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [protected, static] |
writeVPythonVisual(const boost::filesystem::path filename) | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | |
~OutofcoreOctreeBase() | pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > | [virtual] |