Classes | |
class | OutofcoreAbstractMetadata |
class | OutofcoreAbstractNodeContainer |
class | OutofcoreBreadthFirstIterator |
class | OutofcoreDepthFirstIterator |
class | OutofcoreIteratorBase |
Abstract octree iterator class. More... | |
class | OutofcoreOctreeBase |
This code defines the octree used for point storage at Urban Robotics. More... | |
class | OutofcoreOctreeBaseMetadata |
Encapsulated class to read JSON metadata into memory, and write the JSON metadata associated with the octree root node. This is global information that is not the same as the metadata for the root node. Inherits OutofcoreAbstractMetadata interface for metadata in pcl_outofcore. More... | |
class | OutofcoreOctreeBaseNode |
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... | |
class | OutofcoreOctreeDiskContainer |
Class responsible for serialization and deserialization of out of core point data. More... | |
class | OutofcoreOctreeNodeMetadata |
Encapsulated class to read JSON metadata into memory, and write the JSON metadata for each node. More... | |
class | OutofcoreOctreeRamContainer |
Storage container class which the outofcore octree base is templated against. More... | |
struct | OutofcoreParams |
Functions | |
template<typename ContainerT , typename PointT > | |
OutofcoreOctreeBaseNode < ContainerT, PointT > * | 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. | |
std::ostream & | operator<< (std::ostream &, const OutofcoreOctreeNodeMetadata &) |
std::ostream & | operator<< (std::ostream &os, const OutofcoreOctreeBaseMetadata &metadata_arg) |
template<typename ContainerT , typename PointT > | |
bool | pointInBoundingBox (const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb, const Eigen::Vector3d &point) |
template<typename ContainerT , typename PointT > | |
void | 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 | 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. | |
Variables | |
boost::uuids::random_generator OutofcoreOctreeDiskContainer < PointT >::uuid_gen_ & | rand_gen_ |
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.
std::ostream& pcl::outofcore::operator<< | ( | std::ostream & | , |
const OutofcoreOctreeNodeMetadata & | |||
) |
Definition at line 346 of file outofcore_node_data.cpp.
std::ostream& pcl::outofcore::operator<< | ( | std::ostream & | os, |
const OutofcoreOctreeBaseMetadata & | metadata_arg | ||
) |
Definition at line 381 of file outofcore_base_data.cpp.
bool pcl::outofcore::pointInBoundingBox | ( | const Eigen::Vector3d & | min_bb, |
const Eigen::Vector3d & | max_bb, | ||
const Eigen::Vector3d & | point | ||
) |
Definition at line 926 of file octree_base_node.hpp.
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.
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.
boost::uuids::random_generator OutofcoreOctreeDiskContainer<PointT>::uuid_gen_& pcl::outofcore::rand_gen_ |
Definition at line 77 of file octree_disk_container.hpp.