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...
#include <octree_base_node.h>
Public Types | |
typedef std::vector< PointT, Eigen::aligned_allocator < PointT > > | AlignedPointTVector |
typedef pcl::octree::node_type_t | node_type_t |
typedef OutofcoreOctreeBase < OutofcoreOctreeDiskContainer < PointT >, PointT > | octree_disk |
typedef OutofcoreOctreeBaseNode < OutofcoreOctreeDiskContainer < PointT >, PointT > | octree_disk_node |
Public Member Functions | |
virtual boost::uint64_t | addDataToLeaf (const AlignedPointTVector &p, const bool skip_bb_check=true) |
add point to this node if we are a leaf, or find the leaf below us that is supposed to take the point | |
virtual boost::uint64_t | addDataToLeaf (const std::vector< const PointT * > &p, const bool skip_bb_check=true) |
virtual boost::uint64_t | addDataToLeaf_and_genLOD (const AlignedPointTVector &p, const bool skip_bb_check) |
Recursively add points to the leaf and children subsampling LODs on the way down. | |
virtual boost::uint64_t | addPointCloud (const pcl::PCLPointCloud2::Ptr &input_cloud, const bool skip_bb_check=false) |
Add a single PCLPointCloud2 object into the octree. | |
virtual boost::uint64_t | addPointCloud_and_genLOD (const pcl::PCLPointCloud2::Ptr input_cloud) |
Add a single PCLPointCloud2 into the octree and build the subsampled LOD during construction; this method of LOD construction is not multiresolution. Rather, there are no redundant data. | |
virtual void | clearData () |
virtual OutofcoreOctreeBaseNode * | deepCopy () const |
Pure virtual method to perform a deep copy of the octree. | |
virtual void | getBoundingBox (Eigen::Vector3d &min_bb, Eigen::Vector3d &max_bb) const |
gets the minimum and maximum corner of the bounding box represented by this node | |
virtual OutofcoreOctreeBaseNode * | getChildPtr (size_t index_arg) const |
Returns a pointer to the child in octant index_arg. | |
virtual boost::uint64_t | getDataSize () const |
Gets the number of points available in the PCD file. | |
virtual size_t | getDepth () const |
const boost::filesystem::path & | getMetadataFilename () const |
virtual node_type_t | getNodeType () const |
Pure virtual method for receiving the type of octree node (branch or leaf) | |
virtual size_t | getNumChildren () const |
Returns the total number of children on disk. | |
virtual size_t | getNumLoadedChildren () const |
Count loaded chilren. | |
const boost::filesystem::path & | getPCDFilename () const |
OutofcoreOctreeBaseNode () | |
Empty constructor; sets pointers for children and for bounding boxes to 0. | |
OutofcoreOctreeBaseNode (const Eigen::Vector3d &bb_min, const Eigen::Vector3d &bb_max, OutofcoreOctreeBase< ContainerT, PointT > *const tree, const boost::filesystem::path &root_name) | |
Create root node and directory. | |
virtual void | printBoundingBox (const size_t query_depth) const |
Write the voxel size to stdout at query_depth. | |
virtual void | queryBBIncludes (const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb, size_t query_depth, AlignedPointTVector &dst) |
Recursively add points that fall into the queried bounding box up to the query_depth. | |
virtual void | queryBBIncludes (const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb, size_t query_depth, const pcl::PCLPointCloud2::Ptr &dst_blob) |
Recursively add points that fall into the queried bounding box up to the query_depth. | |
virtual void | queryBBIncludes_subsample (const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb, boost::uint64_t query_depth, const double percent, AlignedPointTVector &v) |
Recursively add points that fall into the queried bounding box up to the query_depth. | |
virtual void | queryBBIncludes_subsample (const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb, boost::uint64_t query_depth, const pcl::PCLPointCloud2::Ptr &dst_blob, double percent=1.0) |
virtual void | queryBBIntersects (const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb, const boost::uint32_t query_depth, std::list< std::string > &file_names) |
Recursive acquires PCD paths to any node with which the queried bounding box intersects (at query_depth only). | |
void | queryFrustum (const double planes[24], std::list< std::string > &file_names) |
void | queryFrustum (const double planes[24], std::list< std::string > &file_names, const boost::uint32_t query_depth, const bool skip_vfc_check=false) |
void | queryFrustum (const double planes[24], const Eigen::Vector3d &eye, const Eigen::Matrix4d &view_projection_matrix, std::list< std::string > &file_names, const boost::uint32_t query_depth, const bool skip_vfc_check=false) |
virtual int | read (pcl::PCLPointCloud2::Ptr &output_cloud) |
void | writeVPythonVisual (std::ofstream &file) |
Write a python visual script to file. | |
virtual | ~OutofcoreOctreeBaseNode () |
Will recursively delete all children calling recFreeChildrein. | |
Static Public Attributes | |
static const std::string | node_container_basename = "node" |
static const std::string | node_container_extension = ".oct_dat" |
static const std::string | node_index_basename = "node" |
static const std::string | node_index_extension = ".oct_idx" |
static const double | sample_percent_ = .125 |
Protected Member Functions | |
boost::uint64_t | addDataAtMaxDepth (const AlignedPointTVector &p, const bool skip_bb_check=true) |
Add data to the leaf when at max depth of tree. If skip_bb_check is true, adds to the node regardless of the bounding box it represents; otherwise only adds points that fall within the bounding box. | |
boost::uint64_t | addDataAtMaxDepth (const pcl::PCLPointCloud2::Ptr input_cloud, const bool skip_bb_check=true) |
Add data to the leaf when at max depth of tree. If skip_bb_check is true, adds to the node regardless of the bounding box it represents; otherwise only adds points that fall within the bounding box. | |
void | convertToXYZRecursive () |
Recursively converts data files to ascii XZY files. | |
void | copyAllCurrentAndChildPointsRec (std::list< PointT > &v) |
Copies points from this and all children into a single point container (std::list) | |
void | copyAllCurrentAndChildPointsRec_sub (std::list< PointT > &v, const double percent) |
virtual size_t | countNumChildren () const |
Counts the number of child directories on disk; used to update num_children_. | |
virtual size_t | countNumLoadedChildren () const |
Counts the number of loaded chilren by testing the children_ array; used to update num_loaded_chilren_ internally. | |
void | createChild (const std::size_t idx) |
Creates child node idx. | |
void | enlargeToCube (Eigen::Vector3d &bb_min, Eigen::Vector3d &bb_max) |
Enlarges the shortest two sidelengths of the bounding box to a cubic shape; operation is done in place. | |
void | flushToDiskRecursive () |
void | getOccupiedVoxelCentersRecursive (AlignedPointTVector &voxel_centers, const size_t query_depth) |
Gets a vector of occupied voxel centers. | |
void | getOccupiedVoxelCentersRecursive (std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > &voxel_centers, const size_t query_depth) |
Gets a vector of occupied voxel centers. | |
bool | hasUnloadedChildren () const |
Returns whether or not a node has unloaded children data. | |
bool | inBoundingBox (const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb) const |
Tests whether the input bounding box falls inclusively within this node's bounding box. | |
void | init_root_node (const Eigen::Vector3d &bb_min, const Eigen::Vector3d &bb_max, OutofcoreOctreeBase< ContainerT, PointT > *const tree, const boost::filesystem::path &rootname) |
Create root node and directory. | |
bool | intersectsWithBoundingBox (const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb) const |
Tests whether the input bounding box intersects with the current node's bounding box. | |
virtual void | loadChildren (bool recursive) |
Load nodes child data creating new nodes for each. | |
void | loadFromFile (const boost::filesystem::path &path, OutofcoreOctreeBaseNode *super) |
Loads the nodes metadata from the JSON file. | |
OutofcoreOctreeBaseNode & | operator= (const OutofcoreOctreeBaseNode &rval) |
Operator= is not implemented. | |
OutofcoreOctreeBaseNode (const boost::filesystem::path &directory_path, OutofcoreOctreeBaseNode< ContainerT, PointT > *super, bool load_all) | |
Load from disk If creating root, path is full name. If creating any other node, path is dir; throws exception if directory or metadata not found. | |
OutofcoreOctreeBaseNode (const OutofcoreOctreeBaseNode &rval) | |
no copy construction right now | |
OutofcoreOctreeBaseNode (const Eigen::Vector3d &bb_min, const Eigen::Vector3d &bb_max, const char *dir, OutofcoreOctreeBaseNode< ContainerT, PointT > *super) | |
Private constructor used for children. | |
bool | pointInBoundingBox (const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb, const Eigen::Vector3d &point) |
Tests whether point falls within the input bounding box. | |
bool | pointInBoundingBox (const PointT &p) const |
Tests if specified point is within bounds of current node's bounding box. | |
void | randomSample (const AlignedPointTVector &p, AlignedPointTVector &insertBuff, const bool skip_bb_check) |
Randomly sample point data. | |
void | recFreeChildren () |
Method which recursively free children of this node. | |
void | saveIdx (bool recursive) |
Save node's metadata to file. | |
void | saveMetadataToFile (const boost::filesystem::path &path) |
Write JSON metadata for this node to file. | |
boost::uint64_t | size () const |
Number of points in the payload. | |
void | sortOctantIndices (const pcl::PCLPointCloud2::Ptr &input_cloud, std::vector< std::vector< int > > &indices, const Eigen::Vector3d &mid_xyz) |
Sorts the indices based on x,y,z fields and pushes the index into the proper octant's vector; This could be overloaded with a parallelized implementation. | |
void | subdividePoint (const PointT &point, std::vector< AlignedPointTVector > &c) |
Subdivide a single point into a specific child node. | |
void | subdividePoints (const AlignedPointTVector &p, std::vector< AlignedPointTVector > &c, const bool skip_bb_check) |
Subdivide points to pass to child nodes. | |
Static Protected Member Functions | |
static bool | pointInBoundingBox (const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb, const PointT &p) |
Tests whether p falls within the input bounding box. | |
static bool | pointInBoundingBox (const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb, const double x, const double y, const double z) |
Tests whether x, y, and z fall within the input bounding box. | |
Protected Attributes | |
std::vector < OutofcoreOctreeBaseNode * > | children_ |
The children of this node. | |
size_t | depth_ |
Depth in the tree, root is 0, root's children are 1, ... | |
OutofcoreOctreeBase < ContainerT, PointT > * | m_tree_ |
The tree we belong to. | |
OutofcoreOctreeNodeMetadata::Ptr | node_metadata_ |
uint64_t | num_children_ |
Number of children on disk. This is only changed when a new node is created. | |
uint64_t | num_loaded_children_ |
Number of loaded children this node has. | |
OutofcoreOctreeBaseNode * | parent_ |
super-node | |
boost::shared_ptr< ContainerT > | payload_ |
what holds the points. currently a custom class, but in theory you could use an stl container if you rewrote some of this class. I used to use deques for this... | |
OutofcoreOctreeBaseNode * | root_node_ |
The root node of the tree we belong to. | |
Static Protected Attributes | |
static const std::string | pcd_extension = ".pcd" |
Extension for this class to find the pcd files on disk. | |
static boost::mt19937 | rand_gen_ |
Mersenne Twister: A 623-dimensionally equidistributed uniform pseudo-random number generator. | |
static boost::mutex | rng_mutex_ |
Random number generator mutex. | |
static const boost::uint32_t | rngseed = 0xAABBCCDD |
Random number generator seed. | |
Friends | |
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. | |
class | OutofcoreOctreeBase< ContainerT, PointT > |
void | queryBBIntersects_noload (const boost::filesystem::path &rootnode, 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 | queryBBIntersects_noload (OutofcoreOctreeBaseNode< ContainerT, PointT > *current, const Eigen::Vector3d &min, const Eigen::Vector3d &max, const boost::uint32_t query_depth, std::list< std::string > &bin_name) |
Non-class method overload. |
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.
Definition at line 92 of file octree_base_node.h.
typedef std::vector<PointT, Eigen::aligned_allocator<PointT> > pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::AlignedPointTVector |
Definition at line 110 of file octree_base_node.h.
typedef pcl::octree::node_type_t pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::node_type_t |
Definition at line 112 of file octree_base_node.h.
typedef OutofcoreOctreeBase<OutofcoreOctreeDiskContainer < PointT > , PointT > pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::octree_disk |
Definition at line 107 of file octree_base_node.h.
typedef OutofcoreOctreeBaseNode<OutofcoreOctreeDiskContainer < PointT > , PointT > pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::octree_disk_node |
Definition at line 108 of file octree_base_node.h.
pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::OutofcoreOctreeBaseNode | ( | ) |
Empty constructor; sets pointers for children and for bounding boxes to 0.
Definition at line 90 of file octree_base_node.hpp.
pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::OutofcoreOctreeBaseNode | ( | const Eigen::Vector3d & | bb_min, |
const Eigen::Vector3d & | bb_max, | ||
OutofcoreOctreeBase< ContainerT, PointT > *const | tree, | ||
const boost::filesystem::path & | root_name | ||
) |
Create root node and directory.
Definition at line 183 of file octree_base_node.hpp.
pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::~OutofcoreOctreeBaseNode | ( | ) | [virtual] |
Will recursively delete all children calling recFreeChildrein.
Definition at line 259 of file octree_base_node.hpp.
pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::OutofcoreOctreeBaseNode | ( | const boost::filesystem::path & | directory_path, |
OutofcoreOctreeBaseNode< ContainerT, PointT > * | super, | ||
bool | load_all | ||
) | [protected] |
Load from disk If creating root, path is full name. If creating any other node, path is dir; throws exception if directory or metadata not found.
[in] | Directory | pathname |
[in] | super | |
[in] | loadAll |
PCLException | if directory is missing |
PCLException | if node index is missing |
Definition at line 108 of file octree_base_node.hpp.
pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::OutofcoreOctreeBaseNode | ( | const OutofcoreOctreeBaseNode< ContainerT, PointT > & | rval | ) | [protected] |
no copy construction right now
pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::OutofcoreOctreeBaseNode | ( | const Eigen::Vector3d & | bb_min, |
const Eigen::Vector3d & | bb_max, | ||
const char * | dir, | ||
OutofcoreOctreeBaseNode< ContainerT, PointT > * | super | ||
) | [protected] |
Private constructor used for children.
Definition at line 1729 of file octree_base_node.hpp.
boost::uint64_t pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::addDataAtMaxDepth | ( | const AlignedPointTVector & | p, |
const bool | skip_bb_check = true |
||
) | [protected] |
Add data to the leaf when at max depth of tree. If skip_bb_check is true, adds to the node regardless of the bounding box it represents; otherwise only adds points that fall within the bounding box.
[in] | p | vector of points to attempt to add to the tree |
[in] | skip_bb_check | if true, doesn't check that points are in the proper bounding box; if false, only adds the points that fall into the bounding box to this node |
Definition at line 625 of file octree_base_node.hpp.
boost::uint64_t pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::addDataAtMaxDepth | ( | const pcl::PCLPointCloud2::Ptr | input_cloud, |
const bool | skip_bb_check = true |
||
) | [protected] |
Add data to the leaf when at max depth of tree. If skip_bb_check is true, adds to the node regardless of the bounding box it represents; otherwise only adds points that fall within the bounding box.
[in] | input_cloud | PCLPointCloud2 points to attempt to add to the tree; |
[in] | skip_bb_check | (default true) if true, doesn't check that points are in the proper bounding box; if false, only adds the points that fall into the bounding box to this node |
Definition at line 666 of file octree_base_node.hpp.
uint64_t pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::addDataToLeaf | ( | const AlignedPointTVector & | p, |
const bool | skip_bb_check = true |
||
) | [virtual] |
add point to this node if we are a leaf, or find the leaf below us that is supposed to take the point
[in] | p | vector of points to add to the leaf |
[in] | skipBBCheck | whether to check if the point's coordinates fall within the bounding box |
Definition at line 356 of file octree_base_node.hpp.
boost::uint64_t pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::addDataToLeaf | ( | const std::vector< const PointT * > & | p, |
const bool | skip_bb_check = true |
||
) | [virtual] |
Definition at line 415 of file octree_base_node.hpp.
boost::uint64_t pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::addDataToLeaf_and_genLOD | ( | const AlignedPointTVector & | p, |
const bool | skip_bb_check | ||
) | [virtual] |
Recursively add points to the leaf and children subsampling LODs on the way down.
Definition at line 820 of file octree_base_node.hpp.
boost::uint64_t pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::addPointCloud | ( | const pcl::PCLPointCloud2::Ptr & | input_cloud, |
const bool | skip_bb_check = false |
||
) | [virtual] |
Add a single PCLPointCloud2 object into the octree.
[in] | input_cloud | |
[in] | skip_bb_check | (default = false) |
Definition at line 508 of file octree_base_node.hpp.
boost::uint64_t pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::addPointCloud_and_genLOD | ( | const pcl::PCLPointCloud2::Ptr | input_cloud | ) | [virtual] |
Add a single PCLPointCloud2 into the octree and build the subsampled LOD during construction; this method of LOD construction is not multiresolution. Rather, there are no redundant data.
Definition at line 720 of file octree_base_node.hpp.
virtual void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::clearData | ( | ) | [inline, virtual] |
Definition at line 301 of file octree_base_node.h.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::convertToXYZRecursive | ( | ) | [protected] |
Recursively converts data files to ascii XZY files.
Definition at line 1974 of file octree_base_node.hpp.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::copyAllCurrentAndChildPointsRec | ( | std::list< PointT > & | v | ) | [protected] |
Copies points from this and all children into a single point container (std::list)
Definition at line 1782 of file octree_base_node.hpp.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::copyAllCurrentAndChildPointsRec_sub | ( | std::list< PointT > & | v, |
const double | percent | ||
) | [protected] |
Definition at line 1806 of file octree_base_node.hpp.
size_t pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::countNumChildren | ( | ) | const [protected, virtual] |
Counts the number of child directories on disk; used to update num_children_.
Definition at line 268 of file octree_base_node.hpp.
size_t pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::countNumLoadedChildren | ( | ) | const [protected, virtual] |
Counts the number of loaded chilren by testing the children_ array; used to update num_loaded_chilren_ internally.
Definition at line 1940 of file octree_base_node.hpp.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::createChild | ( | const std::size_t | idx | ) | [protected] |
Creates child node idx.
[in] | idx | Index (0-7) of the child node |
Definition at line 878 of file octree_base_node.hpp.
virtual OutofcoreOctreeBaseNode* pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::deepCopy | ( | ) | const [inline, virtual] |
Pure virtual method to perform a deep copy of the octree.
Implements pcl::octree::OctreeNode.
Definition at line 263 of file octree_base_node.h.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::enlargeToCube | ( | Eigen::Vector3d & | bb_min, |
Eigen::Vector3d & | bb_max | ||
) | [protected] |
Enlarges the shortest two sidelengths of the bounding box to a cubic shape; operation is done in place.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::flushToDiskRecursive | ( | ) | [protected] |
Definition at line 1995 of file octree_base_node.hpp.
virtual void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::getBoundingBox | ( | Eigen::Vector3d & | min_bb, |
Eigen::Vector3d & | max_bb | ||
) | const [inline, virtual] |
gets the minimum and maximum corner of the bounding box represented by this node
[out] | minCoord | returns the minimum corner of the bounding box indexed by 0-->X, 1-->Y, 2-->Z |
[out] | maxCoord | returns the maximum corner of the bounding box indexed by 0-->X, 1-->Y, 2-->Z |
Definition at line 137 of file octree_base_node.h.
OutofcoreOctreeBaseNode< ContainerT, PointT > * pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::getChildPtr | ( | size_t | index_arg | ) | const [virtual] |
Returns a pointer to the child in octant index_arg.
Definition at line 1924 of file octree_base_node.hpp.
boost::uint64_t pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::getDataSize | ( | ) | const [virtual] |
Gets the number of points available in the PCD file.
Definition at line 1932 of file octree_base_node.hpp.
virtual size_t pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::getDepth | ( | ) | const [inline, virtual] |
Definition at line 271 of file octree_base_node.h.
const boost::filesystem::path& pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::getMetadataFilename | ( | ) | const [inline] |
Definition at line 150 of file octree_base_node.h.
virtual node_type_t pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::getNodeType | ( | ) | const [inline, virtual] |
Pure virtual method for receiving the type of octree node (branch or leaf)
Implements pcl::octree::OctreeNode.
Definition at line 249 of file octree_base_node.h.
virtual size_t pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::getNumChildren | ( | ) | const [inline, virtual] |
Returns the total number of children on disk.
Definition at line 278 of file octree_base_node.h.
virtual size_t pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::getNumLoadedChildren | ( | ) | const [inline, virtual] |
Count loaded chilren.
Definition at line 286 of file octree_base_node.h.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::getOccupiedVoxelCentersRecursive | ( | AlignedPointTVector & | voxel_centers, |
const size_t | query_depth | ||
) | [protected] |
Gets a vector of occupied voxel centers.
[out] | voxel_centers | |
[in] | query_depth |
Definition at line 986 of file octree_base_node.hpp.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::getOccupiedVoxelCentersRecursive | ( | std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > & | voxel_centers, |
const size_t | query_depth | ||
) | [protected] |
Gets a vector of occupied voxel centers.
[out] | voxel_centers | |
[in] | query_depth |
Definition at line 1330 of file octree_base_node.hpp.
const boost::filesystem::path& pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::getPCDFilename | ( | ) | const [inline] |
Definition at line 144 of file octree_base_node.h.
bool pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::hasUnloadedChildren | ( | ) | const [protected] |
Returns whether or not a node has unloaded children data.
Definition at line 301 of file octree_base_node.hpp.
bool pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::inBoundingBox | ( | const Eigen::Vector3d & | min_bb, |
const Eigen::Vector3d & | max_bb | ||
) | const [inline, protected] |
Tests whether the input bounding box falls inclusively within this node's bounding box.
[in] | min_bb | The minimum corner of the input bounding box |
[in] | max_bb | The maximum corner of the input bounding box |
Definition at line 1853 of file octree_base_node.hpp.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::init_root_node | ( | const Eigen::Vector3d & | bb_min, |
const Eigen::Vector3d & | bb_max, | ||
OutofcoreOctreeBase< ContainerT, PointT > *const | tree, | ||
const boost::filesystem::path & | rootname | ||
) | [protected] |
Create root node and directory.
Initializes the root node and performs initial filesystem checks for the octree; throws OctreeException::OCT_BAD_PATH if root directory is an existing file
bb_min | triple of x,y,z minima for bounding box |
bb_max | triple of x,y,z maxima for bounding box |
tree | adress of the tree data structure that will hold this initial root node |
rootname | Root directory for location of on-disk octree storage; if directory doesn't exist, it is created; if "rootname" is an existing file, |
PCLException | if the specified path already exists |
Definition at line 202 of file octree_base_node.hpp.
bool pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::intersectsWithBoundingBox | ( | const Eigen::Vector3d & | min_bb, |
const Eigen::Vector3d & | max_bb | ||
) | const [inline, protected] |
Tests whether the input bounding box intersects with the current node's bounding box.
[in] | min_bb | The minimum corner of the input bounding box |
[in] | min_bb | The maximum corner of the input bounding box |
Definition at line 1831 of file octree_base_node.hpp.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::loadChildren | ( | bool | recursive | ) | [protected, virtual] |
Load nodes child data creating new nodes for each.
Definition at line 311 of file octree_base_node.hpp.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::loadFromFile | ( | const boost::filesystem::path & | path, |
OutofcoreOctreeBaseNode< ContainerT, PointT > * | super | ||
) | [protected] |
Loads the nodes metadata from the JSON file.
Definition at line 1956 of file octree_base_node.hpp.
OutofcoreOctreeBaseNode& pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::operator= | ( | const OutofcoreOctreeBaseNode< ContainerT, PointT > & | rval | ) | [protected] |
Operator= is not implemented.
bool pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::pointInBoundingBox | ( | const Eigen::Vector3d & | min_bb, |
const Eigen::Vector3d & | max_bb, | ||
const Eigen::Vector3d & | point | ||
) | [protected] |
Tests whether point falls within the input bounding box.
[in] | min_bb | The minimum corner of the input bounding box |
[in] | max_bb | The maximum corner of the input bounding box |
[in] | point | The test point |
bool pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::pointInBoundingBox | ( | const Eigen::Vector3d & | min_bb, |
const Eigen::Vector3d & | max_bb, | ||
const PointT & | p | ||
) | [inline, static, protected] |
Tests whether p falls within the input bounding box.
[in] | min_bb | The minimum corner of the input bounding box |
[in] | max_bb | The maximum corner of the input bounding box |
[in] | p | The point to be tested |
Definition at line 1875 of file octree_base_node.hpp.
static bool pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::pointInBoundingBox | ( | const Eigen::Vector3d & | min_bb, |
const Eigen::Vector3d & | max_bb, | ||
const double | x, | ||
const double | y, | ||
const double | z | ||
) | [static, protected] |
Tests whether x, y, and z fall within the input bounding box.
[in] | min_bb | The minimum corner of the input bounding box |
[in] | max_bb | The maximum corner of the input bounding box |
bool pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::pointInBoundingBox | ( | const PointT & | p | ) | const [inline, protected] |
Tests if specified point is within bounds of current node's bounding box.
Definition at line 941 of file octree_base_node.hpp.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::printBoundingBox | ( | const size_t | query_depth | ) | const [virtual] |
Write the voxel size to stdout at query_depth.
[in] | query_depth | The depth at which to print the size of the voxel/bounding boxes |
Definition at line 958 of file octree_base_node.hpp.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::queryBBIncludes | ( | const Eigen::Vector3d & | min_bb, |
const Eigen::Vector3d & | max_bb, | ||
size_t | query_depth, | ||
AlignedPointTVector & | dst | ||
) | [virtual] |
Recursively add points that fall into the queried bounding box up to the query_depth.
[in] | min_bb | the minimum corner of the bounding box, indexed by X,Y,Z coordinates |
[in] | max_bb | the maximum corner of the bounding box, indexed by X,Y,Z coordinates |
[in] | query_depth | the maximum depth to query in the octree for points within the bounding box |
[out] | dst | destion of points returned by the queries |
Definition at line 1517 of file octree_base_node.hpp.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::queryBBIncludes | ( | const Eigen::Vector3d & | min_bb, |
const Eigen::Vector3d & | max_bb, | ||
size_t | query_depth, | ||
const pcl::PCLPointCloud2::Ptr & | dst_blob | ||
) | [virtual] |
Recursively add points that fall into the queried bounding box up to the query_depth.
[in] | min_bb | the minimum corner of the bounding box, indexed by X,Y,Z coordinates |
[in] | max_bb | the maximum corner of the bounding box, indexed by X,Y,Z coordinates |
[in] | query_depth | the maximum depth to query in the octree for points within the bounding box |
[out] | dst_blob | destion of points returned by the queries |
Definition at line 1393 of file octree_base_node.hpp.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::queryBBIncludes_subsample | ( | const Eigen::Vector3d & | min_bb, |
const Eigen::Vector3d & | max_bb, | ||
boost::uint64_t | query_depth, | ||
const double | percent, | ||
AlignedPointTVector & | v | ||
) | [virtual] |
Recursively add points that fall into the queried bounding box up to the query_depth.
[in] | min_bb | the minimum corner of the bounding box, indexed by X,Y,Z coordinates |
[in] | max_bb | the maximum corner of the bounding box, indexed by X,Y,Z coordinates |
[in] | query_depth | |
[out] | v | std::list of points returned by the query |
Definition at line 1658 of file octree_base_node.hpp.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::queryBBIncludes_subsample | ( | const Eigen::Vector3d & | min_bb, |
const Eigen::Vector3d & | max_bb, | ||
boost::uint64_t | query_depth, | ||
const pcl::PCLPointCloud2::Ptr & | dst_blob, | ||
double | percent = 1.0 |
||
) | [virtual] |
Definition at line 1591 of file octree_base_node.hpp.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::queryBBIntersects | ( | const Eigen::Vector3d & | min_bb, |
const Eigen::Vector3d & | max_bb, | ||
const boost::uint32_t | query_depth, | ||
std::list< std::string > & | file_names | ||
) | [virtual] |
Recursive acquires PCD paths to any node with which the queried bounding box intersects (at query_depth only).
Definition at line 1353 of file octree_base_node.hpp.
void pcl::outofcore::OutofcoreOctreeBaseNode< Container, PointT >::queryFrustum | ( | const double | planes[24], |
std::list< std::string > & | file_names | ||
) |
Definition at line 1063 of file octree_base_node.hpp.
void pcl::outofcore::OutofcoreOctreeBaseNode< Container, PointT >::queryFrustum | ( | const double | planes[24], |
std::list< std::string > & | file_names, | ||
const boost::uint32_t | query_depth, | ||
const bool | skip_vfc_check = false |
||
) |
Definition at line 1069 of file octree_base_node.hpp.
void pcl::outofcore::OutofcoreOctreeBaseNode< Container, PointT >::queryFrustum | ( | const double | planes[24], |
const Eigen::Vector3d & | eye, | ||
const Eigen::Matrix4d & | view_projection_matrix, | ||
std::list< std::string > & | file_names, | ||
const boost::uint32_t | query_depth, | ||
const bool | skip_vfc_check = false |
||
) |
Definition at line 1218 of file octree_base_node.hpp.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::randomSample | ( | const AlignedPointTVector & | p, |
AlignedPointTVector & | insertBuff, | ||
const bool | skip_bb_check | ||
) | [protected] |
Randomly sample point data.
Definition at line 572 of file octree_base_node.hpp.
int pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::read | ( | pcl::PCLPointCloud2::Ptr & | output_cloud | ) | [virtual] |
Definition at line 1916 of file octree_base_node.hpp.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::recFreeChildren | ( | ) | [protected] |
Method which recursively free children of this node.
Definition at line 335 of file octree_base_node.hpp.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::saveIdx | ( | bool | recursive | ) | [protected] |
Save node's metadata to file.
[in] | recursive,: | if false, save only this node's metadata to file; if true, recursively save all children's metadata to files as well |
Definition at line 284 of file octree_base_node.hpp.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::saveMetadataToFile | ( | const boost::filesystem::path & | path | ) | [protected] |
Write JSON metadata for this node to file.
boost::uint64_t pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::size | ( | ) | const [inline, protected] |
Number of points in the payload.
Definition at line 463 of file octree_base_node.h.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::sortOctantIndices | ( | const pcl::PCLPointCloud2::Ptr & | input_cloud, |
std::vector< std::vector< int > > & | indices, | ||
const Eigen::Vector3d & | mid_xyz | ||
) | [protected] |
Sorts the indices based on x,y,z fields and pushes the index into the proper octant's vector; This could be overloaded with a parallelized implementation.
Definition at line 2007 of file octree_base_node.hpp.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::subdividePoint | ( | const PointT & | point, |
std::vector< AlignedPointTVector > & | c | ||
) | [protected] |
Subdivide a single point into a specific child node.
Definition at line 710 of file octree_base_node.hpp.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::subdividePoints | ( | const AlignedPointTVector & | p, |
std::vector< AlignedPointTVector > & | c, | ||
const bool | skip_bb_check | ||
) | [protected] |
Subdivide points to pass to child nodes.
Definition at line 688 of file octree_base_node.hpp.
void pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::writeVPythonVisual | ( | std::ofstream & | file | ) |
Write a python visual script to file.
[in] | file | output file stream to write the python visual script |
Definition at line 1895 of file octree_base_node.hpp.
OutofcoreOctreeBaseNode<ContainerT, PointT>* makenode_norec | ( | const boost::filesystem::path & | path, |
OutofcoreOctreeBaseNode< ContainerT, PointT > * | super | ||
) | [friend] |
Non-class function which creates a single child leaf; used with queryBBIntersects_noload to avoid loading the data from disk.
friend class OutofcoreOctreeBase< ContainerT, PointT > [friend] |
Definition at line 94 of file octree_base_node.h.
void queryBBIntersects_noload | ( | const boost::filesystem::path & | rootnode, |
const Eigen::Vector3d & | min, | ||
const Eigen::Vector3d & | max, | ||
const boost::uint32_t | query_depth, | ||
std::list< std::string > & | bin_name | ||
) | [friend] |
Non-class method which performs a bounding box query without loading any of the point cloud data from disk.
void queryBBIntersects_noload | ( | OutofcoreOctreeBaseNode< ContainerT, PointT > * | current, |
const Eigen::Vector3d & | min, | ||
const Eigen::Vector3d & | max, | ||
const boost::uint32_t | query_depth, | ||
std::list< std::string > & | bin_name | ||
) | [friend] |
Non-class method overload.
std::vector<OutofcoreOctreeBaseNode*> pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::children_ [protected] |
The children of this node.
Definition at line 538 of file octree_base_node.h.
size_t pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::depth_ [protected] |
Depth in the tree, root is 0, root's children are 1, ...
Definition at line 536 of file octree_base_node.h.
OutofcoreOctreeBase<ContainerT, PointT>* pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::m_tree_ [protected] |
The tree we belong to.
Definition at line 530 of file octree_base_node.h.
const std::string pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::node_container_basename = "node" [static] |
Definition at line 115 of file octree_base_node.h.
const std::string pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::node_container_extension = ".oct_dat" [static] |
Definition at line 117 of file octree_base_node.h.
const std::string pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::node_index_basename = "node" [static] |
Definition at line 114 of file octree_base_node.h.
const std::string pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::node_index_extension = ".oct_idx" [static] |
Definition at line 116 of file octree_base_node.h.
OutofcoreOctreeNodeMetadata::Ptr pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::node_metadata_ [protected] |
Definition at line 568 of file octree_base_node.h.
uint64_t pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::num_children_ [protected] |
Number of children on disk. This is only changed when a new node is created.
Definition at line 541 of file octree_base_node.h.
uint64_t pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::num_loaded_children_ [protected] |
Number of loaded children this node has.
"Loaded" means child OctreeBaseNodes have been allocated, and their metadata files have been loaded into memory. num_loaded_children_ <= num_children_
Definition at line 549 of file octree_base_node.h.
OutofcoreOctreeBaseNode* pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::parent_ [protected] |
super-node
Definition at line 534 of file octree_base_node.h.
boost::shared_ptr<ContainerT> pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::payload_ [protected] |
what holds the points. currently a custom class, but in theory you could use an stl container if you rewrote some of this class. I used to use deques for this...
Definition at line 554 of file octree_base_node.h.
const std::string pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::pcd_extension = ".pcd" [static, protected] |
Extension for this class to find the pcd files on disk.
Definition at line 566 of file octree_base_node.h.
boost::mt19937 pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::rand_gen_ [static, protected] |
Mersenne Twister: A 623-dimensionally equidistributed uniform pseudo-random number generator.
Definition at line 561 of file octree_base_node.h.
boost::mutex pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::rng_mutex_ [static, protected] |
Random number generator mutex.
Definition at line 557 of file octree_base_node.h.
const boost::uint32_t pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::rngseed = 0xAABBCCDD [static, protected] |
Random number generator seed.
Definition at line 564 of file octree_base_node.h.
OutofcoreOctreeBaseNode* pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::root_node_ [protected] |
The root node of the tree we belong to.
Definition at line 532 of file octree_base_node.h.
const double pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::sample_percent_ = .125 [static] |
Definition at line 118 of file octree_base_node.h.