point_cloud_library / 1.12.1 / classpcl_1_1octree_1_1_octree_point_cloud_adjacency.html /

Octree pointcloud voxel class which maintains adjacency information for its voxels. More...

#include <pcl/octree/octree_pointcloud_adjacency.h>

Public Types

using OctreeBaseT = OctreeBase< LeafContainerT, BranchContainerT >
using OctreeAdjacencyT = OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >
using Ptr = shared_ptr< OctreeAdjacencyT >
using ConstPtr = shared_ptr< const OctreeAdjacencyT >
using OctreePointCloudT = OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeBaseT >
using LeafNode = typename OctreePointCloudT::LeafNode
using BranchNode = typename OctreePointCloudT::BranchNode
using PointCloud = pcl::PointCloud< PointT >
using PointCloudPtr = typename PointCloud::Ptr
using PointCloudConstPtr = typename PointCloud::ConstPtr
using VoxelAdjacencyList = boost::adjacency_list< boost::setS, boost::setS, boost::undirectedS, PointT, float >
using VoxelID = typename VoxelAdjacencyList::vertex_descriptor
using EdgeID = typename VoxelAdjacencyList::edge_descriptor
using LeafVectorT = std::vector< LeafContainerT * >
using iterator = typename LeafVectorT::iterator
using const_iterator = typename LeafVectorT::const_iterator
- Public Types inherited from pcl::octree::OctreePointCloud< PointT, OctreePointCloudAdjacencyContainer< PointT >, OctreeContainerEmpty >
using Base = OctreeBase< OctreePointCloudAdjacencyContainer< PointT >, OctreeContainerEmpty >
using LeafNode = typename OctreeBase< OctreePointCloudAdjacencyContainer< PointT >, OctreeContainerEmpty > ::LeafNode
using BranchNode = typename OctreeBase< OctreePointCloudAdjacencyContainer< PointT >, OctreeContainerEmpty > ::BranchNode
using IndicesPtr = shared_ptr< Indices >
using IndicesConstPtr = shared_ptr< const Indices >
using PointCloud = pcl::PointCloud< PointT >
using PointCloudPtr = typename PointCloud::Ptr
using PointCloudConstPtr = typename PointCloud::ConstPtr
using SingleBuffer = OctreePointCloud< PointT, OctreePointCloudAdjacencyContainer< PointT >, OctreeContainerEmpty, OctreeBase< OctreePointCloudAdjacencyContainer< PointT > > >
using Ptr = shared_ptr< OctreePointCloud< PointT, OctreePointCloudAdjacencyContainer< PointT >, OctreeContainerEmpty, OctreeBase< OctreePointCloudAdjacencyContainer< PointT >, OctreeContainerEmpty > > >
using ConstPtr = shared_ptr< const OctreePointCloud< PointT, OctreePointCloudAdjacencyContainer< PointT >, OctreeContainerEmpty, OctreeBase< OctreePointCloudAdjacencyContainer< PointT >, OctreeContainerEmpty > > >
using AlignedPointTVector = std::vector< PointT, Eigen::aligned_allocator< PointT > >
using AlignedPointXYZVector = std::vector< PointXYZ, Eigen::aligned_allocator< PointXYZ > >
- Public Types inherited from pcl::octree::OctreeBase< OctreePointCloudAdjacencyContainer< PointT >, OctreeContainerEmpty >
using OctreeT = OctreeBase< OctreePointCloudAdjacencyContainer< PointT >, OctreeContainerEmpty >
using BranchNode = OctreeBranchNode< OctreeContainerEmpty >
using LeafNode = OctreeLeafNode< OctreePointCloudAdjacencyContainer< PointT > >
using BranchContainer = OctreeContainerEmpty
using LeafContainer = OctreePointCloudAdjacencyContainer< PointT >
using Iterator = OctreeDepthFirstIterator< OctreeT >
using ConstIterator = const OctreeDepthFirstIterator< OctreeT >
using LeafNodeIterator = OctreeLeafNodeDepthFirstIterator< OctreeT >
using ConstLeafNodeIterator = const OctreeLeafNodeDepthFirstIterator< OctreeT >
using LeafNodeDepthFirstIterator = OctreeLeafNodeDepthFirstIterator< OctreeT >
using ConstLeafNodeDepthFirstIterator = const OctreeLeafNodeDepthFirstIterator< OctreeT >
using DepthFirstIterator = OctreeDepthFirstIterator< OctreeT >
using ConstDepthFirstIterator = const OctreeDepthFirstIterator< OctreeT >
using BreadthFirstIterator = OctreeBreadthFirstIterator< OctreeT >
using ConstBreadthFirstIterator = const OctreeBreadthFirstIterator< OctreeT >
using FixedDepthIterator = OctreeFixedDepthIterator< OctreeT >
using ConstFixedDepthIterator = const OctreeFixedDepthIterator< OctreeT >
using LeafNodeBreadthFirstIterator = OctreeLeafNodeBreadthFirstIterator< OctreeT >
using ConstLeafNodeBreadthFirstIterator = const OctreeLeafNodeBreadthFirstIterator< OctreeT >

