#include <pcl/common/io.h>
#include <pcl/PCLPointCloud2.h>
#include <pcl/outofcore/boost.h>
#include <pcl/outofcore/octree_base.h>
#include <pcl/outofcore/octree_disk_container.h>
#include <pcl/outofcore/outofcore_node_data.h>
#include <pcl/octree/octree_nodes.h>
Go to the source code of this file.
Classes | |
class | pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT > |
OutofcoreOctreeBaseNode Class internally representing nodes of an outofcore octree, with accessors to its data via the octree_disk_container class or octree_ram_container class, whichever it is templated against. More... | |
Namespaces | |
namespace | pcl |
namespace | pcl::outofcore |
Functions | |
template<typename ContainerT , typename PointT > | |
OutofcoreOctreeBaseNode < ContainerT, PointT > * | pcl::outofcore::makenode_norec (const boost::filesystem::path &path, OutofcoreOctreeBaseNode< ContainerT, PointT > *super) |
Non-class function which creates a single child leaf; used with queryBBIntersects_noload to avoid loading the data from disk. | |
template<typename ContainerT , typename PointT > | |
void | pcl::outofcore::queryBBIntersects_noload (const boost::filesystem::path &root_node, const Eigen::Vector3d &min, const Eigen::Vector3d &max, const boost::uint32_t query_depth, std::list< std::string > &bin_name) |
Non-class method which performs a bounding box query without loading any of the point cloud data from disk. | |
template<typename ContainerT , typename PointT > | |
void | pcl::outofcore::queryBBIntersects_noload (OutofcoreOctreeBaseNode< ContainerT, PointT > *current, const Eigen::Vector3d &, const Eigen::Vector3d &max, const boost::uint32_t query_depth, std::list< std::string > &bin_name) |
Non-class method overload. |