Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Static Protected Attributes | Private Member Functions | Private Attributes | Friends
pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT > Class Template Reference

This code defines the octree used for point storage at Urban Robotics. More...

#include <octree_base.h>

List of all members.

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< PointTPointCloud
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.
OutofcoreNodeTypegetBranchChildPtr (const BranchNode &branch_arg, unsigned char childIdx_arg) const
const std::stringgetCoordSystem () 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 * > &current_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.
OutofcoreNodeTypegetRootNode ()
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)
OutofcoreOctreeBaseoperator= (OutofcoreOctreeBase &rval)
OutofcoreOctreeBaseoperator= (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
OutofcoreNodeTyperoot_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 >

Detailed Description

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
class pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >

This code defines the octree used for point storage at Urban Robotics.

Note:
Code was adapted from the Urban Robotics out of core octree implementation. Contact Jacob Schloss <jacob.schloss@urbanrobotics.net> with any questions. http://www.urbanrobotics.net/. This code was integrated for the Urban Robotics Code Sprint (URCS) by Stephen Fox (foxstephend@gmail.com). Additional development notes can be found at http://www.pointclouds.org/blog/urcs/.

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:

  1. Point/Region insertion methods
  2. Frustrum/box/region queries
  3. Parameterization of resolution, container type, etc...

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/
     
Author:
Jacob Schloss (jacob.schloss@urbanrobotics.net)
Stephen Fox, Urban Robotics Code Sprint (foxstephend@gmail.com)

Definition at line 149 of file outofcore/include/pcl/outofcore/octree_base.h.


Member Typedef Documentation

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
typedef std::vector<PointT, Eigen::aligned_allocator<PointT> > pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::AlignedPointTVector
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
typedef OutofcoreOctreeBaseNode<ContainerT, PointT> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::BranchNode
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
typedef const OutofcoreBreadthFirstIterator<PointT, ContainerT> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::BreadthFirstConstIterator
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
typedef OutofcoreBreadthFirstIterator<PointT, ContainerT> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::BreadthFirstIterator
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
typedef const OutofcoreDepthFirstIterator<PointT, ContainerT> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::ConstIterator
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
typedef boost::shared_ptr<const OutofcoreOctreeBase<ContainerT, PointT> > pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::ConstPtr
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
typedef const OutofcoreDepthFirstIterator<PointT, ContainerT> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::DepthFirstConstIterator
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
typedef OutofcoreDepthFirstIterator<PointT, ContainerT> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::DepthFirstIterator
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
typedef boost::shared_ptr<const std::vector<int> > pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::IndicesConstPtr
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
typedef boost::shared_ptr<std::vector<int> > pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::IndicesPtr
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
typedef OutofcoreDepthFirstIterator<PointT, ContainerT> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::Iterator
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
typedef OutofcoreOctreeBaseNode<ContainerT, PointT> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::LeafNode
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
typedef OutofcoreOctreeBase<OutofcoreOctreeDiskContainer<PointT>, PointT > pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::octree_disk
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
typedef OutofcoreOctreeBaseNode<OutofcoreOctreeDiskContainer<PointT>, PointT > pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::octree_disk_node
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
typedef OutofcoreOctreeBase<OutofcoreOctreeRamContainer<PointT>, PointT> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::octree_ram
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
typedef OutofcoreOctreeBaseNode<OutofcoreOctreeRamContainer<PointT>, PointT> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::octree_ram_node
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
typedef OutofcoreOctreeBaseNode<ContainerT, PointT> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::OutofcoreNodeType
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
typedef pcl::PointCloud<PointT> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::PointCloud
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
typedef boost::shared_ptr<const PointCloud> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::PointCloudConstPtr
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
typedef boost::shared_ptr<PointCloud> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::PointCloudPtr
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
typedef boost::shared_ptr<OutofcoreOctreeBase<ContainerT, PointT> > pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::Ptr

Constructor & Destructor Documentation

template<typename ContainerT , typename PointT >
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.

Parameters:
Pathto the top-level tree/tree.oct_idx metadata file
load_allLoad entire tree metadata (does not load any points from disk)
Exceptions:
PCLExceptionfor bad extension (root node metadata must be .oct_idx extension)

Definition at line 77 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.

template<typename ContainerT , typename PointT >
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.

Parameters:
minBounding box min
maxBounding box max
node_dim_metersNode dimension in meters (assuming your point data is in meters)
root_node_namemust end in ".oct_idx"
coord_sysCoordinate system which is stored in the JSON metadata
Exceptions:
PCLExceptionif root file extension does not match OutofcoreOctreeBaseNode::node_index_extension

Definition at line 105 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.

template<typename ContainerT , typename PointT >
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

Parameters:
max_depthSpecifies a fixed number of LODs to generate, which is the depth of the tree
minBounding box min
maxBounding box max
Note:
Bounding box of the tree must be set before inserting any points. The tree cannot be resized at this time.
Parameters:
root_node_namemust end in ".oct_idx"
coord_sysCoordinate system which is stored in the JSON metadata
Exceptions:
PCLExceptionif the parent directory has existing children (detects an existing tree)
PCLExceptionif file extension is not ".oct_idx"

Definition at line 127 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.

template<typename ContainerT , typename PointT >
pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::~OutofcoreOctreeBase ( ) [virtual]
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::OutofcoreOctreeBase ( OutofcoreOctreeBase< ContainerT, PointT > &  rval) [protected]
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::OutofcoreOctreeBase ( const OutofcoreOctreeBase< ContainerT, PointT > &  rval) [protected]

Member Function Documentation

template<typename ContainerT , typename PointT >
boost::uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::addDataToLeaf ( const AlignedPointTVector p)

Recursively add points to the tree.

Note:
shared read_write_mutex lock occurs

Definition at line 208 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.

template<typename ContainerT , typename PointT >
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.

template<typename ContainerT , typename PointT >
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.

Parameters:
point_cloudPointer to the point cloud data to copy to the outofcore octree; Assumes templated PointT matches for each.
Returns:
Number of points successfully copied from the point cloud to the octree.

Definition at line 224 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.

template<typename ContainerT , typename PointT >
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.

Parameters:
[in]input_cloudThe 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.
Returns:
Number of poitns successfully copied from the point cloud to the octree

Definition at line 232 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
boost::uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::addPointCloud ( pcl::PCLPointCloud2::Ptr input_cloud)
template<typename ContainerT , typename PointT >
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.

Parameters:
[in]input_cloudThe input cloud of points which will be copied into the sorted nodes of the out-of-core octree
Returns:
The total number of points added to the out-of-core octree.

Definition at line 254 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.

template<typename ContainerT , typename PointT >
boost::uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::addPointCloud_and_genLOD ( PointCloudConstPtr  point_cloud)
template<typename ContainerT , typename PointT >
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.

template<typename ContainerT , typename PointT >
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.

template<typename ContainerT , typename PointT >
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.

template<typename ContainerT , typename PointT >
bool pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::checkExtension ( const boost::filesystem::path &  path_name) [protected]

Auxiliary function to validate path_name extension is .octree.

Returns:
0 if bad; 1 if extension is .oct_idx

Definition at line 698 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.

template<typename ContainerT , typename PointT >
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.

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::DeAllocEmptyNodeCache ( OutofcoreNodeType current) [protected]

flush empty nodes only

template<typename ContainerT , typename PointT >
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::DeAllocEmptyNodeCache ( ) [protected]

DEPRECATED - Flush empty nodes only.

Deprecated:

Definition at line 470 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.

template<typename ContainerT , typename PointT >
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.

template<typename ContainerT , typename PointT >
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::flushToDisk ( ) [protected]

DEPRECATED - Flush all nodes' cache.

Deprecated:
this was moved to the octree_node class

Definition at line 445 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.

template<typename ContainerT , typename PointT >
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::flushToDiskLazy ( ) [protected]

DEPRECATED - Flush all non leaf nodes' cache.

Deprecated:

Definition at line 453 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.

template<typename ContainerT , typename PointT >
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.

template<typename ContainerT , typename PointT >
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.

template<typename ContainerT , typename PointT >
OutofcoreOctreeBaseNode< ContainerT, PointT > * pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getBranchChildPtr ( const BranchNode branch_arg,
unsigned char  childIdx_arg 
) const
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
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.

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
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.

template<typename ContainerT , typename PointT >
pcl::Filter< pcl::PCLPointCloud2 >::Ptr pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getLODFilter ( )
template<typename ContainerT , typename PointT >
const pcl::Filter< pcl::PCLPointCloud2 >::ConstPtr pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getLODFilter ( ) const
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
boost::uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getNumPointsAtDepth ( const boost::uint64_t &  depth_index) const [inline]

Get number of points at specified LOD.

Parameters:
[in]depththe level of detail at which we want the number of points (0 is root, 1, 2,...)
Returns:
number of points in the tree at depth

Definition at line 398 of file outofcore/include/pcl/outofcore/octree_base.h.

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
const std::vector<boost::uint64_t>& pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getNumPointsVector ( ) const [inline]

Get number of points at each LOD.

Returns:
vector of number of points in each LOD indexed by each level of depth, 0 to the depth of the tree.

Definition at line 419 of file outofcore/include/pcl/outofcore/octree_base.h.

template<typename ContainerT , typename PointT >
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.

Parameters:
[in]query_depth,:the depth of the tree at which to retrieve occupied/existing voxels
[out]vectorof PointXYZ voxel centers for nodes that exist at that depth

Definition at line 384 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.

template<typename ContainerT , typename PointT >
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.

Parameters:
[in]query_depth,:the depth of the tree at which to retrieve occupied/existing voxels
[out]vectorof PointXYZ voxel centers for nodes that exist at that depth

Definition at line 400 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
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.

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
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.

Parameters:
[out]voxel_centersstd::vector of the centers of all occupied leaves of the octree

Definition at line 517 of file outofcore/include/pcl/outofcore/octree_base.h.

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
OutofcoreNodeType* pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getRootNode ( ) [inline, protected]
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
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.

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
boost::uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getTreeDepth ( ) const [inline]
template<typename ContainerT , typename PointT >
double pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getVoxelSideLength ( const boost::uint64_t &  depth) const

gets the side length of an (assumed) perfect cubic voxel.

Note:
If the initial bounding box specified in constructing the octree is not square, then this method does not return a sensible value
Returns:
the side length of the cubic voxel size at the specified depth

Definition at line 549 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
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.

Returns:
The side length of a the cubic voxel located at the leaves

Definition at line 454 of file outofcore/include/pcl/outofcore/octree_base.h.

template<typename ContainerT , typename PointT >
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.

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
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]
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
OutofcoreOctreeBase& pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::operator= ( OutofcoreOctreeBase< ContainerT, PointT > &  rval) [protected]
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
OutofcoreOctreeBase& pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::operator= ( const OutofcoreOctreeBase< ContainerT, PointT > &  rval) [protected]
template<typename ContainerT , typename PointT >
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.

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::printBoundingBox ( OutofcoreNodeType node) const