Public Member Functions

iterator begin ()
iterator end ()
LeafContainerT * at (std::size_t idx)
std::size_t size () const
OctreePointCloudAdjacency (const double resolution_arg)
Constructor. More...
void addPointsFromInputCloud ()
Adds points from cloud to the octree. More...
LeafContainerT * getLeafContainerAtPoint (const PointT &point_arg) const
Gets the leaf container for a given point. More...
void computeVoxelAdjacencyGraph (VoxelAdjacencyList &voxel_adjacency_graph)
Computes an adjacency graph of voxel relations. More...
void setTransformFunction (std::function< void(PointT &p)> transform_func)
Sets a point transform (and inverse) used to transform the space of the input cloud. More...
bool testForOcclusion (const PointT &point_arg, const PointXYZ &camera_pos=PointXYZ(0, 0, 0))
Tests whether input point is occluded from specified camera point by other voxels. More...
- Public Member Functions inherited from pcl::octree::OctreePointCloud< PointT, OctreePointCloudAdjacencyContainer< PointT >, OctreeContainerEmpty >
OctreePointCloud (const double resolution_arg)
Octree pointcloud constructor. More...
void setInputCloud (const PointCloudConstPtr &cloud_arg, const IndicesConstPtr &indices_arg=IndicesConstPtr())
Provide a pointer to the input data set. More...
const IndicesConstPtr getIndices () const
Get a pointer to the vector of indices used. More...
PointCloudConstPtr getInputCloud () const
Get a pointer to the input point cloud dataset. More...
void setEpsilon (double eps)
Set the search epsilon precision (error bound) for nearest neighbors searches. More...
double getEpsilon () const
Get the search epsilon precision (error bound) for nearest neighbors searches. More...
void setResolution (double resolution_arg)
Set/change the octree voxel resolution. More...
double getResolution () const
Get octree voxel resolution. More...
uindex_t getTreeDepth () const
Get the maximum depth of the octree. More...
void addPointsFromInputCloud ()
Add points from input point cloud to octree. More...
void addPointFromCloud (uindex_t point_idx_arg, IndicesPtr indices_arg)
Add point at given index from input point cloud to octree. More...
void addPointToCloud (const PointT &point_arg, PointCloudPtr cloud_arg)
Add point simultaneously to octree and input point cloud. More...
void addPointToCloud (const PointT &point_arg, PointCloudPtr cloud_arg, IndicesPtr indices_arg)
Add point simultaneously to octree and input point cloud. More...
bool isVoxelOccupiedAtPoint (const PointT &point_arg) const
Check if voxel at given point exist. More...
bool isVoxelOccupiedAtPoint (const double point_x_arg, const double point_y_arg, const double point_z_arg) const
Check if voxel at given point coordinates exist. More...
bool isVoxelOccupiedAtPoint (const index_t &point_idx_arg) const
Check if voxel at given point from input cloud exist. More...
void deleteTree ()
Delete the octree structure and its leaf nodes. More...
uindex_t getOccupiedVoxelCenters (AlignedPointTVector &voxel_center_list_arg) const
Get a PointT vector of centers of all occupied voxels. More...
uindex_t getApproxIntersectedVoxelCentersBySegment (const Eigen::Vector3f &origin, const Eigen::Vector3f &end, AlignedPointTVector &voxel_center_list, float precision=0.2)
Get a PointT vector of centers of voxels intersected by a line segment. More...
void deleteVoxelAtPoint (const PointT &point_arg)
Delete leaf node / voxel at given point. More...
void deleteVoxelAtPoint (const index_t &point_idx_arg)
Delete leaf node / voxel at given point from input cloud. More...
void defineBoundingBox ()
Investigate dimensions of pointcloud data set and define corresponding bounding box for octree. More...
void defineBoundingBox (const double min_x_arg, const double min_y_arg, const double min_z_arg, const double max_x_arg, const double max_y_arg, const double max_z_arg)
Define bounding box for octree. More...
void defineBoundingBox (const double max_x_arg, const double max_y_arg, const double max_z_arg)
Define bounding box for octree. More...
void defineBoundingBox (const double cubeLen_arg)
Define bounding box cube for octree. More...
void getBoundingBox (double &min_x_arg, double &min_y_arg, double &min_z_arg, double &max_x_arg, double &max_y_arg, double &max_z_arg) const
Get bounding box for octree. More...
double getVoxelSquaredDiameter (uindex_t tree_depth_arg) const
Calculates the squared diameter of a voxel at given tree depth. More...
double getVoxelSquaredDiameter () const
Calculates the squared diameter of a voxel at leaf depth. More...
double getVoxelSquaredSideLen (uindex_t tree_depth_arg) const
Calculates the squared voxel cube side length at given tree depth. More...
double getVoxelSquaredSideLen () const
Calculates the squared voxel cube side length at leaf level. More...
void getVoxelBounds (const OctreeIteratorBase< OctreeBase< OctreePointCloudAdjacencyContainer< PointT >, OctreeContainerEmpty > > &iterator, Eigen::Vector3f &min_pt, Eigen::Vector3f &max_pt) const
Generate bounds of the current voxel of an octree iterator. More...
void enableDynamicDepth (std::size_t maxObjsPerLeaf)
Enable dynamic octree structure. More...
- Public Member Functions inherited from pcl::octree::OctreeBase< OctreePointCloudAdjacencyContainer< PointT >, OctreeContainerEmpty >
Iterator begin (uindex_t max_depth_arg=0u)
const Iterator end ()
LeafNodeDepthFirstIterator leaf_depth_begin (uindex_t max_depth_arg=0u)
const LeafNodeDepthFirstIterator leaf_depth_end ()
DepthFirstIterator depth_begin (uindex_t max_depth_arg=0u)
const DepthFirstIterator depth_end ()
BreadthFirstIterator breadth_begin (uindex_t max_depth_arg=0u)
const BreadthFirstIterator breadth_end ()
FixedDepthIterator fixed_depth_begin (uindex_t fixed_depth_arg=0u)
const FixedDepthIterator fixed_depth_end ()
LeafNodeBreadthFirstIterator leaf_breadth_begin (uindex_t max_depth_arg=0u)
const LeafNodeBreadthFirstIterator leaf_breadth_end ()
OctreeBase ()
Empty constructor. More...
OctreeBase (const OctreeBase &source)
Copy constructor. More...
virtual ~OctreeBase ()
Empty deconstructor. More...
OctreeBase & operator= (const OctreeBase &source)
Copy operator. More...
void setMaxVoxelIndex (uindex_t max_voxel_index_arg)
Set the maximum amount of voxels per dimension. More...
void setTreeDepth (uindex_t max_depth_arg)
Set the maximum depth of the octree. More...
uindex_t getTreeDepth () const
Get the maximum depth of the octree. More...
OctreePointCloudAdjacencyContainer< PointT > * createLeaf (uindex_t idx_x_arg, uindex_t idx_y_arg, uindex_t idx_z_arg)
Create new leaf node at (idx_x_arg, idx_y_arg, idx_z_arg). More...
OctreePointCloudAdjacencyContainer< PointT > * findLeaf (uindex_t idx_x_arg, uindex_t idx_y_arg, uindex_t idx_z_arg)
Find leaf node at (idx_x_arg, idx_y_arg, idx_z_arg). More...
bool existLeaf (uindex_t idx_x_arg, uindex_t idx_y_arg, uindex_t idx_z_arg) const
idx_x_arg for the existence of leaf node at (idx_x_arg, idx_y_arg, idx_z_arg). More...
void removeLeaf (uindex_t idx_x_arg, uindex_t idx_y_arg, uindex_t idx_z_arg)
Remove leaf node at (idx_x_arg, idx_y_arg, idx_z_arg). More...
std::size_t getLeafCount () const
Return the amount of existing leafs in the octree. More...
std::size_t getBranchCount () const
Return the amount of existing branch nodes in the octree. More...
void deleteTree ()
Delete the octree structure and its leaf nodes. More...
void serializeTree (std::vector< char > &binary_tree_out_arg)
Serialize octree into a binary output vector describing its branch node structure. More...
void serializeTree (std::vector< char > &binary_tree_out_arg, std::vector< OctreePointCloudAdjacencyContainer< PointT > * > &leaf_container_vector_arg)
Serialize octree into a binary output vector describing its branch node structure and push all LeafContainerT elements stored in the octree to a vector. More...
void serializeLeafs (std::vector< OctreePointCloudAdjacencyContainer< PointT > * > &leaf_container_vector_arg)
Outputs a vector of all LeafContainerT elements that are stored within the octree leaf nodes. More...
void deserializeTree (std::vector< char > &binary_tree_input_arg)
Deserialize a binary octree description vector and create a corresponding octree structure. More...
void deserializeTree (std::vector< char > &binary_tree_input_arg, std::vector< OctreePointCloudAdjacencyContainer< PointT > * > &leaf_container_vector_arg)
Deserialize a binary octree description and create a corresponding octree structure. More...

