Octree double buffer class More...
#include <octree2buf_base.h>

Public Types | |
| typedef BranchContainerT | BranchContainer |
| typedef BufferedBranchNode < BranchContainerT > | BranchNode |
| typedef OctreeBreadthFirstIterator < OctreeT > | BreadthFirstIterator |
| typedef const OctreeBreadthFirstIterator < OctreeT > | ConstBreadthFirstIterator |
| typedef const OctreeDepthFirstIterator < OctreeT > | ConstDepthFirstIterator |
| typedef const OctreeDepthFirstIterator < OctreeT > | ConstIterator |
| typedef const OctreeLeafNodeIterator < OctreeT > | ConstLeafNodeIterator |
| typedef OctreeDepthFirstIterator < OctreeT > | DepthFirstIterator |
| typedef OctreeDepthFirstIterator < OctreeT > | Iterator |
| typedef LeafContainerT | LeafContainer |
| typedef OctreeLeafNode < LeafContainerT > | LeafNode |
| typedef OctreeLeafNodeIterator < OctreeT > | LeafNodeIterator |
| typedef Octree2BufBase < LeafContainerT, BranchContainerT > | OctreeT |
Public Member Functions | |
| Iterator | begin (unsigned int max_depth_arg=0) |
| BreadthFirstIterator | breadth_begin (unsigned int max_depth_arg=0) |
| const BreadthFirstIterator | breadth_end () |
| LeafContainerT * | createLeaf (unsigned int idx_x_arg, unsigned int idx_y_arg, unsigned int idx_z_arg) |
| Create new leaf node at (idx_x_arg, idx_y_arg, idx_z_arg). | |
| void | deleteCurrentBuffer () |
| Delete the octree structure in the current buffer. | |
| void | deletePreviousBuffer () |
| Delete octree structure of previous buffer. | |
| void | deleteTree () |
| Delete the octree structure and its leaf nodes. | |
| DepthFirstIterator | depth_begin (unsigned int maxDepth_arg=0) |
| const DepthFirstIterator | depth_end () |
| void | deserializeTree (std::vector< char > &binary_tree_in_arg, bool do_XOR_decoding_arg=false) |
| Deserialize a binary octree description vector and create a corresponding octree structure. Leaf nodes are initialized with getDataTByKey(..). | |
| void | deserializeTree (std::vector< char > &binary_tree_in_arg, std::vector< LeafContainerT * > &leaf_container_vector_arg, bool do_XOR_decoding_arg=false) |
| Deserialize a binary octree description and create a corresponding octree structure. Leaf nodes are initialized with DataT elements from the dataVector. | |
| const Iterator | end () |
| bool | existLeaf (unsigned int idx_x_arg, unsigned int idx_y_arg, unsigned int idx_z_arg) const |
| Check for the existence of leaf node at (idx_x_arg, idx_y_arg, idx_z_arg). | |
| LeafContainerT * | findLeaf (unsigned int idx_x_arg, unsigned int idx_y_arg, unsigned int idx_z_arg) |
| Find leaf node at (idx_x_arg, idx_y_arg, idx_z_arg). | |
| std::size_t | getBranchCount () const |
| Return the amount of existing branches in the octree. | |
| std::size_t | getLeafCount () const |
| Return the amount of existing leafs in the octree. | |
| unsigned int | getTreeDepth () const |
| Get the maximum depth of the octree. | |
| LeafNodeIterator | leaf_begin (unsigned int max_depth_arg=0) |
| const LeafNodeIterator | leaf_end () |
| Octree2BufBase () | |
| Empty constructor. | |
| Octree2BufBase (const Octree2BufBase &source) | |
| Copy constructor. | |
| Octree2BufBase & | operator= (const Octree2BufBase &source) |
| Copy constructor. | |
| void | removeLeaf (unsigned int idx_x_arg, unsigned int idx_y_arg, unsigned int idx_z_arg) |
| Remove leaf node at (idx_x_arg, idx_y_arg, idx_z_arg). | |
| void | serializeLeafs (std::vector< LeafContainerT * > &leaf_container_vector_arg) |
| Outputs a vector of all DataT elements that are stored within the octree leaf nodes. | |
| void | serializeNewLeafs (std::vector< LeafContainerT * > &leaf_container_vector_arg) |
| Outputs a vector of all DataT elements from leaf nodes, that do not exist in the previous octree buffer. | |
| void | serializeTree (std::vector< char > &binary_tree_out_arg, bool do_XOR_encoding_arg=false) |
| Serialize octree into a binary output vector describing its branch node structure. | |
| void | serializeTree (std::vector< char > &binary_tree_out_arg, std::vector< LeafContainerT * > &leaf_container_vector_arg, bool do_XOR_encoding_arg=false) |
| Serialize octree into a binary output vector describing its branch node structure and and push all DataT elements stored in the octree to a vector. | |
| void | setMaxVoxelIndex (unsigned int max_voxel_index_arg) |
| Set the maximum amount of voxels per dimension. | |
| void | setTreeDepth (unsigned int depth_arg) |
| Set the maximum depth of the octree. | |
| void | switchBuffers () |
| Switch buffers and reset current octree structure. | |
| virtual | ~Octree2BufBase () |
| Empty deconstructor. | |
Protected Member Functions | |
| bool | branchHasChild (const BranchNode &branch_arg, unsigned char child_idx_arg) const |
| Check if branch is pointing to a particular child node. | |
| BranchNode * | createBranchChild (BranchNode &branch_arg, unsigned char child_idx_arg) |
| Fetch and add a new branch child to a branch class in current buffer. | |
| LeafContainerT * | createLeaf (const OctreeKey &key_arg) |
| Create a leaf node. | |
| LeafNode * | createLeafChild (BranchNode &branch_arg, unsigned char child_idx_arg) |
| Fetch and add a new leaf child to a branch class. | |
| unsigned int | createLeafRecursive (const OctreeKey &key_arg, unsigned int depth_mask_arg, BranchNode *branch_arg, LeafNode *&return_leaf_arg, BranchNode *&parent_of_leaf_arg, bool branch_reset_arg=false) |
| Create a leaf node at octree key. If leaf node does already exist, it is returned. | |
| void | deleteBranch (BranchNode &branch_arg) |
| Delete branch and all its subchilds from octree (both buffers) | |
| void | deleteBranchChild (BranchNode &branch_arg, unsigned char buffer_selector_arg, unsigned char child_idx_arg) |
| Delete child node and all its subchilds from octree in specific buffer. | |
| void | deleteBranchChild (BranchNode &branch_arg, unsigned char child_idx_arg) |
| Delete child node and all its subchilds from octree in current buffer. | |
| bool | deleteLeafRecursive (const OctreeKey &key_arg, unsigned int depth_mask_arg, BranchNode *branch_arg) |
| Recursively search and delete leaf node. | |
| virtual void | deserializeTreeCallback (LeafContainerT &, const OctreeKey &) |
| Callback executed for every leaf node data during deserialization. | |
| void | deserializeTreeRecursive (BranchNode *branch_arg, unsigned int depth_mask_arg, OctreeKey &key_arg, typename std::vector< char >::const_iterator &binary_tree_in_it_arg, typename std::vector< char >::const_iterator &binary_tree_in_it_end_arg, typename std::vector< LeafContainerT * >::const_iterator *leaf_container_vector_it_arg, typename std::vector< LeafContainerT * >::const_iterator *leaf_container_vector_it_end_arg, bool branch_reset_arg=false, bool do_XOR_decoding_arg=false) |
| Rebuild an octree based on binary XOR octree description and DataT objects for leaf node initialization. | |
| bool | existLeaf (const OctreeKey &key_arg) const |
| Check for leaf not existance in the octree. | |
| LeafContainerT * | findLeaf (const OctreeKey &key_arg) const |
| Find leaf node. | |
| void | findLeafRecursive (const OctreeKey &key_arg, unsigned int depth_mask_arg, BranchNode *branch_arg, LeafContainerT *&result_arg) const |
| Recursively search for a given leaf node and return a pointer. | |
| char | getBranchBitPattern (const BranchNode &branch_arg) const |
| Generate bit pattern reflecting the existence of child node pointers for current buffer. | |
| char | getBranchBitPattern (const BranchNode &branch_arg, unsigned char bufferSelector_arg) const |
| Generate bit pattern reflecting the existence of child node pointers in specific buffer. | |
| OctreeNode * | getBranchChildPtr (const BranchNode &branch_arg, unsigned char child_idx_arg) const |
| Retrieve a child node pointer for child node at child_idx. | |
| char | getBranchXORBitPattern (const BranchNode &branch_arg) const |
| Generate XOR bit pattern reflecting differences between the two octree buffers. | |
| OctreeNode * | getRootNode () const |
| Retrieve root node. | |
| bool | hasBranchChanges (const BranchNode &branch_arg) const |
| Test if branch changed between previous and current buffer. | |
| double | Log2 (double n_arg) |
| Helper function to calculate the binary logarithm. | |
| bool | octreeCanResize () |
| Test if octree is able to dynamically change its depth. This is required for adaptive bounding box adjustment. | |
| void | printBinary (char data_arg) |
| Prints binary representation of a byte - used for debugging. | |
| void | removeLeaf (const OctreeKey &key_arg) |
| Remove leaf node from octree. | |
| virtual void | serializeTreeCallback (LeafContainerT &, const OctreeKey &) |
| Callback executed for every leaf node data during serialization. | |
| void | serializeTreeRecursive (BranchNode *branch_arg, OctreeKey &key_arg, std::vector< char > *binary_tree_out_arg, typename std::vector< LeafContainerT * > *leaf_container_vector_arg, bool do_XOR_encoding_arg=false, bool new_leafs_filter_arg=false) |
| Recursively explore the octree and output binary octree description together with a vector of leaf node DataT content. | |
| void | setBranchChildPtr (BranchNode &branch_arg, unsigned char child_idx_arg, OctreeNode *new_child_arg) |
| Assign new child node to branch. | |
| void | treeCleanUpRecursive (BranchNode *branch_arg) |
| Recursively explore the octree and remove unused branch and leaf nodes. | |
Protected Attributes | |
| std::size_t | branch_count_ |
| Amount of branch nodes. | |
| unsigned char | buffer_selector_ |
| Currently active octree buffer. | |
| unsigned int | depth_mask_ |
| Depth mask based on octree depth. | |
| bool | dynamic_depth_enabled_ |
| Enable dynamic_depth. | |
| std::size_t | leaf_count_ |
| Amount of leaf nodes. | |
| OctreeKey | max_key_ |
| key range | |
| unsigned int | octree_depth_ |
| Octree depth. | |
| BranchNode * | root_node_ |
| Pointer to root branch node of octree. | |
| bool | tree_dirty_flag_ |
Friends | |
| class | OctreeBreadthFirstIterator< OctreeT > |
| class | OctreeDepthFirstIterator< OctreeT > |
| class | OctreeIteratorBase< OctreeT > |
| class | OctreeLeafNodeIterator< OctreeT > |
Octree double buffer class
Definition at line 227 of file octree2buf_base.h.
| typedef BranchContainerT pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::BranchContainer |
Definition at line 243 of file octree2buf_base.h.
| typedef BufferedBranchNode<BranchContainerT> pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::BranchNode |
Reimplemented in pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, Octree2BufBase< LeafContainerT, BranchContainerT > >, and pcl::octree::OctreePointCloud< pcl::PointXYZRGBA, OctreeContainerPointIndices, OctreeContainerEmpty, Octree2BufBase< OctreeContainerPointIndices, OctreeContainerEmpty > >.
Definition at line 240 of file octree2buf_base.h.
| typedef OctreeBreadthFirstIterator<OctreeT> pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::BreadthFirstIterator |
Reimplemented in pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, Octree2BufBase< LeafContainerT, BranchContainerT > >, and pcl::octree::OctreePointCloud< pcl::PointXYZRGBA, OctreeContainerPointIndices, OctreeContainerEmpty, Octree2BufBase< OctreeContainerPointIndices, OctreeContainerEmpty > >.
Definition at line 262 of file octree2buf_base.h.
| typedef const OctreeBreadthFirstIterator<OctreeT> pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::ConstBreadthFirstIterator |
Reimplemented in pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, Octree2BufBase< LeafContainerT, BranchContainerT > >, and pcl::octree::OctreePointCloud< pcl::PointXYZRGBA, OctreeContainerPointIndices, OctreeContainerEmpty, Octree2BufBase< OctreeContainerPointIndices, OctreeContainerEmpty > >.
Definition at line 266 of file octree2buf_base.h.
| typedef const OctreeDepthFirstIterator<OctreeT> pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::ConstDepthFirstIterator |
Reimplemented in pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, Octree2BufBase< LeafContainerT, BranchContainerT > >, and pcl::octree::OctreePointCloud< pcl::PointXYZRGBA, OctreeContainerPointIndices, OctreeContainerEmpty, Octree2BufBase< OctreeContainerPointIndices, OctreeContainerEmpty > >.
Definition at line 260 of file octree2buf_base.h.
| typedef const OctreeDepthFirstIterator<OctreeT> pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::ConstIterator |
Reimplemented in pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, Octree2BufBase< LeafContainerT, BranchContainerT > >, and pcl::octree::OctreePointCloud< pcl::PointXYZRGBA, OctreeContainerPointIndices, OctreeContainerEmpty, Octree2BufBase< OctreeContainerPointIndices, OctreeContainerEmpty > >.
Definition at line 248 of file octree2buf_base.h.
| typedef const OctreeLeafNodeIterator<OctreeT> pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::ConstLeafNodeIterator |
Reimplemented in pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, Octree2BufBase< LeafContainerT, BranchContainerT > >, and pcl::octree::OctreePointCloud< pcl::PointXYZRGBA, OctreeContainerPointIndices, OctreeContainerEmpty, Octree2BufBase< OctreeContainerPointIndices, OctreeContainerEmpty > >.
Definition at line 254 of file octree2buf_base.h.
| typedef OctreeDepthFirstIterator<OctreeT> pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::DepthFirstIterator |
Reimplemented in pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, Octree2BufBase< LeafContainerT, BranchContainerT > >, and pcl::octree::OctreePointCloud< pcl::PointXYZRGBA, OctreeContainerPointIndices, OctreeContainerEmpty, Octree2BufBase< OctreeContainerPointIndices, OctreeContainerEmpty > >.
Definition at line 256 of file octree2buf_base.h.
| typedef OctreeDepthFirstIterator<OctreeT> pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::Iterator |
Reimplemented in pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, Octree2BufBase< LeafContainerT, BranchContainerT > >, and pcl::octree::OctreePointCloud< pcl::PointXYZRGBA, OctreeContainerPointIndices, OctreeContainerEmpty, Octree2BufBase< OctreeContainerPointIndices, OctreeContainerEmpty > >.
Definition at line 247 of file octree2buf_base.h.
| typedef LeafContainerT pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::LeafContainer |
Definition at line 244 of file octree2buf_base.h.
| typedef OctreeLeafNode<LeafContainerT> pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::LeafNode |
Reimplemented in pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, Octree2BufBase< LeafContainerT, BranchContainerT > >, and pcl::octree::OctreePointCloud< pcl::PointXYZRGBA, OctreeContainerPointIndices, OctreeContainerEmpty, Octree2BufBase< OctreeContainerPointIndices, OctreeContainerEmpty > >.
Definition at line 241 of file octree2buf_base.h.
| typedef OctreeLeafNodeIterator<OctreeT> pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::LeafNodeIterator |
Reimplemented in pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, Octree2BufBase< LeafContainerT, BranchContainerT > >, and pcl::octree::OctreePointCloud< pcl::PointXYZRGBA, OctreeContainerPointIndices, OctreeContainerEmpty, Octree2BufBase< OctreeContainerPointIndices, OctreeContainerEmpty > >.
Definition at line 250 of file octree2buf_base.h.
| typedef Octree2BufBase<LeafContainerT, BranchContainerT> pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::OctreeT |
Definition at line 232 of file octree2buf_base.h.
| pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::Octree2BufBase | ( | ) |
Empty constructor.
Definition at line 48 of file octree2buf_base.hpp.
| pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::~Octree2BufBase | ( | ) | [virtual] |
Empty deconstructor.
Definition at line 63 of file octree2buf_base.hpp.
| pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::Octree2BufBase | ( | const Octree2BufBase< LeafContainerT, BranchContainerT > & | source | ) | [inline] |
Copy constructor.
Definition at line 278 of file octree2buf_base.h.
| Iterator pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::begin | ( | unsigned int | max_depth_arg = 0 | ) | [inline] |
Definition at line 249 of file octree2buf_base.h.
| bool pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::branchHasChild | ( | const BranchNode & | branch_arg, |
| unsigned char | child_idx_arg | ||
| ) | const [inline, protected] |
Check if branch is pointing to a particular child node.
| branch_arg,: | reference to octree branch class |
| child_idx_arg,: | index to child node |
Definition at line 527 of file octree2buf_base.h.
| BreadthFirstIterator pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::breadth_begin | ( | unsigned int | max_depth_arg = 0 | ) | [inline] |
Definition at line 267 of file octree2buf_base.h.
| const BreadthFirstIterator pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::breadth_end | ( | ) | [inline] |
Definition at line 268 of file octree2buf_base.h.
| BranchNode* pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::createBranchChild | ( | BranchNode & | branch_arg, |
| unsigned char | child_idx_arg | ||
| ) | [inline, protected] |
Fetch and add a new branch child to a branch class in current buffer.
| branch_arg,: | reference to octree branch class |
| child_idx_arg,: | index to child node |
Definition at line 714 of file octree2buf_base.h.
| LeafContainerT * pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::createLeaf | ( | unsigned int | idx_x_arg, |
| unsigned int | idx_y_arg, | ||
| unsigned int | idx_z_arg | ||
| ) |
Create new leaf node at (idx_x_arg, idx_y_arg, idx_z_arg).
| idx_x_arg,: | index of leaf node in the X axis. |
| idx_y_arg,: | index of leaf node in the Y axis. |
| idx_z_arg,: | index of leaf node in the Z axis. |
Definition at line 116 of file octree2buf_base.hpp.
| LeafContainerT* pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::createLeaf | ( | const OctreeKey & | key_arg | ) | [inline, protected] |
Create a leaf node.
| key_arg,: | octree key addressing a leaf node. |
Definition at line 482 of file octree2buf_base.h.
| LeafNode* pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::createLeafChild | ( | BranchNode & | branch_arg, |
| unsigned char | child_idx_arg | ||
| ) | [inline, protected] |
Fetch and add a new leaf child to a branch class.
| branch_arg,: | reference to octree branch class |
| child_idx_arg,: | index to child node |
Definition at line 731 of file octree2buf_base.h.
| unsigned int pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::createLeafRecursive | ( | const OctreeKey & | key_arg, |
| unsigned int | depth_mask_arg, | ||
| BranchNode * | branch_arg, | ||
| LeafNode *& | return_leaf_arg, | ||
| BranchNode *& | parent_of_leaf_arg, | ||
| bool | branch_reset_arg = false |
||
| ) | [protected] |
Create a leaf node at octree key. If leaf node does already exist, it is returned.
| key_arg,: | reference to an octree key |
| depth_mask_arg,: | depth mask used for octree key analysis and for branch depth indicator |
| branch_arg,: | current branch node |
| return_leaf_arg,: | return pointer to leaf container |
| parent_of_leaf_arg,: | return pointer to parent of leaf node |
| branch_reset_arg,: | Reset pointer array of current branch |
Definition at line 323 of file octree2buf_base.hpp.
| void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::deleteBranch | ( | BranchNode & | branch_arg | ) | [inline, protected] |
Delete branch and all its subchilds from octree (both buffers)
| branch_arg,: | reference to octree branch class |
Definition at line 684 of file octree2buf_base.h.
| void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::deleteBranchChild | ( | BranchNode & | branch_arg, |
| unsigned char | buffer_selector_arg, | ||
| unsigned char | child_idx_arg | ||
| ) | [inline, protected] |
Delete child node and all its subchilds from octree in specific buffer.
| branch_arg,: | reference to octree branch class |
| buffer_selector_arg,: | buffer selector |
| child_idx_arg,: | index to child node |
Definition at line 637 of file octree2buf_base.h.
| void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::deleteBranchChild | ( | BranchNode & | branch_arg, |
| unsigned char | child_idx_arg | ||
| ) | [inline, protected] |
Delete child node and all its subchilds from octree in current buffer.
| branch_arg,: | reference to octree branch class |
| child_idx_arg,: | index to child node |
Definition at line 676 of file octree2buf_base.h.
| void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::deleteCurrentBuffer | ( | ) | [inline] |
Delete the octree structure in the current buffer.
Definition at line 392 of file octree2buf_base.h.
| bool pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::deleteLeafRecursive | ( | const OctreeKey & | key_arg, |
| unsigned int | depth_mask_arg, | ||
| BranchNode * | branch_arg | ||
| ) | [protected] |
Recursively search and delete leaf node.
| key_arg,: | reference to an octree key |
| depth_mask_arg,: | depth mask used for octree key analysis and branch depth indicator |
| branch_arg,: | current branch node |
Definition at line 474 of file octree2buf_base.hpp.
| void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::deletePreviousBuffer | ( | ) | [inline] |
Delete octree structure of previous buffer.
Definition at line 386 of file octree2buf_base.h.
| void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::deleteTree | ( | ) |
Delete the octree structure and its leaf nodes.
Reimplemented in pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, Octree2BufBase< LeafContainerT, BranchContainerT > >, and pcl::octree::OctreePointCloud< pcl::PointXYZRGBA, OctreeContainerPointIndices, OctreeContainerEmpty, Octree2BufBase< OctreeContainerPointIndices, OctreeContainerEmpty > >.
Definition at line 149 of file octree2buf_base.hpp.
| DepthFirstIterator pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::depth_begin | ( | unsigned int | maxDepth_arg = 0 | ) | [inline] |
Definition at line 261 of file octree2buf_base.h.
| const DepthFirstIterator pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::depth_end | ( | ) | [inline] |
Definition at line 262 of file octree2buf_base.h.
| void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::deserializeTree | ( | std::vector< char > & | binary_tree_in_arg, |
| bool | do_XOR_decoding_arg = false |
||
| ) |
Deserialize a binary octree description vector and create a corresponding octree structure. Leaf nodes are initialized with getDataTByKey(..).
| binary_tree_in_arg,: | reference to input vector for reading binary tree structure. |
| do_XOR_decoding_arg,: | select if binary tree structure is based on current octree (false) of based on a XOR comparison between current and previous octree |
Definition at line 247 of file octree2buf_base.hpp.
| void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::deserializeTree | ( | std::vector< char > & | binary_tree_in_arg, |
| std::vector< LeafContainerT * > & | leaf_container_vector_arg, | ||
| bool | do_XOR_decoding_arg = false |
||
| ) |
Deserialize a binary octree description and create a corresponding octree structure. Leaf nodes are initialized with DataT elements from the dataVector.
| binary_tree_in_arg,: | reference to inpvectoream for reading binary tree structure. |
| leaf_container_vector_arg,: | vector of pointers to all LeafContainerT objects in the octree |
| do_XOR_decoding_arg,: | select if binary tree structure is based on current octree (false) of based on a XOR comparison between current and previous octree |
Definition at line 269 of file octree2buf_base.hpp.
| virtual void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::deserializeTreeCallback | ( | LeafContainerT & | , |
| const OctreeKey & | |||
| ) | [inline, protected, virtual] |
Callback executed for every leaf node data during deserialization.
Definition at line 839 of file octree2buf_base.h.
| void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::deserializeTreeRecursive | ( | BranchNode * | branch_arg, |
| unsigned int | depth_mask_arg, | ||
| OctreeKey & | key_arg, | ||
| typename std::vector< char >::const_iterator & | binary_tree_in_it_arg, | ||
| typename std::vector< char >::const_iterator & | binary_tree_in_it_end_arg, | ||
| typename std::vector< LeafContainerT * >::const_iterator * | leaf_container_vector_it_arg, | ||
| typename std::vector< LeafContainerT * >::const_iterator * | leaf_container_vector_it_end_arg, | ||
| bool | branch_reset_arg = false, |
||
| bool | do_XOR_decoding_arg = false |
||
| ) | [protected] |
Rebuild an octree based on binary XOR octree description and DataT objects for leaf node initialization.
| branch_arg,: | current branch node |
| depth_mask_arg,: | depth mask used for octree key analysis and branch depth indicator |
| key_arg,: | reference to an octree key |
| binary_tree_in_it_arg | iterator of binary input data |
| leaf_container_vector__it_end_arg | end iterator of binary input data |
| leaf_container_vector_it_arg,: | iterator pointing to leaf containter pointers to be added to a leaf node |
| leaf_container_vector_it_end_arg,: | iterator pointing to leaf containter pointers pointing to last object in input container. |
| branch_reset_arg,: | Reset pointer array of current branch |
| do_XOR_decoding_arg,: | select if binary tree structure is based on current octree (false) of based on a XOR comparison between current and previous octree |
Definition at line 629 of file octree2buf_base.hpp.
| const Iterator pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::end | ( | ) | [inline] |
Definition at line 250 of file octree2buf_base.h.
| bool pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::existLeaf | ( | unsigned int | idx_x_arg, |
| unsigned int | idx_y_arg, | ||
| unsigned int | idx_z_arg | ||
| ) | const |
Check for the existence of leaf node at (idx_x_arg, idx_y_arg, idx_z_arg).
| idx_x_arg,: | index of leaf node in the X axis. |
| idx_y_arg,: | index of leaf node in the Y axis. |
| idx_z_arg,: | index of leaf node in the Z axis. |
Definition at line 127 of file octree2buf_base.hpp.
| bool pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::existLeaf | ( | const OctreeKey & | key_arg | ) | const [inline, protected] |
Check for leaf not existance in the octree.
| key_arg,: | octree key addressing a leaf node. |
Definition at line 498 of file octree2buf_base.h.
| LeafContainerT * pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::findLeaf | ( | unsigned int | idx_x_arg, |
| unsigned int | idx_y_arg, | ||
| unsigned int | idx_z_arg | ||
| ) |
Find leaf node at (idx_x_arg, idx_y_arg, idx_z_arg).
| idx_x_arg,: | index of leaf node in the X axis. |
| idx_y_arg,: | index of leaf node in the Y axis. |
| idx_z_arg,: | index of leaf node in the Z axis. |
Definition at line 105 of file octree2buf_base.hpp.
| LeafContainerT* pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::findLeaf | ( | const OctreeKey & | key_arg | ) | const [inline, protected] |
Find leaf node.
| key_arg,: | octree key addressing a leaf node. |
Definition at line 469 of file octree2buf_base.h.
| void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::findLeafRecursive | ( | const OctreeKey & | key_arg, |
| unsigned int | depth_mask_arg, | ||
| BranchNode * | branch_arg, | ||
| LeafContainerT *& | result_arg | ||
| ) | const [protected] |
Recursively search for a given leaf node and return a pointer.
| key_arg,: | reference to an octree key |
| depth_mask_arg,: | depth mask used for octree key analysis and for branch depth indicator |
| branch_arg,: | current branch node |
| result_arg,: | pointer to leaf container class |
Definition at line 439 of file octree2buf_base.hpp.
| char pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::getBranchBitPattern | ( | const BranchNode & | branch_arg | ) | const [inline, protected] |
Generate bit pattern reflecting the existence of child node pointers for current buffer.
| branch_arg,: | reference to octree branch class |
Definition at line 560 of file octree2buf_base.h.
| char pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::getBranchBitPattern | ( | const BranchNode & | branch_arg, |
| unsigned char | bufferSelector_arg | ||
| ) | const [inline, protected] |
Generate bit pattern reflecting the existence of child node pointers in specific buffer.
| branch_arg,: | reference to octree branch class |
| bufferSelector_arg,: | buffer selector |
Definition at line 581 of file octree2buf_base.h.
| OctreeNode* pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::getBranchChildPtr | ( | const BranchNode & | branch_arg, |
| unsigned char | child_idx_arg | ||
| ) | const [inline, protected] |
Retrieve a child node pointer for child node at child_idx.
| branch_arg,: | reference to octree branch class |
| child_idx_arg,: | index to child node |
Definition at line 539 of file octree2buf_base.h.
| std::size_t pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::getBranchCount | ( | ) | const [inline] |
Return the amount of existing branches in the octree.
Definition at line 375 of file octree2buf_base.h.
| char pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::getBranchXORBitPattern | ( | const BranchNode & | branch_arg | ) | const [inline, protected] |
Generate XOR bit pattern reflecting differences between the two octree buffers.
| branch_arg,: | reference to octree branch class |
Definition at line 602 of file octree2buf_base.h.
| std::size_t pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::getLeafCount | ( | ) | const [inline] |
Return the amount of existing leafs in the octree.
Definition at line 367 of file octree2buf_base.h.
| OctreeNode* pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::getRootNode | ( | ) | const [inline, protected] |
Retrieve root node.
Definition at line 459 of file octree2buf_base.h.
| unsigned int pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::getTreeDepth | ( | ) | const [inline] |
Get the maximum depth of the octree.
Reimplemented in pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, Octree2BufBase< LeafContainerT, BranchContainerT > >, and pcl::octree::OctreePointCloud< pcl::PointXYZRGBA, OctreeContainerPointIndices, OctreeContainerEmpty, Octree2BufBase< OctreeContainerPointIndices, OctreeContainerEmpty > >.
Definition at line 322 of file octree2buf_base.h.
| bool pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::hasBranchChanges | ( | const BranchNode & | branch_arg | ) | const [inline, protected] |
Test if branch changed between previous and current buffer.
| branch_arg,: | reference to octree branch class |
Definition at line 627 of file octree2buf_base.h.
| LeafNodeIterator pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::leaf_begin | ( | unsigned int | max_depth_arg = 0 | ) | [inline] |
Definition at line 255 of file octree2buf_base.h.
| const LeafNodeIterator pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::leaf_end | ( | ) | [inline] |
Definition at line 256 of file octree2buf_base.h.
| double pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::Log2 | ( | double | n_arg | ) | [inline, protected] |
Helper function to calculate the binary logarithm.
| n_arg,: | some value |
Definition at line 858 of file octree2buf_base.h.
| bool pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::octreeCanResize | ( | ) | [inline, protected] |
Test if octree is able to dynamically change its depth. This is required for adaptive bounding box adjustment.
Definition at line 866 of file octree2buf_base.h.
| Octree2BufBase& pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::operator= | ( | const Octree2BufBase< LeafContainerT, BranchContainerT > & | source | ) | [inline] |
Copy constructor.
Definition at line 293 of file octree2buf_base.h.
| void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::printBinary | ( | char | data_arg | ) | [inline, protected] |
Prints binary representation of a byte - used for debugging.
| data_arg | - byte to be printed to stdout |
Definition at line 874 of file octree2buf_base.h.
| void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::removeLeaf | ( | unsigned int | idx_x_arg, |
| unsigned int | idx_y_arg, | ||
| unsigned int | idx_z_arg | ||
| ) |
Remove leaf node at (idx_x_arg, idx_y_arg, idx_z_arg).
| idx_x_arg,: | index of leaf node in the X axis. |
| idx_y_arg,: | index of leaf node in the Y axis. |
| idx_z_arg,: | index of leaf node in the Z axis. |
Definition at line 138 of file octree2buf_base.hpp.
| void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::removeLeaf | ( | const OctreeKey & | key_arg | ) | [inline, protected] |
Remove leaf node from octree.
| key_arg,: | octree key addressing a leaf node. |
Definition at line 506 of file octree2buf_base.h.
| void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::serializeLeafs | ( | std::vector< LeafContainerT * > & | leaf_container_vector_arg | ) |
Outputs a vector of all DataT elements that are stored within the octree leaf nodes.
| leaf_container_vector_arg,: | vector of pointers to all LeafContainerT objects in the octree |
Definition at line 230 of file octree2buf_base.hpp.
| void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::serializeNewLeafs | ( | std::vector< LeafContainerT * > & | leaf_container_vector_arg | ) |
Outputs a vector of all DataT elements from leaf nodes, that do not exist in the previous octree buffer.
| leaf_container_vector_arg,: | vector of pointers to all LeafContainerT objects in the octree |
Definition at line 306 of file octree2buf_base.hpp.
| void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::serializeTree | ( | std::vector< char > & | binary_tree_out_arg, |
| bool | do_XOR_encoding_arg = false |
||
| ) |
Serialize octree into a binary output vector describing its branch node structure.
| binary_tree_out_arg,: | reference to output vector for writing binary tree structure. |
| do_XOR_encoding_arg,: | select if binary tree structure should be generated based on current octree (false) of based on a XOR comparison between current and previous octree |
Definition at line 192 of file octree2buf_base.hpp.
| void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::serializeTree | ( | std::vector< char > & | binary_tree_out_arg, |
| std::vector< LeafContainerT * > & | leaf_container_vector_arg, | ||
| bool | do_XOR_encoding_arg = false |
||
| ) |
Serialize octree into a binary output vector describing its branch node structure and and push all DataT elements stored in the octree to a vector.
| binary_tree_out_arg,: | reference to output vector for writing binary tree structure. |
| leaf_container_vector_arg,: | pointer to all LeafContainerT objects in the octree |
| do_XOR_encoding_arg,: | select if binary tree structure should be generated based on current octree (false) of based on a XOR comparison between current and previous octree |
Definition at line 209 of file octree2buf_base.hpp.
| virtual void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::serializeTreeCallback | ( | LeafContainerT & | , |
| const OctreeKey & | |||
| ) | [inline, protected, virtual] |
Callback executed for every leaf node data during serialization.
Definition at line 832 of file octree2buf_base.h.
| void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::serializeTreeRecursive | ( | BranchNode * | branch_arg, |
| OctreeKey & | key_arg, | ||
| std::vector< char > * | binary_tree_out_arg, | ||
| typename std::vector< LeafContainerT * > * | leaf_container_vector_arg, | ||
| bool | do_XOR_encoding_arg = false, |
||
| bool | new_leafs_filter_arg = false |
||
| ) | [protected] |
Recursively explore the octree and output binary octree description together with a vector of leaf node DataT content.
| branch_arg,: | current branch node |
| key_arg,: | reference to an octree key |
| binary_tree_out_arg,: | binary output vector |
| leaf_container_vector_arg,: | vector to return pointers to all leaf container in the tree. |
| do_XOR_encoding_arg,: | select if binary tree structure should be generated based on current octree (false) of based on a XOR comparison between current and previous octree |
| new_leafs_filter_arg,: | execute callback only for leaf nodes that did not exist in preceding buffer |
Definition at line 530 of file octree2buf_base.hpp.
| void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::setBranchChildPtr | ( | BranchNode & | branch_arg, |
| unsigned char | child_idx_arg, | ||
| OctreeNode * | new_child_arg | ||
| ) | [inline, protected] |
Assign new child node to branch.
| branch_arg,: | reference to octree branch class |
| child_idx_arg,: | index to child node |
| new_child_arg,: | pointer to new child node |
Definition at line 551 of file octree2buf_base.h.
| void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::setMaxVoxelIndex | ( | unsigned int | max_voxel_index_arg | ) |
Set the maximum amount of voxels per dimension.
| max_voxel_index_arg,: | maximum amount of voxels per dimension |
Definition at line 72 of file octree2buf_base.hpp.
| void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::setTreeDepth | ( | unsigned int | depth_arg | ) |
Set the maximum depth of the octree.
| depth_arg,: | maximum depth of octree |
Definition at line 89 of file octree2buf_base.hpp.
| void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::switchBuffers | ( | ) |
Switch buffers and reset current octree structure.
Definition at line 166 of file octree2buf_base.hpp.
| void pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::treeCleanUpRecursive | ( | BranchNode * | branch_arg | ) | [protected] |
Recursively explore the octree and remove unused branch and leaf nodes.
| branch_arg,: | current branch node |
Definition at line 790 of file octree2buf_base.hpp.
friend class OctreeBreadthFirstIterator< OctreeT > [friend] |
Reimplemented in pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, Octree2BufBase< LeafContainerT, BranchContainerT > >, and pcl::octree::OctreePointCloud< pcl::PointXYZRGBA, OctreeContainerPointIndices, OctreeContainerEmpty, Octree2BufBase< OctreeContainerPointIndices, OctreeContainerEmpty > >.
Definition at line 237 of file octree2buf_base.h.
friend class OctreeDepthFirstIterator< OctreeT > [friend] |
Reimplemented in pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, Octree2BufBase< LeafContainerT, BranchContainerT > >, and pcl::octree::OctreePointCloud< pcl::PointXYZRGBA, OctreeContainerPointIndices, OctreeContainerEmpty, Octree2BufBase< OctreeContainerPointIndices, OctreeContainerEmpty > >.
Definition at line 236 of file octree2buf_base.h.
friend class OctreeIteratorBase< OctreeT > [friend] |
Reimplemented in pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, Octree2BufBase< LeafContainerT, BranchContainerT > >, and pcl::octree::OctreePointCloud< pcl::PointXYZRGBA, OctreeContainerPointIndices, OctreeContainerEmpty, Octree2BufBase< OctreeContainerPointIndices, OctreeContainerEmpty > >.
Definition at line 235 of file octree2buf_base.h.
friend class OctreeLeafNodeIterator< OctreeT > [friend] |
Reimplemented in pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, Octree2BufBase< LeafContainerT, BranchContainerT > >, and pcl::octree::OctreePointCloud< pcl::PointXYZRGBA, OctreeContainerPointIndices, OctreeContainerEmpty, Octree2BufBase< OctreeContainerPointIndices, OctreeContainerEmpty > >.
Definition at line 238 of file octree2buf_base.h.
std::size_t pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::branch_count_ [protected] |
Amount of branch nodes.
Definition at line 895 of file octree2buf_base.h.
unsigned char pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::buffer_selector_ [protected] |
Currently active octree buffer.
Definition at line 907 of file octree2buf_base.h.
unsigned int pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::depth_mask_ [protected] |
Depth mask based on octree depth.
Definition at line 901 of file octree2buf_base.h.
bool pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::dynamic_depth_enabled_ [protected] |
Enable dynamic_depth.
Definition at line 917 of file octree2buf_base.h.
std::size_t pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::leaf_count_ [protected] |
Amount of leaf nodes.
Definition at line 892 of file octree2buf_base.h.
OctreeKey pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::max_key_ [protected] |
key range
Definition at line 904 of file octree2buf_base.h.
unsigned int pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::octree_depth_ [protected] |
Octree depth.
Definition at line 913 of file octree2buf_base.h.
BranchNode* pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::root_node_ [protected] |
Pointer to root branch node of octree.
Definition at line 898 of file octree2buf_base.h.
bool pcl::octree::Octree2BufBase< LeafContainerT, BranchContainerT >::tree_dirty_flag_ [protected] |
Definition at line 910 of file octree2buf_base.h.