This code defines the octree used for point storage at Urban Robotics. More...
#include <octree_base.h>
Public Types | |
typedef std::vector< PointT, Eigen::aligned_allocator < PointT > > | AlignedPointTVector |
typedef OutofcoreOctreeBaseNode < ContainerT, PointT > | BranchNode |
typedef const OutofcoreBreadthFirstIterator < PointT, ContainerT > | BreadthFirstConstIterator |
typedef OutofcoreBreadthFirstIterator < PointT, ContainerT > | BreadthFirstIterator |
typedef const OutofcoreDepthFirstIterator < PointT, ContainerT > | ConstIterator |
typedef boost::shared_ptr < const OutofcoreOctreeBase < ContainerT, PointT > > | ConstPtr |
typedef const OutofcoreDepthFirstIterator < PointT, ContainerT > | DepthFirstConstIterator |
typedef OutofcoreDepthFirstIterator < PointT, ContainerT > | DepthFirstIterator |
typedef boost::shared_ptr < const std::vector< int > > | IndicesConstPtr |
typedef boost::shared_ptr < std::vector< int > > | IndicesPtr |
typedef OutofcoreDepthFirstIterator < PointT, ContainerT > | Iterator |
typedef OutofcoreOctreeBaseNode < ContainerT, PointT > | LeafNode |
typedef OutofcoreOctreeBase < OutofcoreOctreeDiskContainer < PointT >, PointT > | octree_disk |
typedef OutofcoreOctreeBaseNode < OutofcoreOctreeDiskContainer < PointT >, PointT > | octree_disk_node |
typedef OutofcoreOctreeBase < OutofcoreOctreeRamContainer < PointT >, PointT > | octree_ram |
typedef OutofcoreOctreeBaseNode < OutofcoreOctreeRamContainer < PointT >, PointT > | octree_ram_node |
typedef OutofcoreOctreeBaseNode < ContainerT, PointT > | OutofcoreNodeType |
typedef pcl::PointCloud< PointT > | PointCloud |
typedef boost::shared_ptr < const PointCloud > | PointCloudConstPtr |
typedef boost::shared_ptr < PointCloud > | PointCloudPtr |
typedef boost::shared_ptr < OutofcoreOctreeBase < ContainerT, PointT > > | Ptr |
Public Member Functions | |
boost::uint64_t | addDataToLeaf (const AlignedPointTVector &p) |
Recursively add points to the tree. | |
boost::uint64_t | addDataToLeaf_and_genLOD (AlignedPointTVector &p) |
Recursively add points to the tree subsampling LODs on the way. | |
boost::uint64_t | addPointCloud (PointCloudConstPtr point_cloud) |
Copies the points from the point_cloud falling within the bounding box of the octree to the out-of-core octree; this is an interface to addDataToLeaf and can be used multiple times. | |
boost::uint64_t | addPointCloud (pcl::PCLPointCloud2::Ptr &input_cloud, const bool skip_bb_check=false) |
Recursively copies points from input_cloud into the leaf nodes of the out-of-core octree, and stores them to disk. | |
boost::uint64_t | addPointCloud (pcl::PCLPointCloud2::Ptr &input_cloud) |
boost::uint64_t | addPointCloud_and_genLOD (pcl::PCLPointCloud2::Ptr &input_cloud) |
Recursively add points to the tree. | |
boost::uint64_t | addPointCloud_and_genLOD (PointCloudConstPtr point_cloud) |
void | buildLOD () |
Generate multi-resolution LODs for the tree, which are a uniform random sampling all child leafs below the node. | |
void | convertToXYZ () |
Save each .bin file as an XYZ file. | |
bool | getBinDimension (double &x, double &y) const |
Computes the expected voxel dimensions at the leaves. | |
bool | getBoundingBox (Eigen::Vector3d &min, Eigen::Vector3d &max) const |
Get the overall bounding box of the outofcore octree; this is the same as the bounding box of the root_node_ node. | |
OutofcoreNodeType * | getBranchChildPtr (const BranchNode &branch_arg, unsigned char childIdx_arg) const |
const std::string & | getCoordSystem () const |
Get coordinate system tag from the JSON metadata file. | |
boost::uint64_t | getDepth () const |
Get number of LODs, which is the height of the tree. | |
pcl::Filter < pcl::PCLPointCloud2 >::Ptr | getLODFilter () |
const pcl::Filter < pcl::PCLPointCloud2 > ::ConstPtr | getLODFilter () const |
boost::uint64_t | getNumPointsAtDepth (const boost::uint64_t &depth_index) const |
Get number of points at specified LOD. | |
const std::vector < boost::uint64_t > & | getNumPointsVector () const |
Get number of points at each LOD. | |
void | getOccupiedVoxelCenters (AlignedPointTVector &voxel_centers, size_t query_depth) const |
Returns the voxel centers of all existing voxels at query_depth. | |
void | getOccupiedVoxelCenters (std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > &voxel_centers, size_t query_depth) const |
Returns the voxel centers of all existing voxels at query_depth. | |
void | getOccupiedVoxelCenters (AlignedPointTVector &voxel_centers) const |
Gets the voxel centers of all occupied/existing leaves of the tree. | |
void | getOccupiedVoxelCenters (std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > &voxel_centers) const |
Returns the voxel centers of all occupied/existing leaves of the tree. | |
double | getSamplePercent () const |
Returns the sample_percent_ used when constructing the LOD. | |
boost::uint64_t | getTreeDepth () const |
double | getVoxelSideLength (const boost::uint64_t &depth) const |
gets the side length of an (assumed) perfect cubic voxel. | |
double | getVoxelSideLength () const |
Gets the smallest (assumed) cubic voxel side lengths. The smallest voxels are located at the max depth of the tree. | |
OutofcoreOctreeBase (const boost::filesystem::path &root_node_name, const bool load_all) | |
Load an existing tree. | |
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) | |
Create a new tree. | |
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) | |
Create a new tree; will not overwrite existing tree of same name. | |
void | printBoundingBox (const size_t query_depth) const |
Prints size of BBox to stdout. | |
void | printBoundingBox (OutofcoreNodeType &node) const |
Prints the coordinates of the bounding box of the node to stdout. | |
void | printBoundingBox () const |
Prints size of the bounding boxes to stdou. | |
void | queryBBIncludes (const Eigen::Vector3d &min, const Eigen::Vector3d &max, const boost::uint64_t query_depth, AlignedPointTVector &dst) const |
Get Points in BB, only points inside BB. The query processes the data at each node, filtering points that fall out of the query bounds, and returns a single, concatenated point cloud. | |
void | queryBBIncludes (const Eigen::Vector3d &min, const Eigen::Vector3d &max, const boost::uint64_t query_depth, const pcl::PCLPointCloud2::Ptr &dst_blob) const |
Query all points falling within the input bounding box at query_depth and return a PCLPointCloud2 object in dst_blob. | |
void | queryBBIncludes_subsample (const Eigen::Vector3d &min, const Eigen::Vector3d &max, uint64_t query_depth, const double percent, AlignedPointTVector &dst) const |
Returns a random subsample of points within the given bounding box at query_depth. | |
void | queryBBIntersects (const Eigen::Vector3d &min, const Eigen::Vector3d &max, const boost::uint32_t query_depth, std::list< std::string > &bin_name) const |
Get a list of file paths at query_depth that intersect with your bounding box specified by min and max. When querying with this method, you may be stuck with extra data (some outside of your query bounds) that reside in the files. | |
virtual void | queryBoundingBox (const Eigen::Vector3d &min, const Eigen::Vector3d &max, const int query_depth, const pcl::PCLPointCloud2::Ptr &dst_blob, double percent=1.0) |
Query all points falling within the input bounding box at query_depth and return a PCLPointCloud2 object in dst_blob. If the optional argument for filter is given, points are processed by that filter before returning. | |
virtual void | queryBoundingBox (const Eigen::Vector3d &min, const Eigen::Vector3d &max, const int query_depth, std::list< std::string > &filenames) const |
Returns list of pcd files from nodes whose bounding boxes intersect with the input bounding box. | |
boost::uint64_t | queryBoundingBoxNumPoints (const Eigen::Vector3d &min, const Eigen::Vector3d &max, const int query_depth, bool load_from_disk=true) |
Queries the number of points in a bounding box. | |
void | queryFrustum (const double *planes, std::list< std::string > &file_names) const |
void | queryFrustum (const double *planes, std::list< std::string > &file_names, const boost::uint32_t query_depth) const |
void | 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 |
void | setLODFilter (const pcl::Filter< pcl::PCLPointCloud2 >::Ptr &filter_arg) |
Sets the filter to use when building the levels of depth. Recommended filters are pcl::RandomSample<pcl::PCLPointCloud2> or pcl::VoxelGrid. | |
void | setSamplePercent (const double sample_percent_arg) |
Sets the sampling percent for constructing LODs. Each LOD gets sample_percent^d points. | |
void | writeVPythonVisual (const boost::filesystem::path filename) |
Write a python script using the vpython module containing all the bounding boxes. | |
virtual | ~OutofcoreOctreeBase () |
Protected Member Functions | |
void | buildLODRecursive (const std::vector< BranchNode * > ¤t_branch) |
recursive portion of lod builder | |
bool | checkExtension (const boost::filesystem::path &path_name) |
Auxiliary function to validate path_name extension is .octree. | |
void | DeAllocEmptyNodeCache (OutofcoreNodeType *current) |
flush empty nodes only | |
void | DeAllocEmptyNodeCache () |
DEPRECATED - Flush empty nodes only. | |
void | flushToDisk () |
DEPRECATED - Flush all nodes' cache. | |
void | flushToDiskLazy () |
DEPRECATED - Flush all non leaf nodes' cache. | |
OutofcoreNodeType * | getRootNode () |
void | incrementPointsInLOD (boost::uint64_t depth, boost::uint64_t inc) |
Increment current depths (LOD for branch nodes) point count; called by addDataAtMaxDepth in OutofcoreOctreeBaseNode. | |
void | 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) |
OutofcoreOctreeBase & | operator= (OutofcoreOctreeBase &rval) |
OutofcoreOctreeBase & | operator= (const OutofcoreOctreeBase &rval) |
OutofcoreOctreeBase (OutofcoreOctreeBase &rval) | |
OutofcoreOctreeBase (const OutofcoreOctreeBase &rval) | |
void | saveToFile () |
Write octree definition ".octree" (defined by octree_extension_) to disk. | |
Protected Attributes | |
boost::shared_ptr < OutofcoreOctreeBaseMetadata > | metadata_ |
boost::shared_mutex | read_write_mutex_ |
shared mutex for controlling read/write access to disk | |
OutofcoreNodeType * | root_node_ |
Pointer to the root node of the octree data structure. | |
Static Protected Attributes | |
static const uint64_t | LOAD_COUNT_ = static_cast<uint64_t>(2e9) |
static const int | OUTOFCORE_VERSION_ = static_cast<int>(3) |
static const std::string | TREE_EXTENSION_ = ".octree" |
defined as ".octree" to append to treepath files | |
Private Member Functions | |
boost::uint64_t | calculateDepth (const Eigen::Vector3d &min_bb, const Eigen::Vector3d &max_bb, const double leaf_resolution) |
Auxiliary function to compute the depth of the tree given the bounding box and the desired size of the leaf voxels. | |
void | enlargeToCube (Eigen::Vector3d &bb_min, Eigen::Vector3d &bb_max) |
Auxiliary function to enlarge a bounding box to a cube. | |
Private Attributes | |
pcl::RandomSample < pcl::PCLPointCloud2 >::Ptr | lod_filter_ptr_ |
double | sample_percent_ |
Friends | |
class | OutofcoreOctreeBaseNode< ContainerT, PointT > |
class | pcl::outofcore::OutofcoreIteratorBase< PointT, ContainerT > |
This code defines the octree used for point storage at Urban Robotics.
The primary purpose of this class is an interface to the recursive traversal (recursion handled by OutofcoreOctreeBaseNode) of the in-memory/top-level octree structure. The metadata in each node can be loaded entirely into main memory, from which the tree can be traversed recursively in this state. This class provides an the interface for:
For lower-level node access, there is a Depth-First iterator for traversing the trees with direct access to the nodes. This can be used for implementing other algorithms, and other iterators can be written in a similar fashion.
The format of the octree is stored on disk in a hierarchical octree structure, where .oct_idx are the JSON-based node metadata files managed by OutofcoreOctreeNodeMetadata, and .octree is the JSON-based octree metadata file managed by OutofcoreOctreeBaseMetadata. Children of each node live in up to eight subdirectories named from 0 to 7, where a metadata and optionally a pcd file will exist. The PCD files are stored in compressed binary PCD format, containing all of the fields existing in the PCLPointCloud2 objects originally inserted into the out of core object.
A brief outline of the out of core octree can be seen below. The files in [brackets] exist only when the LOD are built.
At this point in time, there is not support for multiple trees existing in a single directory hierarchy.
tree_name/ tree_name.oct_idx tree_name.octree [tree_name-uuid.pcd] 0/ tree_name.oct_idx [tree_name-uuid.pcd] 0/ ... 1/ ... ... 0/ tree_name.oct_idx tree_name.pcd 1/ ... 7/
Definition at line 149 of file outofcore/include/pcl/outofcore/octree_base.h.
typedef std::vector<PointT, Eigen::aligned_allocator<PointT> > pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::AlignedPointTVector |
Definition at line 188 of file outofcore/include/pcl/outofcore/octree_base.h.
typedef OutofcoreOctreeBaseNode<ContainerT, PointT> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::BranchNode |
Definition at line 165 of file outofcore/include/pcl/outofcore/octree_base.h.
typedef const OutofcoreBreadthFirstIterator<PointT, ContainerT> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::BreadthFirstConstIterator |
Definition at line 172 of file outofcore/include/pcl/outofcore/octree_base.h.
typedef OutofcoreBreadthFirstIterator<PointT, ContainerT> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::BreadthFirstIterator |
Definition at line 171 of file outofcore/include/pcl/outofcore/octree_base.h.
typedef const OutofcoreDepthFirstIterator<PointT, ContainerT> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::ConstIterator |
Definition at line 169 of file outofcore/include/pcl/outofcore/octree_base.h.
typedef boost::shared_ptr<const OutofcoreOctreeBase<ContainerT, PointT> > pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::ConstPtr |
Definition at line 178 of file outofcore/include/pcl/outofcore/octree_base.h.
typedef const OutofcoreDepthFirstIterator<PointT, ContainerT> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::DepthFirstConstIterator |
Definition at line 175 of file outofcore/include/pcl/outofcore/octree_base.h.
typedef OutofcoreDepthFirstIterator<PointT, ContainerT> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::DepthFirstIterator |
Definition at line 174 of file outofcore/include/pcl/outofcore/octree_base.h.
typedef boost::shared_ptr<const std::vector<int> > pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::IndicesConstPtr |
Definition at line 183 of file outofcore/include/pcl/outofcore/octree_base.h.
typedef boost::shared_ptr<std::vector<int> > pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::IndicesPtr |
Definition at line 182 of file outofcore/include/pcl/outofcore/octree_base.h.
typedef OutofcoreDepthFirstIterator<PointT, ContainerT> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::Iterator |
Definition at line 168 of file outofcore/include/pcl/outofcore/octree_base.h.
typedef OutofcoreOctreeBaseNode<ContainerT, PointT> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::LeafNode |
Definition at line 166 of file outofcore/include/pcl/outofcore/octree_base.h.
typedef OutofcoreOctreeBase<OutofcoreOctreeDiskContainer<PointT>, PointT > pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::octree_disk |
Definition at line 157 of file outofcore/include/pcl/outofcore/octree_base.h.
typedef OutofcoreOctreeBaseNode<OutofcoreOctreeDiskContainer<PointT>, PointT > pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::octree_disk_node |
Definition at line 158 of file outofcore/include/pcl/outofcore/octree_base.h.
typedef OutofcoreOctreeBase<OutofcoreOctreeRamContainer<PointT>, PointT> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::octree_ram |
Definition at line 160 of file outofcore/include/pcl/outofcore/octree_base.h.
typedef OutofcoreOctreeBaseNode<OutofcoreOctreeRamContainer<PointT>, PointT> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::octree_ram_node |
Definition at line 161 of file outofcore/include/pcl/outofcore/octree_base.h.
typedef OutofcoreOctreeBaseNode<ContainerT, PointT> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::OutofcoreNodeType |
Definition at line 163 of file outofcore/include/pcl/outofcore/octree_base.h.
typedef pcl::PointCloud<PointT> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::PointCloud |
Definition at line 180 of file outofcore/include/pcl/outofcore/octree_base.h.
typedef boost::shared_ptr<const PointCloud> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::PointCloudConstPtr |
Definition at line 186 of file outofcore/include/pcl/outofcore/octree_base.h.
typedef boost::shared_ptr<PointCloud> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::PointCloudPtr |
Definition at line 185 of file outofcore/include/pcl/outofcore/octree_base.h.
typedef boost::shared_ptr<OutofcoreOctreeBase<ContainerT, PointT> > pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::Ptr |
Definition at line 177 of file outofcore/include/pcl/outofcore/octree_base.h.
pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::OutofcoreOctreeBase | ( | const boost::filesystem::path & | root_node_name, |
const bool | load_all | ||
) |
Load an existing tree.
If load_all is set, the BB and point count for every node is loaded, otherwise only the root node is actually created, and the rest will be generated on insertion or query.
Path | to the top-level tree/tree.oct_idx metadata file |
load_all | Load entire tree metadata (does not load any points from disk) |
PCLException | for bad extension (root node metadata must be .oct_idx extension) |
Definition at line 77 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
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 | ||
) |
Create a new tree.
Create a new tree rootname with specified bounding box; will remove and overwrite existing tree with the same name
Computes the depth of the tree based on desired leaf , then calls the other constructor.
min | Bounding box min |
max | Bounding box max |
node_dim_meters | Node dimension in meters (assuming your point data is in meters) |
root_node_name | must end in ".oct_idx" |
coord_sys | Coordinate system which is stored in the JSON metadata |
PCLException | if root file extension does not match OutofcoreOctreeBaseNode::node_index_extension |
Definition at line 105 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
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 | ||
) |
Create a new tree; will not overwrite existing tree of same name.
Create a new tree rootname with specified bounding box; will not overwrite an existing tree
max_depth | Specifies a fixed number of LODs to generate, which is the depth of the tree |
min | Bounding box min |
max | Bounding box max |
root_node_name | must end in ".oct_idx" |
coord_sys | Coordinate system which is stored in the JSON metadata |
PCLException | if the parent directory has existing children (detects an existing tree) |
PCLException | if file extension is not ".oct_idx" |
Definition at line 127 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::~OutofcoreOctreeBase | ( | ) | [virtual] |
Definition at line 189 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::OutofcoreOctreeBase | ( | OutofcoreOctreeBase< ContainerT, PointT > & | rval | ) | [protected] |
pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::OutofcoreOctreeBase | ( | const OutofcoreOctreeBase< ContainerT, PointT > & | rval | ) | [protected] |
boost::uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::addDataToLeaf | ( | const AlignedPointTVector & | p | ) |
Recursively add points to the tree.
Definition at line 208 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
boost::uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::addDataToLeaf_and_genLOD | ( | AlignedPointTVector & | p | ) |
Recursively add points to the tree subsampling LODs on the way.
shared read_write_mutex lock occurs
Definition at line 270 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
boost::uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::addPointCloud | ( | PointCloudConstPtr | point_cloud | ) |
Copies the points from the point_cloud falling within the bounding box of the octree to the out-of-core octree; this is an interface to addDataToLeaf and can be used multiple times.
point_cloud | Pointer to the point cloud data to copy to the outofcore octree; Assumes templated PointT matches for each. |
Definition at line 224 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
boost::uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::addPointCloud | ( | pcl::PCLPointCloud2::Ptr & | input_cloud, |
const bool | skip_bb_check = false |
||
) |
Recursively copies points from input_cloud into the leaf nodes of the out-of-core octree, and stores them to disk.
[in] | input_cloud | The cloud of points to be inserted into the out-of-core octree. Note if multiple PCLPointCloud2 objects are added to the tree, this assumes that they all have exactly the same fields. |
[in] | skip_bb_check | (default=false) whether to skip the bounding box check on insertion. Note the bounding box check is never skipped in the current implementation. |
Definition at line 232 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
boost::uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::addPointCloud | ( | pcl::PCLPointCloud2::Ptr & | input_cloud | ) |
boost::uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::addPointCloud_and_genLOD | ( | pcl::PCLPointCloud2::Ptr & | input_cloud | ) |
Recursively add points to the tree.
Recursively add points to the tree. 1/8 of the remaining points at each LOD are stored at each internal node of the octree until either (a) runs out of points, in which case the leaf is not at the maximum depth of the tree, or (b) a larger set of points falls in the leaf at the maximum depth. Note unlike the old implementation, multiple copies of the same point will not be added at multiple LODs as it walks the tree. Once the point is added to the octree, it is no longer propagated further down the tree.
[in] | input_cloud | The input cloud of points which will be copied into the sorted nodes of the out-of-core octree |
Definition at line 254 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
boost::uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::addPointCloud_and_genLOD | ( | PointCloudConstPtr | point_cloud | ) |
Definition at line 243 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::buildLOD | ( | ) |
Generate multi-resolution LODs for the tree, which are a uniform random sampling all child leafs below the node.
Definition at line 560 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::buildLODRecursive | ( | const std::vector< BranchNode * > & | current_branch | ) | [protected] |
recursive portion of lod builder
Definition at line 592 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
boost::uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::calculateDepth | ( | const Eigen::Vector3d & | min_bb, |
const Eigen::Vector3d & | max_bb, | ||
const double | leaf_resolution | ||
) | [private] |
Auxiliary function to compute the depth of the tree given the bounding box and the desired size of the leaf voxels.
Definition at line 729 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
bool pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::checkExtension | ( | const boost::filesystem::path & | path_name | ) | [protected] |
Auxiliary function to validate path_name extension is .octree.
Definition at line 698 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::convertToXYZ | ( | ) |
Save each .bin file as an XYZ file.
Definition at line 461 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::DeAllocEmptyNodeCache | ( | OutofcoreNodeType * | current | ) | [protected] |
flush empty nodes only
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::DeAllocEmptyNodeCache | ( | ) | [protected] |
DEPRECATED - Flush empty nodes only.
Definition at line 470 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::enlargeToCube | ( | Eigen::Vector3d & | bb_min, |
Eigen::Vector3d & | bb_max | ||
) | [private] |
Auxiliary function to enlarge a bounding box to a cube.
Definition at line 712 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::flushToDisk | ( | ) | [protected] |
DEPRECATED - Flush all nodes' cache.
Definition at line 445 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::flushToDiskLazy | ( | ) | [protected] |
DEPRECATED - Flush all non leaf nodes' cache.
Definition at line 453 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
bool pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getBinDimension | ( | double & | x, |
double & | y | ||
) | const |
Computes the expected voxel dimensions at the leaves.
Definition at line 525 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
bool pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getBoundingBox | ( | Eigen::Vector3d & | min, |
Eigen::Vector3d & | max | ||
) | const |
Get the overall bounding box of the outofcore octree; this is the same as the bounding box of the root_node_ node.
Definition at line 362 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
OutofcoreOctreeBaseNode< ContainerT, PointT > * pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getBranchChildPtr | ( | const BranchNode & | branch_arg, |
unsigned char | childIdx_arg | ||
) | const |
Definition at line 494 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
const std::string& pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getCoordSystem | ( | ) | const [inline] |
Get coordinate system tag from the JSON metadata file.
Definition at line 462 of file outofcore/include/pcl/outofcore/octree_base.h.
boost::uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getDepth | ( | ) | const [inline] |
Get number of LODs, which is the height of the tree.
Definition at line 427 of file outofcore/include/pcl/outofcore/octree_base.h.
pcl::Filter< pcl::PCLPointCloud2 >::Ptr pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getLODFilter | ( | ) |
Definition at line 501 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
const pcl::Filter< pcl::PCLPointCloud2 >::ConstPtr pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getLODFilter | ( | ) | const |
Definition at line 509 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
boost::uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getNumPointsAtDepth | ( | const boost::uint64_t & | depth_index | ) | const [inline] |
Get number of points at specified LOD.
[in] | depth | the level of detail at which we want the number of points (0 is root, 1, 2,...) |
Definition at line 398 of file outofcore/include/pcl/outofcore/octree_base.h.
const std::vector<boost::uint64_t>& pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getNumPointsVector | ( | ) | const [inline] |
Get number of points at each LOD.
Definition at line 419 of file outofcore/include/pcl/outofcore/octree_base.h.
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getOccupiedVoxelCenters | ( | AlignedPointTVector & | voxel_centers, |
size_t | query_depth | ||
) | const |
Returns the voxel centers of all existing voxels at query_depth.
[in] | query_depth,: | the depth of the tree at which to retrieve occupied/existing voxels |
[out] | vector | of PointXYZ voxel centers for nodes that exist at that depth |
Definition at line 384 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getOccupiedVoxelCenters | ( | std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > & | voxel_centers, |
size_t | query_depth | ||
) | const |
Returns the voxel centers of all existing voxels at query_depth.
[in] | query_depth,: | the depth of the tree at which to retrieve occupied/existing voxels |
[out] | vector | of PointXYZ voxel centers for nodes that exist at that depth |
Definition at line 400 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getOccupiedVoxelCenters | ( | AlignedPointTVector & | voxel_centers | ) | const [inline] |
Gets the voxel centers of all occupied/existing leaves of the tree.
Definition at line 508 of file outofcore/include/pcl/outofcore/octree_base.h.
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getOccupiedVoxelCenters | ( | std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > & | voxel_centers | ) | const [inline] |
Returns the voxel centers of all occupied/existing leaves of the tree.
[out] | voxel_centers | std::vector of the centers of all occupied leaves of the octree |
Definition at line 517 of file outofcore/include/pcl/outofcore/octree_base.h.
OutofcoreNodeType* pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getRootNode | ( | ) | [inline, protected] |
Definition at line 577 of file outofcore/include/pcl/outofcore/octree_base.h.
double pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getSamplePercent | ( | ) | const [inline] |
Returns the sample_percent_ used when constructing the LOD.
Definition at line 549 of file outofcore/include/pcl/outofcore/octree_base.h.
boost::uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getTreeDepth | ( | ) | const [inline] |
Definition at line 433 of file outofcore/include/pcl/outofcore/octree_base.h.
double pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getVoxelSideLength | ( | const boost::uint64_t & | depth | ) | const |
gets the side length of an (assumed) perfect cubic voxel.
Definition at line 549 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
double pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getVoxelSideLength | ( | ) | const [inline] |
Gets the smallest (assumed) cubic voxel side lengths. The smallest voxels are located at the max depth of the tree.
Definition at line 454 of file outofcore/include/pcl/outofcore/octree_base.h.
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::incrementPointsInLOD | ( | boost::uint64_t | depth, |
boost::uint64_t | inc | ||
) | [inline, protected] |
Increment current depths (LOD for branch nodes) point count; called by addDataAtMaxDepth in OutofcoreOctreeBaseNode.
Definition at line 684 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
void 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 | ||
) | [protected] |
Definition at line 140 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
OutofcoreOctreeBase& pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::operator= | ( | OutofcoreOctreeBase< ContainerT, PointT > & | rval | ) | [protected] |
OutofcoreOctreeBase& pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::operator= | ( | const OutofcoreOctreeBase< ContainerT, PointT > & | rval | ) | [protected] |
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::printBoundingBox | ( | const size_t | query_depth | ) | const |
Prints size of BBox to stdout.
Definition at line 375 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::printBoundingBox | ( | OutofcoreNodeType & | node | ) | const |
Prints the coordinates of the bounding box of the node to stdout.
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::printBoundingBox | ( | ) | const [inline] |
Prints size of the bounding boxes to stdou.
Definition at line 487 of file outofcore/include/pcl/outofcore/octree_base.h.
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::queryBBIncludes | ( | const Eigen::Vector3d & | min, |
const Eigen::Vector3d & | max, | ||
const boost::uint64_t | query_depth, | ||
AlignedPointTVector & | dst | ||
) | const |
Get Points in BB, only points inside BB. The query processes the data at each node, filtering points that fall out of the query bounds, and returns a single, concatenated point cloud.
[in] | min | The minimum corner of the bounding box for querying |
[in] | max | The maximum corner of the bounding box for querying |
[in] | query_depth | The depth from which point data will be taken |
[out] | dst | The destination vector of points |
Definition at line 313 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
void 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 |
Query all points falling within the input bounding box at query_depth and return a PCLPointCloud2 object in dst_blob.
[in] | min | The minimum corner of the input bounding box. |
[in] | max | The maximum corner of the input bounding box. |
[in] | query_depth | The query depth at which to search for points; only points at this depth are returned |
[out] | dst_blob | Storage location for the points satisfying the query. |
Definition at line 324 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
void 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 |
Returns a random subsample of points within the given bounding box at query_depth.
[in] | min | The minimum corner of the boudning box to query. |
[out] | max | The maximum corner of the bounding box to query. |
[in] | query_depth | The depth in the tree at which to look for the points. Only returns points within the given bounding box at the specified query_depth. |
[out] | dst | The destination in which to return the points. |
Definition at line 338 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
void 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 |
Get a list of file paths at query_depth that intersect with your bounding box specified by min and max. When querying with this method, you may be stuck with extra data (some outside of your query bounds) that reside in the files.
[in] | min | The minimum corner of the bounding box |
[in] | max | The maximum corner of the bounding box |
[in] | query_depth | 0 is root, (this->depth) is full |
[out] | bin_name | List of paths to point data files (PCD currently) which satisfy the query |
Definition at line 416 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
void 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 |
||
) | [virtual] |
Query all points falling within the input bounding box at query_depth and return a PCLPointCloud2 object in dst_blob. If the optional argument for filter is given, points are processed by that filter before returning.
[in] | min | The minimum corner of the input bounding box. |
[in] | max | The maximum corner of the input bounding box. |
[in] | query_depth | The depth of tree at which to query; only points at this depth are returned |
[out] | dst_blob | The destination in which points within the bounding box are stored. |
[in] | percent | optional sampling percentage which is applied after each time data are read from disk |
Definition at line 347 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
virtual void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::queryBoundingBox | ( | const Eigen::Vector3d & | min, |
const Eigen::Vector3d & | max, | ||
const int | query_depth, | ||
std::list< std::string > & | filenames | ||
) | const [inline, virtual] |
Returns list of pcd files from nodes whose bounding boxes intersect with the input bounding box.
[in] | min | The minimum corner of the input bounding box. |
[in] | max | The maximum corner of the input bounding box. |
[out] | filenames | The list of paths to the PCD files which can be loaded and processed. |
Definition at line 378 of file outofcore/include/pcl/outofcore/octree_base.h.
boost::uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::queryBoundingBoxNumPoints | ( | const Eigen::Vector3d & | min, |
const Eigen::Vector3d & | max, | ||
const int | query_depth, | ||
bool | load_from_disk = true |
||
) |
Queries the number of points in a bounding box.
[in] | min | The minimum corner of the input bounding box |
[out] | max | The maximum corner of the input bounding box |
[in] | query_depth | The depth of the nodes to restrict the search to (only this depth is searched) |
[in] | load_from_disk | (default true) Whether to load PCD files to count exactly the number of points within the bounding box; setting this to false will return an upper bound by just reading the number of points from the PCD header, even if there may be some points in that node do not fall within the query bounding box. |
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::queryFrustum | ( | const double * | planes, |
std::list< std::string > & | file_names | ||
) | const |
void pcl::outofcore::OutofcoreOctreeBase< Container, PointT >::queryFrustum | ( | const double * | planes, |
std::list< std::string > & | file_names, | ||
const boost::uint32_t | query_depth | ||
) | const |
Definition at line 290 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
void pcl::outofcore::OutofcoreOctreeBase< Container, 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 |
Definition at line 299 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::saveToFile | ( | ) | [protected] |
Write octree definition ".octree" (defined by octree_extension_) to disk.
Definition at line 200 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::setLODFilter | ( | const pcl::Filter< pcl::PCLPointCloud2 >::Ptr & | filter_arg | ) |
Sets the filter to use when building the levels of depth. Recommended filters are pcl::RandomSample<pcl::PCLPointCloud2> or pcl::VoxelGrid.
Definition at line 517 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::setSamplePercent | ( | const double | sample_percent_arg | ) | [inline] |
Sets the sampling percent for constructing LODs. Each LOD gets sample_percent^d points.
[in] | sample_percent_arg | Percentage between 0 and 1. |
Definition at line 557 of file outofcore/include/pcl/outofcore/octree_base.h.
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::writeVPythonVisual | ( | const boost::filesystem::path | filename | ) |
Write a python script using the vpython module containing all the bounding boxes.
Definition at line 433 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.
friend class OutofcoreOctreeBaseNode< ContainerT, PointT > [friend] |
Definition at line 151 of file outofcore/include/pcl/outofcore/octree_base.h.
friend class pcl::outofcore::OutofcoreIteratorBase< PointT, ContainerT > [friend] |
Definition at line 152 of file outofcore/include/pcl/outofcore/octree_base.h.
const uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::LOAD_COUNT_ = static_cast<uint64_t>(2e9) [static, protected] |
Definition at line 639 of file outofcore/include/pcl/outofcore/octree_base.h.
pcl::RandomSample<pcl::PCLPointCloud2>::Ptr pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::lod_filter_ptr_ [private] |
Definition at line 653 of file outofcore/include/pcl/outofcore/octree_base.h.
boost::shared_ptr<OutofcoreOctreeBaseMetadata> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::metadata_ [protected] |
Definition at line 631 of file outofcore/include/pcl/outofcore/octree_base.h.
const int pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::OUTOFCORE_VERSION_ = static_cast<int>(3) [static, protected] |
Definition at line 637 of file outofcore/include/pcl/outofcore/octree_base.h.
boost::shared_mutex pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::read_write_mutex_ [mutable, protected] |
shared mutex for controlling read/write access to disk
Definition at line 629 of file outofcore/include/pcl/outofcore/octree_base.h.
OutofcoreNodeType* pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::root_node_ [protected] |
Pointer to the root node of the octree data structure.
Definition at line 626 of file outofcore/include/pcl/outofcore/octree_base.h.
double pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::sample_percent_ [private] |
Definition at line 651 of file outofcore/include/pcl/outofcore/octree_base.h.
const std::string pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::TREE_EXTENSION_ = ".octree" [static, protected] |
defined as ".octree" to append to treepath files
Definition at line 636 of file outofcore/include/pcl/outofcore/octree_base.h.