Protected Member Functions

void addPointIdx (uindex_t point_idx_arg) override
Add point at index from input pointcloud dataset to octree. More...
void computeNeighbors (OctreeKey &key_arg, LeafContainerT *leaf_container)
Fills in the neighbors fields for new voxels. More...
void genOctreeKeyforPoint (const PointT &point_arg, OctreeKey &key_arg) const
Generates octree key for specified point (uses transform if provided). More...
- Protected Member Functions inherited from pcl::octree::OctreePointCloud< PointT, OctreePointCloudAdjacencyContainer< PointT >, OctreeContainerEmpty >
void expandLeafNode (LeafNode *leaf_node, BranchNode *parent_branch, unsigned char child_idx, uindex_t depth_mask)
Add point at index from input pointcloud dataset to octree. More...
const PointT & getPointByIndex (uindex_t index_arg) const
Get point at index from input pointcloud dataset. More...
OctreePointCloudAdjacencyContainer< PointT > * findLeafAtPoint (const PointT &point_arg) const
Find octree leaf node at a given point. More...
void getKeyBitSize ()
Define octree key setting and octree depth based on defined bounding box. More...
void adoptBoundingBoxToPoint (const PointT &point_idx_arg)
Grow the bounding box/octree until point fits. More...
bool isPointWithinBoundingBox (const PointT &point_idx_arg) const
Checks if given point is within the bounding box of the octree. More...
void genOctreeKeyforPoint (const PointT &point_arg, OctreeKey &key_arg) const
Generate octree key for voxel at a given point. More...
void genOctreeKeyforPoint (const double point_x_arg, const double point_y_arg, const double point_z_arg, OctreeKey &key_arg) const
Generate octree key for voxel at a given point. More...
virtual bool genOctreeKeyForDataT (const index_t &data_arg, OctreeKey &key_arg) const
Virtual method for generating octree key for a given point index. More...
void genLeafNodeCenterFromOctreeKey (const OctreeKey &key_arg, PointT &point_arg) const
Generate a point at center of leaf node voxel. More...
void genVoxelCenterFromOctreeKey (const OctreeKey &key_arg, uindex_t tree_depth_arg, PointT &point_arg) const
Generate a point at center of octree voxel at given tree level. More...
void genVoxelBoundsFromOctreeKey (const OctreeKey &key_arg, uindex_t tree_depth_arg, Eigen::Vector3f &min_pt, Eigen::Vector3f &max_pt) const
Generate bounds of an octree voxel using octree key and tree depth arguments. More...
uindex_t getOccupiedVoxelCentersRecursive (const BranchNode *node_arg, const OctreeKey &key_arg, AlignedPointTVector &voxel_center_list_arg) const
Recursively search the tree for all leaf nodes and return a vector of voxel centers. More...
- Protected Member Functions inherited from pcl::octree::OctreeBase< OctreePointCloudAdjacencyContainer< PointT >, OctreeContainerEmpty >
OctreePointCloudAdjacencyContainer< PointT > * createLeaf (const OctreeKey &key_arg)
Create a leaf node. More...
OctreePointCloudAdjacencyContainer< PointT > * findLeaf (const OctreeKey &key_arg) const
Find leaf node. More...
bool existLeaf (const OctreeKey &key_arg) const
Check for existence of a leaf node in the octree. More...
void removeLeaf (const OctreeKey &key_arg)
Remove leaf node from octree. More...
OctreeNode * getRootNode () const
Retrieve root node. More...
bool branchHasChild (const BranchNode &branch_arg, unsigned char child_idx_arg) const
Check if branch is pointing to a particular child node. More...
OctreeNode * getBranchChildPtr (const BranchNode &branch_arg, unsigned char child_idx_arg) const
Retrieve a child node pointer for child node at child_idx. More...
void setBranchChildPtr (BranchNode &branch_arg, unsigned char child_idx_arg, OctreeNode *new_child_arg)
Assign new child node to branch. More...
char getBranchBitPattern (const BranchNode &branch_arg) const
Generate bit pattern reflecting the existence of child node pointers. More...
void deleteBranchChild (BranchNode &branch_arg, unsigned char child_idx_arg)
Delete child node and all its subchilds from octree. More...
void deleteBranch (BranchNode &branch_arg)
Delete branch and all its subchilds from octree. More...
BranchNode * createBranchChild (BranchNode &branch_arg, unsigned char child_idx_arg)
Create and add a new branch child to a branch class. More...
LeafNode * createLeafChild (BranchNode &branch_arg, unsigned char child_idx_arg)
Create and add a new leaf child to a branch class. More...
uindex_t createLeafRecursive (const OctreeKey &key_arg, uindex_t depth_mask_arg, BranchNode *branch_arg, LeafNode *&return_leaf_arg, BranchNode *&parent_of_leaf_arg)
Create a leaf node at octree key. More...
void findLeafRecursive (const OctreeKey &key_arg, uindex_t depth_mask_arg, BranchNode *branch_arg, OctreePointCloudAdjacencyContainer< PointT > *&result_arg) const
Recursively search for a given leaf node and return a pointer. More...
bool deleteLeafRecursive (const OctreeKey &key_arg, uindex_t depth_mask_arg, BranchNode *branch_arg)
Recursively search and delete leaf node. More...
void serializeTreeRecursive (const BranchNode *branch_arg, OctreeKey &key_arg, std::vector< char > *binary_tree_out_arg, typename std::vector< OctreePointCloudAdjacencyContainer< PointT > * > *leaf_container_vector_arg) const
Recursively explore the octree and output binary octree description together with a vector of leaf node LeafContainerTs. More...
void deserializeTreeRecursive (BranchNode *branch_arg, uindex_t depth_mask_arg, OctreeKey &key_arg, typename std::vector< char >::const_iterator &binary_tree_input_it_arg, typename std::vector< char >::const_iterator &binary_tree_input_it_end_arg, typename std::vector< OctreePointCloudAdjacencyContainer< PointT > * >::const_iterator *leaf_container_vector_it_arg, typename std::vector< OctreePointCloudAdjacencyContainer< PointT > * >::const_iterator *leaf_container_vector_it_end_arg)
Recursive method for deserializing octree structure. More...
virtual void serializeTreeCallback (OctreePointCloudAdjacencyContainer< PointT > &, const OctreeKey &) const
Callback executed for every leaf node during serialization. More...
virtual void deserializeTreeCallback (OctreePointCloudAdjacencyContainer< PointT > &, const OctreeKey &)
Callback executed for every leaf node during deserialization. More...
bool octreeCanResize ()
Test if octree is able to dynamically change its depth. More...