Prints the coordinates of the bounding box of the node to stdout.

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
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.

template<typename ContainerT , typename PointT >
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.

Parameters:
[in]minThe minimum corner of the bounding box for querying
[in]maxThe maximum corner of the bounding box for querying
[in]query_depthThe depth from which point data will be taken
Note:
If the LODs of the tree have not been built, you must specify the maximum depth in order to retrieve any data
Parameters:
[out]dstThe destination vector of points

Definition at line 313 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.

template<typename ContainerT , typename PointT >
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.

Parameters:
[in]minThe minimum corner of the input bounding box.
[in]maxThe maximum corner of the input bounding box.
[in]query_depthThe query depth at which to search for points; only points at this depth are returned
[out]dst_blobStorage location for the points satisfying the query.

Definition at line 324 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
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.

Parameters:
[in]minThe minimum corner of the boudning box to query.
[out]maxThe maximum corner of the bounding box to query.
[in]query_depthThe 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]dstThe destination in which to return the points.

Definition at line 338 of file outofcore/include/pcl/outofcore/impl/octree_base.hpp.

template<typename ContainerT , typename PointT >
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.

Parameters:
[in]minThe minimum corner of the bounding box
[in]maxThe maximum corner of the bounding box
[in]query_depth0 is root, (this->depth) is full
[out]bin_nameList 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.

