point_cloud_library / 1.12.1 / classpcl_1_1outofcore_1_1_outofcore_octree_base.html /

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

#include <pcl/outofcore/octree_base.h>

Public Types

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

Public Member Functions

OutofcoreOctreeBase (const boost::filesystem::path &root_node_name, const bool load_all)
Load an existing tree. More...
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. More...
OutofcoreOctreeBase (const std::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. More...
virtual ~OutofcoreOctreeBase ()
std::uint64_t addDataToLeaf (const AlignedPointTVector &p)
Recursively add points to the tree. More...
std::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. More...
std::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. More...
std::uint64_t addPointCloud_and_genLOD (pcl::PCLPointCloud2::Ptr &input_cloud)
Recursively add points to the tree. More...
std::uint64_t addPointCloud (pcl::PCLPointCloud2::Ptr &input_cloud)
std::uint64_t addPointCloud_and_genLOD (PointCloudConstPtr point_cloud)
std::uint64_t addDataToLeaf_and_genLOD (AlignedPointTVector &p)
Recursively add points to the tree subsampling LODs on the way. More...
void queryFrustum (const double *planes, std::list< std::string > &file_names) const
void queryFrustum (const double *planes, std::list< std::string > &file_names, const std::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 std::uint32_t query_depth) const
void queryBBIntersects (const Eigen::Vector3d &min, const Eigen::Vector3d &max, const std::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. More...
void queryBBIncludes (const Eigen::Vector3d &min, const Eigen::Vector3d &max, const std::uint64_t query_depth, AlignedPointTVector &dst) const
Get Points in BB, only points inside BB. More...
void queryBBIncludes (const Eigen::Vector3d &min, const Eigen::Vector3d &max, const std::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. More...
void queryBBIncludes_subsample (const Eigen::Vector3d &min, const Eigen::Vector3d &max, std::uint64_t query_depth, const double percent, AlignedPointTVector &dst) const
Returns a random subsample of points within the given bounding box at query_depth. More...
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. More...
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. More...
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. More...
std::uint64_t getNumPointsAtDepth (const std::uint64_t &depth_index) const
Get number of points at specified LOD. More...
std::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. More...
const std::vector< std::uint64_t > & getNumPointsVector () const
Get number of points at each LOD. More...
std::uint64_t getDepth () const
Get number of LODs, which is the height of the tree. More...
std::uint64_t getTreeDepth () const
bool getBinDimension (double &x, double &y) const
Computes the expected voxel dimensions at the leaves. More...
double getVoxelSideLength (const std::uint64_t &depth) const
gets the side length of an (assumed) perfect cubic voxel. More...
double getVoxelSideLength () const
Gets the smallest (assumed) cubic voxel side lengths. More...
const std::string & getCoordSystem () const
Get coordinate system tag from the JSON metadata file. More...
void buildLOD ()
Generate multi-resolution LODs for the tree, which are a uniform random sampling all child leafs below the node. More...
void printBoundingBox (const std::size_t query_depth) const
Prints size of BBox to stdout. More...
void printBoundingBox (OutofcoreNodeType &node) const
Prints the coordinates of the bounding box of the node to stdout. More...
void printBoundingBox () const
Prints size of the bounding boxes to stdou. More...
void getOccupiedVoxelCenters (AlignedPointTVector &voxel_centers, std::size_t query_depth) const
Returns the voxel centers of all existing voxels at query_depth. More...
void getOccupiedVoxelCenters (std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > &voxel_centers, std::size_t query_depth) const
Returns the voxel centers of all existing voxels at query_depth. More...
void getOccupiedVoxelCenters (AlignedPointTVector &voxel_centers) const
Gets the voxel centers of all occupied/existing leaves of the tree. More...
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. More...
void convertToXYZ ()
Save each .bin file as an XYZ file. More...
void writeVPythonVisual (const boost::filesystem::path filename)
Write a python script using the vpython module containing all the bounding boxes. More...
OutofcoreNodeType * getBranchChildPtr (const BranchNode &branch_arg, unsigned char childIdx_arg) const
pcl::Filter< pcl::PCLPointCloud2 >::Ptr getLODFilter ()
const pcl::Filter< pcl::PCLPointCloud2 >::ConstPtr getLODFilter () const
void setLODFilter (const pcl::Filter< pcl::PCLPointCloud2 >::Ptr &filter_arg)
Sets the filter to use when building the levels of depth. More...
double getSamplePercent () const
Returns the sample_percent_ used when constructing the LOD. More...
void setSamplePercent (const double sample_percent_arg)
Sets the sampling percent for constructing LODs. More...

Protected Member Functions

void init (const std::uint64_t &depth, const Eigen::Vector3d &min, const Eigen::Vector3d &max, const boost::filesystem::path &root_name, const std::string &coord_sys)
OutofcoreOctreeBase (OutofcoreOctreeBase &rval)
OutofcoreOctreeBase (const OutofcoreOctreeBase &rval)
OutofcoreOctreeBase & operator= (OutofcoreOctreeBase &rval)
OutofcoreOctreeBase & operator= (const OutofcoreOctreeBase &rval)
OutofcoreNodeType * getRootNode ()
void DeAllocEmptyNodeCache (OutofcoreNodeType *current)
flush empty nodes only More...
void saveToFile ()
Write octree definition ".octree" (defined by octree_extension_) to disk. More...
void buildLODRecursive (const std::vector< BranchNode * > &current_branch)
recursive portion of lod builder More...
void incrementPointsInLOD (std::uint64_t depth, std::uint64_t inc)
Increment current depths (LOD for branch nodes) point count; called by addDataAtMaxDepth in OutofcoreOctreeBaseNode. More...
bool checkExtension (const boost::filesystem::path &path_name)
Auxiliary function to validate path_name extension is .octree. More...
void flushToDisk ()
Flush all nodes' cache. More...
void flushToDiskLazy ()
Flush all non leaf nodes' cache. More...
void DeAllocEmptyNodeCache ()
Flush empty nodes only. More...

Protected Attributes

OutofcoreNodeType * root_node_
Pointer to the root node of the octree data structure. More...
std::shared_timed_mutex read_write_mutex_
shared mutex for controlling read/write access to disk More...
OutofcoreOctreeBaseMetadata::Ptr metadata_

Static Protected Attributes

const static std::string TREE_EXTENSION_ = ".octree"
defined as ".octree" to append to treepath files More...
const static int OUTOFCORE_VERSION_ = static_cast<int>(3)
const static std::uint64_t LOAD_COUNT_ = static_cast<std::uint64_t>(2e9)

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.nosp@m..sch.nosp@m.loss@.nosp@m.urba.nosp@m.nrobo.nosp@m.tics.nosp@m..net with any questions. http://www.urbanrobotics.net/. This code was integrated for the Urban Robotics Code Sprint (URCS) by Stephen Fox ( foxst.nosp@m.ephe.nosp@m.nd@gm.nosp@m.ail..nosp@m.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 pcl::outofcore::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 pcl::outofcore::OutofcoreOctreeNodeMetadata, and .octree is the JSON-based octree metadata file managed by pcl::outofcore::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.nosp@m..sch.nosp@m.loss@.nosp@m.urba.nosp@m.nrobo.nosp@m.tics.nosp@m..net)
Stephen Fox, Urban Robotics Code Sprint ( foxst.nosp@m.ephe.nosp@m.nd@gm.nosp@m.ail..nosp@m.com)

Definition at line 150 of file octree_base.h.

Member Typedef Documentation

AlignedPointTVector

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
using pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::AlignedPointTVector = std::vector<PointT, Eigen::aligned_allocator<PointT> >

Definition at line 189 of file octree_base.h.

BranchNode

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
using pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::BranchNode = OutofcoreOctreeBaseNode<ContainerT, PointT>

Definition at line 166 of file octree_base.h.

BreadthFirstConstIterator

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
using pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::BreadthFirstConstIterator = const OutofcoreBreadthFirstIterator<PointT, ContainerT>

Definition at line 173 of file octree_base.h.

BreadthFirstIterator

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
using pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::BreadthFirstIterator = OutofcoreBreadthFirstIterator<PointT, ContainerT>

Definition at line 172 of file octree_base.h.

ConstIterator

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
using pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::ConstIterator = const OutofcoreDepthFirstIterator<PointT, ContainerT>

Definition at line 170 of file octree_base.h.

ConstPtr

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
using pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::ConstPtr = shared_ptr<const OutofcoreOctreeBase<ContainerT, PointT> >

Definition at line 179 of file octree_base.h.

DepthFirstConstIterator

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
using pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::DepthFirstConstIterator = const OutofcoreDepthFirstIterator<PointT, ContainerT>

Definition at line 176 of file octree_base.h.

DepthFirstIterator

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
using pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::DepthFirstIterator = OutofcoreDepthFirstIterator<PointT, ContainerT>

Definition at line 175 of file octree_base.h.

IndicesConstPtr

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
using pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::IndicesConstPtr = shared_ptr<const pcl::Indices>

Definition at line 184 of file octree_base.h.

IndicesPtr

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
using pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::IndicesPtr = shared_ptr<pcl::Indices>

Definition at line 183 of file octree_base.h.

Iterator

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
using pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::Iterator = OutofcoreDepthFirstIterator<PointT, ContainerT>

Definition at line 169 of file octree_base.h.

LeafNode

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
using pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::LeafNode = OutofcoreOctreeBaseNode<ContainerT, PointT>

Definition at line 167 of file octree_base.h.

octree_disk

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

Definition at line 158 of file octree_base.h.

octree_disk_node

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
using pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::octree_disk_node = OutofcoreOctreeBaseNode<OutofcoreOctreeDiskContainer<PointT>, PointT >

Definition at line 159 of file octree_base.h.

octree_ram

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
using pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::octree_ram = OutofcoreOctreeBase<OutofcoreOctreeRamContainer<PointT>, PointT>

Definition at line 161 of file octree_base.h.

octree_ram_node

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
using pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::octree_ram_node = OutofcoreOctreeBaseNode<OutofcoreOctreeRamContainer<PointT>, PointT>

Definition at line 162 of file octree_base.h.

OutofcoreNodeType

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
using pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::OutofcoreNodeType = OutofcoreOctreeBaseNode<ContainerT, PointT>

Definition at line 164 of file octree_base.h.

PointCloud

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

Definition at line 181 of file octree_base.h.

PointCloudConstPtr

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
using pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::PointCloudConstPtr = typename PointCloud::ConstPtr

Definition at line 187 of file octree_base.h.

PointCloudPtr

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
using pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::PointCloudPtr = typename PointCloud::Ptr

Definition at line 186 of file octree_base.h.

Ptr

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
using pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::Ptr = shared_ptr<OutofcoreOctreeBase<ContainerT, PointT> >

Definition at line 178 of file octree_base.h.

Constructor & Destructor Documentation

OutofcoreOctreeBase() [1/5]

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
root_node_name Path to the top-level tree/tree.oct_idx metadata file
load_all Load entire tree metadata (does not load any points from disk)
Exceptions
PCLException for bad extension (root node metadata must be .oct_idx extension)

Definition at line 77 of file octree_base.hpp.

OutofcoreOctreeBase() [2/5]

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
min Bounding box min
max Bounding box max
resolution_arg 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
Exceptions
PCLException if root file extension does not match pcl::outofcore::OutofcoreOctreeBaseNode::node_index_extension

Definition at line 105 of file octree_base.hpp.

OutofcoreOctreeBase() [3/5]

template<typename ContainerT , typename PointT >
pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::OutofcoreOctreeBase ( const std::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_depth Specifies a fixed number of LODs to generate, which is the depth of the tree
min Bounding box min
max Bounding 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_name must end in ".oct_idx"
coord_sys Coordinate system which is stored in the JSON metadata
Exceptions
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 octree_base.hpp.

~OutofcoreOctreeBase()

template<typename ContainerT , typename PointT >
pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::~OutofcoreOctreeBase
virtual

Definition at line 189 of file octree_base.hpp.

OutofcoreOctreeBase() [4/5]

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::OutofcoreOctreeBase ( OutofcoreOctreeBase< ContainerT, PointT > & rval )
protected

OutofcoreOctreeBase() [5/5]

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

addDataToLeaf()

template<typename ContainerT , typename PointT >
std::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 octree_base.hpp.

addDataToLeaf_and_genLOD()

template<typename ContainerT , typename PointT >
std::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 octree_base.hpp.

addPointCloud() [1/3]

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
std::uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::addPointCloud ( pcl::PCLPointCloud2::Ptr & input_cloud )

addPointCloud() [2/3]

template<typename ContainerT , typename PointT >
std::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_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.
Returns
Number of points successfully copied from the point cloud to the octree

Definition at line 232 of file octree_base.hpp.

addPointCloud() [3/3]

template<typename ContainerT , typename PointT >
std::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_cloud Pointer 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 octree_base.hpp.

Referenced by pcl::outofcore::OutofcoreOctreeBase< ContainerT, pcl::PointXYZRGB >::addPointCloud().

addPointCloud_and_genLOD() [1/2]

template<typename ContainerT , typename PointT >
std::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_cloud The 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 octree_base.hpp.

addPointCloud_and_genLOD() [2/2]

template<typename ContainerT , typename PointT >
std::uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::addPointCloud_and_genLOD ( PointCloudConstPtr point_cloud )

Definition at line 243 of file octree_base.hpp.

buildLOD()

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 562 of file octree_base.hpp.

buildLODRecursive()

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 594 of file octree_base.hpp.

checkExtension()

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 700 of file octree_base.hpp.

convertToXYZ()

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 octree_base.hpp.

DeAllocEmptyNodeCache() [1/2]

template<typename ContainerT , typename PointT >
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::DeAllocEmptyNodeCache
protected

Flush empty nodes only.

Definition at line 470 of file octree_base.hpp.

DeAllocEmptyNodeCache() [2/2]

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

flush empty nodes only

flushToDisk()

template<typename ContainerT , typename PointT >
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::flushToDisk
protected

Flush all nodes' cache.

Definition at line 445 of file octree_base.hpp.

Referenced by pcl::outofcore::OutofcoreOctreeBase< ContainerT, pcl::PointXYZRGB >::flushToDisk().

flushToDiskLazy()

template<typename ContainerT , typename PointT >
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::flushToDiskLazy
protected

Flush all non leaf nodes' cache.

Definition at line 453 of file octree_base.hpp.

Referenced by pcl::outofcore::OutofcoreOctreeBase< ContainerT, pcl::PointXYZRGB >::flushToDiskLazy().

getBinDimension()

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 527 of file octree_base.hpp.

getBoundingBox()

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.

Parameters
min
max

Definition at line 362 of file octree_base.hpp.

Referenced by pcl::outofcore::OutofcoreOctreeBase< ContainerT, pcl::PointXYZRGB >::getBoundingBox().

getBranchChildPtr()

template<typename ContainerT , typename PointT >
OutofcoreOctreeBaseNode< ContainerT, PointT > * pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getBranchChildPtr ( const BranchNode & branch_arg,
unsigned char childIdx_arg
) const

Definition at line 496 of file octree_base.hpp.

getCoordSystem()

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 470 of file octree_base.h.

getDepth()

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
std::uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getDepth ( ) const
inline

getLODFilter() [1/2]

template<typename ContainerT , typename PointT >
const pcl::Filter< pcl::PCLPointCloud2 >::ConstPtr pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getLODFilter

Definition at line 503 of file octree_base.hpp.

getLODFilter() [2/2]

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
const pcl::Filter<pcl::PCLPointCloud2>::ConstPtr pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getLODFilter ( ) const

getNumPointsAtDepth()

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
std::uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getNumPointsAtDepth ( const std::uint64_t & depth_index ) const
inline

Get number of points at specified LOD.

Parameters
[in] depth_index the 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 406 of file octree_base.h.

getNumPointsVector()

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
const std::vector<std::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 427 of file octree_base.h.

getOccupiedVoxelCenters() [1/4]

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 516 of file octree_base.h.

getOccupiedVoxelCenters() [2/4]

template<typename ContainerT , typename PointT >
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getOccupiedVoxelCenters ( AlignedPointTVector & voxel_centers,
std::size_t query_depth
) const

Returns the voxel centers of all existing voxels at query_depth.

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

Definition at line 384 of file octree_base.hpp.

Referenced by pcl::outofcore::OutofcoreOctreeBase< ContainerT, pcl::PointXYZRGB >::getOccupiedVoxelCenters().

getOccupiedVoxelCenters() [3/4]

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_centers std::vector of the centers of all occupied leaves of the octree

Definition at line 525 of file octree_base.h.

getOccupiedVoxelCenters() [4/4]

template<typename ContainerT , typename PointT >
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getOccupiedVoxelCenters ( std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > & voxel_centers,
std::size_t query_depth
) const

Returns the voxel centers of all existing voxels at query_depth.

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

Definition at line 400 of file octree_base.hpp.

getRootNode()

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
OutofcoreNodeType* pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getRootNode ( )
inlineprotected

getSamplePercent()

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 557 of file octree_base.h.

getTreeDepth()

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
std::uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getTreeDepth ( ) const
inline

getVoxelSideLength() [1/2]

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 462 of file octree_base.h.

Referenced by pcl::outofcore::OutofcoreOctreeBase< ContainerT, pcl::PointXYZRGB >::getVoxelSideLength().

getVoxelSideLength() [2/2]

template<typename ContainerT , typename PointT >
double pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::getVoxelSideLength ( const std::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 551 of file octree_base.hpp.

incrementPointsInLOD()

template<typename ContainerT , typename PointT >
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::incrementPointsInLOD ( std::uint64_t depth,
std::uint64_t inc
)
inlineprotected

Increment current depths (LOD for branch nodes) point count; called by addDataAtMaxDepth in OutofcoreOctreeBaseNode.

Definition at line 686 of file octree_base.hpp.

init()

template<typename ContainerT , typename PointT >
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::init ( const std::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 octree_base.hpp.

operator=() [1/2]

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

operator=() [2/2]

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
OutofcoreOctreeBase& pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::operator= ( OutofcoreOctreeBase< ContainerT, PointT > & rval )
protected

printBoundingBox() [1/3]

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 495 of file octree_base.h.

Referenced by pcl::outofcore::OutofcoreOctreeBase< ContainerT, pcl::PointXYZRGB >::printBoundingBox().

printBoundingBox() [2/3]

template<typename ContainerT , typename PointT >
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::printBoundingBox ( const std::size_t query_depth ) const

Prints size of BBox to stdout.

Definition at line 375 of file octree_base.hpp.

printBoundingBox() [3/3]

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.

queryBBIncludes() [1/2]

template<typename ContainerT , typename PointT >
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::queryBBIncludes ( const Eigen::Vector3d & min,
const Eigen::Vector3d & max,
const std::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] 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
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] dst The destination vector of points

Definition at line 313 of file octree_base.hpp.

Referenced by pcl::outofcore::OutofcoreOctreeBase< ContainerT, pcl::PointXYZRGB >::queryBoundingBox().

queryBBIncludes() [2/2]

template<typename ContainerT , typename PointT >
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::queryBBIncludes ( const Eigen::Vector3d & min,
const Eigen::Vector3d & max,
const std::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] 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 octree_base.hpp.

queryBBIncludes_subsample()

template<typename ContainerT , typename PointT >
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::queryBBIncludes_subsample ( const Eigen::Vector3d & min,
const Eigen::Vector3d & max,
std::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] 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.
percent
[out] dst The destination in which to return the points.

Definition at line 338 of file octree_base.hpp.

queryBBIntersects()

template<typename ContainerT , typename PointT >
void pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::queryBBIntersects ( const Eigen::Vector3d & min,
const Eigen::Vector3d & max,
const std::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] 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 octree_base.hpp.

queryBoundingBox() [1/2]

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] 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 octree_base.hpp.

queryBoundingBox() [2/2]

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
inlinevirtual

Returns list of pcd files from nodes whose bounding boxes intersect with the input bounding box.

Parameters
[in] min The minimum corner of the input bounding box.
[in] max The maximum corner of the input bounding box.
query_depth
[out] filenames The list of paths to the PCD files which can be loaded and processed.

Definition at line 383 of file octree_base.h.

queryBoundingBoxNumPoints()

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
std::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] 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.
Returns
Number of points in the bounding box at depth query_depth

queryFrustum() [1/3]

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 std::uint32_t query_depth
) const

Definition at line 299 of file octree_base.hpp.

queryFrustum() [2/3]

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

queryFrustum() [3/3]

template<typename Container , typename PointT >
void pcl::outofcore::OutofcoreOctreeBase< Container, PointT >::queryFrustum ( const double * planes,
std::list< std::string > & file_names,
const std::uint32_t query_depth
) const

Definition at line 290 of file octree_base.hpp.

saveToFile()

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 octree_base.hpp.

setLODFilter()

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 519 of file octree_base.hpp.

setSamplePercent()

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_arg Percentage between 0 and 1.

Definition at line 565 of file octree_base.h.

writeVPythonVisual()

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 octree_base.hpp.

Friends And Related Function Documentation

OutofcoreOctreeBaseNode< ContainerT, PointT >

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
friend class OutofcoreOctreeBaseNode< ContainerT, PointT >
friend

Definition at line 152 of file octree_base.h.

pcl::outofcore::OutofcoreIteratorBase< PointT, ContainerT >

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

Definition at line 153 of file octree_base.h.

Member Data Documentation

LOAD_COUNT_

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
const static std::uint64_t pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::LOAD_COUNT_ = static_cast<std::uint64_t>(2e9)
staticprotected

Definition at line 640 of file octree_base.h.

metadata_

OUTOFCORE_VERSION_

template<typename ContainerT , typename PointT >
const int pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::OUTOFCORE_VERSION_ = static_cast<int>(3)
staticprotected

Definition at line 638 of file octree_base.h.

read_write_mutex_

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
std::shared_timed_mutex pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::read_write_mutex_
mutableprotected

shared mutex for controlling read/write access to disk

Definition at line 630 of file octree_base.h.

Referenced by pcl::outofcore::OutofcoreOctreeBase< ContainerT, pcl::PointXYZRGB >::queryBoundingBox().

root_node_

template<typename ContainerT = OutofcoreOctreeDiskContainer<pcl::PointXYZ>, typename PointT = pcl::PointXYZ>
OutofcoreNodeType* pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::root_node_
protected

TREE_EXTENSION_

template<typename ContainerT , typename PointT >
const std::string pcl::outofcore::OutofcoreOctreeBase< ContainerT, PointT >::TREE_EXTENSION_ = ".octree"
staticprotected

defined as ".octree" to append to treepath files

Note
this might change

Definition at line 637 of file octree_base.h.


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

© 2009–2012, Willow Garage, Inc.
© 2012–, Open Perception, Inc.
Licensed under the BSD License.
https://pointclouds.org/documentation/classpcl_1_1outofcore_1_1_outofcore_octree_base.html