Additional Inherited Members

- Protected Attributes inherited from pcl::octree::OctreePointCloud< PointT, OctreePointCloudAdjacencyContainer< PointT >, OctreeContainerEmpty >
PointCloudConstPtr input_
Pointer to input point cloud dataset. More...
IndicesConstPtr indices_
A pointer to the vector of point indices to use. More...
double epsilon_
Epsilon precision (error bound) for nearest neighbors searches. More...
double resolution_
Octree resolution. More...
double min_x_
double max_x_
double min_y_
double max_y_
double min_z_
double max_z_
bool bounding_box_defined_
Flag indicating if octree has defined bounding box. More...
std::size_t max_objs_per_leaf_
Amount of DataT objects per leafNode before expanding branch. More...
- Protected Attributes inherited from pcl::octree::OctreeBase< OctreePointCloudAdjacencyContainer< PointT >, OctreeContainerEmpty >
std::size_t leaf_count_
Amount of leaf nodes
More...
std::size_t branch_count_
Amount of branch nodes
More...
BranchNode * root_node_
Pointer to root branch node of octree
More...
uindex_t depth_mask_
Depth mask based on octree depth
More...
uindex_t octree_depth_
Octree depth. More...
bool dynamic_depth_enabled_
Enable dynamic_depth. More...
OctreeKey max_key_
key range More...