template<typename ContainerT , typename PointT >
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.

Parameters:
[in]minThe minimum corner of the input bounding box.
[in]maxThe maximum corner of the input bounding box.
[in]query_depthThe depth of tree at which to query; only points at this depth are returned
[out]dst_blobThe destination in which points within the bounding box are stored.
[in]percentoptional 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.

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
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.

Parameters:
[in]minThe minimum corner of the input bounding box.
[in]maxThe maximum corner of the input bounding box.
[out]filenamesThe 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.

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
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.

Parameters:
[in]minThe minimum corner of the input bounding box
[out]maxThe maximum corner of the input bounding box
[in]query_depthThe 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.
Returns:
Number of points in the bounding box at depth query_depth
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::queryFrustum ( const double *  planes,
std::list< std::string > &  file_names 
) const
template<typename Container , typename PointT >
void pcl::outofcore::OutofcoreOctreeBase< Container, PointT >::queryFrustum ( const double *  planes,
std::list< std::string > &  file_names,
const boost::uint32_t  query_depth 
) const
template<typename Container , typename PointT >
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
template<typename ContainerT , typename PointT >
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.

template<typename ContainerT , typename PointT >
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.

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
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.

Parameters:
[in]sample_percent_argPercentage between 0 and 1.

Definition at line 557 of file outofcore/include/pcl/outofcore/octree_base.h.

template<typename ContainerT , typename PointT >
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.


Friends And Related Function Documentation

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
friend class OutofcoreOctreeBaseNode< ContainerT, PointT > [friend]
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
friend class pcl::outofcore::OutofcoreIteratorBase< PointT, ContainerT > [friend]

Member Data Documentation

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
const uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::LOAD_COUNT_ = static_cast<uint64_t>(2e9) [static, protected]
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
pcl::RandomSample<pcl::PCLPointCloud2>::Ptr pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::lod_filter_ptr_ [private]
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
boost::shared_ptr<OutofcoreOctreeBaseMetadata> pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::metadata_ [protected]
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
const int pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::OUTOFCORE_VERSION_ = static_cast<int>(3) [static, protected]
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
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.

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
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.

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
double pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::sample_percent_ [private]
template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
const std::string pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::TREE_EXTENSION_ = ".octree" [static, protected]

defined as ".octree" to append to treepath files

Note:
this might change

Definition at line 636 of file outofcore/include/pcl/outofcore/octree_base.h.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:44:32