Detailed Description

template<typename PointT, typename LeafContainerT = OctreePointCloudAdjacencyContainer<PointT>, typename BranchContainerT = OctreeContainerEmpty>
class pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >

Octree pointcloud voxel class which maintains adjacency information for its voxels.

This pointcloud octree class generates an octree from a point cloud (zero-copy). The octree pointcloud is initialized with its voxel resolution. Its bounding box is automatically adjusted or can be predefined.

The OctreePointCloudAdjacencyContainer class can be used to store data in leaf nodes.

An optional transform function can be provided which changes how the voxel grid is computed - this can be used to, for example, make voxel bins larger as they increase in distance from the origin (camera).

Note
See SupervoxelClustering for an example of how to provide a transform function.

If used in academic work, please cite:

  • J. Papon, A. Abramov, M. Schoeler, F. Woergoetter Voxel Cloud Connectivity Segmentation - Supervoxels from PointClouds In Proceedings of the IEEE Conference on Computer Vision and Pattern Recognition (CVPR) 2013
Author
Jeremie Papon ( jpapo.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)

Definition at line 78 of file octree_pointcloud_adjacency.h.

Member Typedef Documentation

BranchNode

template<typename PointT , typename LeafContainerT = OctreePointCloudAdjacencyContainer<PointT>, typename BranchContainerT = OctreeContainerEmpty>
using pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::BranchNode = typename OctreePointCloudT::BranchNode

Definition at line 92 of file octree_pointcloud_adjacency.h.

const_iterator

template<typename PointT , typename LeafContainerT = OctreePointCloudAdjacencyContainer<PointT>, typename BranchContainerT = OctreeContainerEmpty>
using pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::const_iterator = typename LeafVectorT::const_iterator

Definition at line 109 of file octree_pointcloud_adjacency.h.

ConstPtr

template<typename PointT , typename LeafContainerT = OctreePointCloudAdjacencyContainer<PointT>, typename BranchContainerT = OctreeContainerEmpty>
using pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::ConstPtr = shared_ptr<const OctreeAdjacencyT>

Definition at line 87 of file octree_pointcloud_adjacency.h.

EdgeID

template<typename PointT , typename LeafContainerT = OctreePointCloudAdjacencyContainer<PointT>, typename BranchContainerT = OctreeContainerEmpty>
using pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::EdgeID = typename VoxelAdjacencyList::edge_descriptor

Definition at line 102 of file octree_pointcloud_adjacency.h.

iterator

template<typename PointT , typename LeafContainerT = OctreePointCloudAdjacencyContainer<PointT>, typename BranchContainerT = OctreeContainerEmpty>
using pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::iterator = typename LeafVectorT::iterator

Definition at line 108 of file octree_pointcloud_adjacency.h.

LeafNode

template<typename PointT , typename LeafContainerT = OctreePointCloudAdjacencyContainer<PointT>, typename BranchContainerT = OctreeContainerEmpty>
using pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::LeafNode = typename OctreePointCloudT::LeafNode

Definition at line 91 of file octree_pointcloud_adjacency.h.

LeafVectorT

template<typename PointT , typename LeafContainerT = OctreePointCloudAdjacencyContainer<PointT>, typename BranchContainerT = OctreeContainerEmpty>
using pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::LeafVectorT = std::vector<LeafContainerT*>

Definition at line 105 of file octree_pointcloud_adjacency.h.

OctreeAdjacencyT

template<typename PointT , typename LeafContainerT = OctreePointCloudAdjacencyContainer<PointT>, typename BranchContainerT = OctreeContainerEmpty>
using pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::OctreeAdjacencyT = OctreePointCloudAdjacency<PointT, LeafContainerT, BranchContainerT>

Definition at line 85 of file octree_pointcloud_adjacency.h.

OctreeBaseT

template<typename PointT , typename LeafContainerT = OctreePointCloudAdjacencyContainer<PointT>, typename BranchContainerT = OctreeContainerEmpty>
using pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::OctreeBaseT = OctreeBase<LeafContainerT, BranchContainerT>

Definition at line 82 of file octree_pointcloud_adjacency.h.

OctreePointCloudT

template<typename PointT , typename LeafContainerT = OctreePointCloudAdjacencyContainer<PointT>, typename BranchContainerT = OctreeContainerEmpty>
using pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::OctreePointCloudT = OctreePointCloud<PointT, LeafContainerT, BranchContainerT, OctreeBaseT>

Definition at line 90 of file octree_pointcloud_adjacency.h.

PointCloud

template<typename PointT , typename LeafContainerT = OctreePointCloudAdjacencyContainer<PointT>, typename BranchContainerT = OctreeContainerEmpty>
using pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::PointCloud = pcl::PointCloud<PointT>

Definition at line 94 of file octree_pointcloud_adjacency.h.

PointCloudConstPtr

template<typename PointT , typename LeafContainerT = OctreePointCloudAdjacencyContainer<PointT>, typename BranchContainerT = OctreeContainerEmpty>
using pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::PointCloudConstPtr = typename PointCloud::ConstPtr

Definition at line 96 of file octree_pointcloud_adjacency.h.

PointCloudPtr

template<typename PointT , typename LeafContainerT = OctreePointCloudAdjacencyContainer<PointT>, typename BranchContainerT = OctreeContainerEmpty>
using pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::PointCloudPtr = typename PointCloud::Ptr

Definition at line 95 of file octree_pointcloud_adjacency.h.

Ptr

template<typename PointT , typename LeafContainerT = OctreePointCloudAdjacencyContainer<PointT>, typename BranchContainerT = OctreeContainerEmpty>
using pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::Ptr = shared_ptr<OctreeAdjacencyT>

Definition at line 86 of file octree_pointcloud_adjacency.h.

VoxelAdjacencyList

template<typename PointT , typename LeafContainerT = OctreePointCloudAdjacencyContainer<PointT>, typename BranchContainerT = OctreeContainerEmpty>
using pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::VoxelAdjacencyList = boost:: adjacency_list<boost::setS, boost::setS, boost::undirectedS, PointT, float>

Definition at line 100 of file octree_pointcloud_adjacency.h.

VoxelID

template<typename PointT , typename LeafContainerT = OctreePointCloudAdjacencyContainer<PointT>, typename BranchContainerT = OctreeContainerEmpty>
using pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::VoxelID = typename VoxelAdjacencyList::vertex_descriptor

Definition at line 101 of file octree_pointcloud_adjacency.h.

Constructor & Destructor Documentation

OctreePointCloudAdjacency()

template<typename PointT , typename LeafContainerT , typename BranchContainerT >
pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::OctreePointCloudAdjacency ( const double resolution_arg )

Constructor.

Parameters
[in] resolution_arg Octree resolution at lowest octree level (voxel size)

Definition at line 55 of file octree_pointcloud_adjacency.hpp.

Member Function Documentation

addPointIdx()

template<typename PointT , typename LeafContainerT , typename BranchContainerT >
void pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::addPointIdx ( uindex_t point_idx_arg )
overrideprotectedvirtual

Add point at index from input pointcloud dataset to octree.

Parameters
[in] point_idx_arg The index representing the point in the dataset given by setInputCloud() to be added
Note
This virtual implementation allows the use of a transform function to compute keys.

Reimplemented from pcl::octree::OctreePointCloud< PointT, OctreePointCloudAdjacencyContainer< PointT >, OctreeContainerEmpty >.

Definition at line 150 of file octree_pointcloud_adjacency.hpp.

References pcl::isFinite().

addPointsFromInputCloud()

template<typename PointT , typename LeafContainerT , typename BranchContainerT >
void pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::addPointsFromInputCloud

at()

template<typename PointT , typename LeafContainerT = OctreePointCloudAdjacencyContainer<PointT>, typename BranchContainerT = OctreeContainerEmpty>
LeafContainerT* pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::at ( std::size_t idx )
inline

Definition at line 122 of file octree_pointcloud_adjacency.h.

begin()

template<typename PointT , typename LeafContainerT = OctreePointCloudAdjacencyContainer<PointT>, typename BranchContainerT = OctreeContainerEmpty>
iterator pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::begin ( )
inline

Definition at line 112 of file octree_pointcloud_adjacency.h.

computeNeighbors()

template<typename PointT , typename LeafContainerT , typename BranchContainerT >
void pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::computeNeighbors ( OctreeKey & key_arg,
LeafContainerT * leaf_container
)
protected

Fills in the neighbors fields for new voxels.

Parameters
[in] key_arg Key of the voxel to check neighbors for
[in] leaf_container Pointer to container of the leaf to check neighbors for

Definition at line 171 of file octree_pointcloud_adjacency.hpp.

References pcl::octree::OctreeKey::x, pcl::octree::OctreeKey::y, and pcl::octree::OctreeKey::z.

computeVoxelAdjacencyGraph()

template<typename PointT , typename LeafContainerT , typename BranchContainerT >
void pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::computeVoxelAdjacencyGraph ( VoxelAdjacencyList & voxel_adjacency_graph )

Computes an adjacency graph of voxel relations.

Warning
This slows down rapidly as cloud size increases due to the number of edges.
Parameters
[out] voxel_adjacency_graph Boost Graph Library Adjacency graph of the voxel touching relationships. Vertices are PointT, edges represent touching, and edge lengths are the distance between the points.

Definition at line 224 of file octree_pointcloud_adjacency.hpp.

end()

template<typename PointT , typename LeafContainerT = OctreePointCloudAdjacencyContainer<PointT>, typename BranchContainerT = OctreeContainerEmpty>
iterator pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::end ( )
inline

Definition at line 117 of file octree_pointcloud_adjacency.h.

genOctreeKeyforPoint()

template<typename PointT , typename LeafContainerT , typename BranchContainerT >
void pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::genOctreeKeyforPoint ( const PointT & point_arg,
OctreeKey & key_arg
) const
protected

Generates octree key for specified point (uses transform if provided).

Parameters
[in] point_arg Point to generate key for
[out] key_arg Resulting octree key

Definition at line 121 of file octree_pointcloud_adjacency.hpp.

References pcl::isFinite(), pcl::octree::OctreeKey::x, pcl::octree::OctreeKey::y, and pcl::octree::OctreeKey::z.

getLeafContainerAtPoint()

template<typename PointT , typename LeafContainerT , typename BranchContainerT >
LeafContainerT * pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::getLeafContainerAtPoint ( const PointT & point_arg ) const

Gets the leaf container for a given point.

Parameters
[in] point_arg Point to search for
Returns
Pointer to the leaf container - null if no leaf container found.

Definition at line 208 of file octree_pointcloud_adjacency.hpp.

setTransformFunction()

template<typename PointT , typename LeafContainerT = OctreePointCloudAdjacencyContainer<PointT>, typename BranchContainerT = OctreeContainerEmpty>
void pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::setTransformFunction ( std::function< void(PointT &p)> transform_func )
inline

Sets a point transform (and inverse) used to transform the space of the input cloud.

This is useful for changing how adjacency is calculated - such as relaxing the adjacency criterion for points further from the camera.

Parameters
[in] transform_func A boost:function pointer to the transform to be used. The transform must have one parameter (a point) which it modifies in place.

Definition at line 173 of file octree_pointcloud_adjacency.h.

size()

template<typename PointT , typename LeafContainerT = OctreePointCloudAdjacencyContainer<PointT>, typename BranchContainerT = OctreeContainerEmpty>
std::size_t pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::size ( ) const
inline

Definition at line 129 of file octree_pointcloud_adjacency.h.

testForOcclusion()

template<typename PointT , typename LeafContainerT , typename BranchContainerT >
bool pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::testForOcclusion ( const PointT & point_arg,
const PointXYZ & camera_pos = PointXYZ(0, 0, 0)
)

Tests whether input point is occluded from specified camera point by other voxels.

Parameters
[in] point_arg Point to test for
[in] camera_pos Position of camera, defaults to origin
Returns
True if path to camera is blocked by a voxel, false otherwise.

Definition at line 271 of file octree_pointcloud_adjacency.hpp.

References pcl::octree::OctreeKey::x, pcl::octree::OctreeKey::y, and pcl::octree::OctreeKey::z.


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_1octree_1_1_octree_point_cloud_adjacency.html