Point Cloud Library (PCL)
1.9.1-dev
|
Octree pointcloud voxel class which maintains adjacency information for its voxels. More...
#include <pcl/octree/octree_pointcloud_adjacency.h>
Public Types | |
typedef OctreeBase< LeafContainerT, BranchContainerT > | OctreeBaseT |
typedef OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT > | OctreeAdjacencyT |
typedef boost::shared_ptr< OctreeAdjacencyT > | Ptr |
typedef boost::shared_ptr< const OctreeAdjacencyT > | ConstPtr |
typedef OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeBaseT > | OctreePointCloudT |
typedef OctreePointCloudT::LeafNode | LeafNode |
typedef OctreePointCloudT::BranchNode | BranchNode |
typedef pcl::PointCloud< PointT > | PointCloud |
typedef boost::shared_ptr< PointCloud > | PointCloudPtr |
typedef boost::shared_ptr< const PointCloud > | PointCloudConstPtr |
typedef boost::adjacency_list< boost::setS, boost::setS, boost::undirectedS, PointT, float > | VoxelAdjacencyList |
typedef VoxelAdjacencyList::vertex_descriptor | VoxelID |
typedef VoxelAdjacencyList::edge_descriptor | EdgeID |
typedef std::vector< LeafContainerT * > | LeafVectorT |
typedef LeafVectorT::iterator | iterator |
typedef LeafVectorT::const_iterator | const_iterator |
![]() | |
typedef OctreeBase< LeafContainerT, BranchContainerT > | Base |
typedef OctreeBase< LeafContainerT, BranchContainerT >::LeafNode | LeafNode |
typedef OctreeBase< LeafContainerT, BranchContainerT >::BranchNode | BranchNode |
typedef boost::shared_ptr< std::vector< int > > | IndicesPtr |
typedef boost::shared_ptr< const std::vector< int > > | IndicesConstPtr |
typedef pcl::PointCloud< PointT > | PointCloud |
typedef boost::shared_ptr< PointCloud > | PointCloudPtr |
typedef boost::shared_ptr< const PointCloud > | PointCloudConstPtr |
typedef OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeBase< LeafContainerT > > | SingleBuffer |
typedef boost::shared_ptr< OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeBase< LeafContainerT, BranchContainerT > > > | Ptr |
typedef boost::shared_ptr< const OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeBase< LeafContainerT, BranchContainerT > > > | ConstPtr |
typedef std::vector< PointT, Eigen::aligned_allocator< PointT > > | AlignedPointTVector |
typedef std::vector< PointXYZ, Eigen::aligned_allocator< PointXYZ > > | AlignedPointXYZVector |
![]() | |
typedef OctreeBase< LeafContainerT, BranchContainerT > | OctreeT |
typedef OctreeBranchNode< BranchContainerT > | BranchNode |
typedef OctreeLeafNode< LeafContainerT > | LeafNode |
typedef BranchContainerT | BranchContainer |
typedef LeafContainerT | LeafContainer |
typedef OctreeDepthFirstIterator< OctreeT > | Iterator |
typedef const OctreeDepthFirstIterator< OctreeT > | ConstIterator |
typedef OctreeLeafNodeDepthFirstIterator< OctreeT > | LeafNodeIterator |
typedef const OctreeLeafNodeDepthFirstIterator< OctreeT > | ConstLeafNodeIterator |
typedef OctreeLeafNodeDepthFirstIterator< OctreeT > | LeafNodeDepthFirstIterator |
typedef const OctreeLeafNodeDepthFirstIterator< OctreeT > | ConstLeafNodeDepthFirstIterator |
typedef OctreeDepthFirstIterator< OctreeT > | DepthFirstIterator |
typedef const OctreeDepthFirstIterator< OctreeT > | ConstDepthFirstIterator |
typedef OctreeBreadthFirstIterator< OctreeT > | BreadthFirstIterator |
typedef const OctreeBreadthFirstIterator< OctreeT > | ConstBreadthFirstIterator |
typedef OctreeFixedDepthIterator< OctreeT > | FixedDepthIterator |
typedef const OctreeFixedDepthIterator< OctreeT > | ConstFixedDepthIterator |
typedef OctreeLeafNodeBreadthFirstIterator< OctreeT > | LeafNodeBreadthFirstIterator |
typedef const OctreeLeafNodeBreadthFirstIterator< OctreeT > | ConstLeafNodeBreadthFirstIterator |
Public Member Functions | |
iterator | begin () |
iterator | end () |
LeafContainerT * | at (size_t idx) |
size_t | size () const |
OctreePointCloudAdjacency (const double resolution_arg) | |
Constructor. More... | |
~OctreePointCloudAdjacency () | |
Empty class destructor. 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 (boost::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... | |
![]() | |
OctreePointCloud (const double resolution_arg) | |
Octree pointcloud constructor. More... | |
~OctreePointCloud () | |
Empty deconstructor. More... | |
void | setInputCloud (const PointCloudConstPtr &cloud_arg, const IndicesConstPtr &indices_arg=IndicesConstPtr()) |
Provide a pointer to the input data set. More... | |
IndicesConstPtr const | 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... | |
unsigned int | getTreeDepth () const |
Get the maximum depth of the octree. More... | |
void | addPointsFromInputCloud () |
Add points from input point cloud to octree. More... | |
void | addPointFromCloud (const int 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 int &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... | |
int | getOccupiedVoxelCenters (AlignedPointTVector &voxel_center_list_arg) const |
Get a PointT vector of centers of all occupied voxels. More... | |
int | 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 int &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 (unsigned int 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 (unsigned int 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< LeafContainerT, BranchContainerT > > &iterator, Eigen::Vector3f &min_pt, Eigen::Vector3f &max_pt) const |
Generate bounds of the current voxel of an octree iterator. More... | |
void | enableDynamicDepth (size_t maxObjsPerLeaf) |
Enable dynamic octree structure. More... | |
![]() | |
Iterator | begin (unsigned int max_depth_arg=0u) |
const Iterator | end () |
LeafNodeIterator | leaf_begin (unsigned int max_depth_arg=0u) |
const LeafNodeIterator | leaf_end () |
LeafNodeDepthFirstIterator | leaf_depth_begin (unsigned int max_depth_arg=0u) |
const LeafNodeDepthFirstIterator | leaf_depth_end () |
DepthFirstIterator | depth_begin (unsigned int max_depth_arg=0u) |
const DepthFirstIterator | depth_end () |
BreadthFirstIterator | breadth_begin (unsigned int max_depth_arg=0u) |
const BreadthFirstIterator | breadth_end () |
FixedDepthIterator | fixed_depth_begin (unsigned int fixed_depth_arg=0u) |
const FixedDepthIterator | fixed_depth_end () |
LeafNodeBreadthFirstIterator | leaf_breadth_begin (unsigned int max_depth_arg=0u) |
const LeafNodeBreadthFirstIterator | leaf_breadth_end () |
OctreeBase () | |
Empty constructor. More... | |
virtual | ~OctreeBase () |
Empty deconstructor. More... | |
OctreeBase (const OctreeBase &source) | |
Copy constructor. More... | |
OctreeBase & | operator= (const OctreeBase &source) |
Copy operator. More... | |
void | setMaxVoxelIndex (unsigned int max_voxel_index_arg) |
Set the maximum amount of voxels per dimension. More... | |
void | setTreeDepth (unsigned int max_depth_arg) |
Set the maximum depth of the octree. More... | |
unsigned int | getTreeDepth () const |
Get the maximum depth of the octree. More... | |
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). More... | |
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). More... | |
bool | existLeaf (unsigned int idx_x_arg, unsigned int idx_y_arg, unsigned int 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 (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). 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< LeafContainerT * > &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< LeafContainerT * > &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< LeafContainerT * > &leaf_container_vector_arg) |
Deserialize a binary octree description and create a corresponding octree structure. More... | |
Protected Member Functions | |
void | addPointIdx (const int 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... | |
![]() | |
void | expandLeafNode (LeafNode *leaf_node, BranchNode *parent_branch, unsigned char child_idx, unsigned int depth_mask) |
Add point at index from input pointcloud dataset to octree. More... | |
const PointT & | getPointByIndex (const unsigned int index_arg) const |
Get point at index from input pointcloud dataset. More... | |
LeafContainerT * | 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 int &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, unsigned int 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, unsigned int 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... | |
int | 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... | |
![]() | |
LeafContainerT * | createLeaf (const OctreeKey &key_arg) |
Create a leaf node. More... | |
LeafContainerT * | 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... | |
unsigned int | createLeafRecursive (const OctreeKey &key_arg, unsigned int 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, unsigned int depth_mask_arg, BranchNode *branch_arg, LeafContainerT *&result_arg) const |
Recursively search for a given leaf node and return a pointer. More... | |
bool | deleteLeafRecursive (const OctreeKey &key_arg, unsigned int 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< LeafContainerT * > *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, unsigned int 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< LeafContainerT * >::const_iterator *leaf_container_vector_it_arg, typename std::vector< LeafContainerT * >::const_iterator *leaf_container_vector_it_end_arg) |
Recursive method for deserializing octree structure. More... | |
virtual void | serializeTreeCallback (LeafContainerT &, const OctreeKey &) const |
Callback executed for every leaf node during serialization. More... | |
virtual void | deserializeTreeCallback (LeafContainerT &, const OctreeKey &) |
Callback executed for every leaf node during deserialization. More... | |
double | Log2 (double n_arg) |
Helper function to calculate the binary logarithm. More... | |
bool | octreeCanResize () |
Test if octree is able to dynamically change its depth. More... | |
Additional Inherited Members | |
![]() | |
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... | |
![]() | |
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... | |
unsigned int | depth_mask_ |
Depth mask based on octree depth. More... | |
unsigned int | octree_depth_ |
Octree depth. More... | |
bool | dynamic_depth_enabled_ |
Enable dynamic_depth. More... | |
OctreeKey | max_key_ |
key range More... | |
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).
If used in academic work, please cite:
Definition at line 78 of file octree_pointcloud_adjacency.h.
typedef OctreePointCloudT::BranchNode pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::BranchNode |
Definition at line 91 of file octree_pointcloud_adjacency.h.
typedef LeafVectorT::const_iterator pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::const_iterator |
Definition at line 107 of file octree_pointcloud_adjacency.h.
typedef boost::shared_ptr<const OctreeAdjacencyT> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::ConstPtr |
Definition at line 87 of file octree_pointcloud_adjacency.h.
typedef VoxelAdjacencyList::edge_descriptor pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::EdgeID |
Definition at line 100 of file octree_pointcloud_adjacency.h.
typedef LeafVectorT::iterator pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::iterator |
Definition at line 106 of file octree_pointcloud_adjacency.h.
typedef OctreePointCloudT::LeafNode pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::LeafNode |
Definition at line 90 of file octree_pointcloud_adjacency.h.
typedef std::vector<LeafContainerT*> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::LeafVectorT |
Definition at line 103 of file octree_pointcloud_adjacency.h.
typedef OctreePointCloudAdjacency<PointT, LeafContainerT, BranchContainerT> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::OctreeAdjacencyT |
Definition at line 85 of file octree_pointcloud_adjacency.h.
typedef OctreeBase<LeafContainerT, BranchContainerT> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::OctreeBaseT |
Definition at line 83 of file octree_pointcloud_adjacency.h.
typedef OctreePointCloud<PointT, LeafContainerT, BranchContainerT, OctreeBaseT> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::OctreePointCloudT |
Definition at line 89 of file octree_pointcloud_adjacency.h.
typedef pcl::PointCloud<PointT> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::PointCloud |
Definition at line 93 of file octree_pointcloud_adjacency.h.
typedef boost::shared_ptr<const PointCloud> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::PointCloudConstPtr |
Definition at line 95 of file octree_pointcloud_adjacency.h.
typedef boost::shared_ptr<PointCloud> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::PointCloudPtr |
Definition at line 94 of file octree_pointcloud_adjacency.h.
typedef boost::shared_ptr<OctreeAdjacencyT> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::Ptr |
Definition at line 86 of file octree_pointcloud_adjacency.h.
typedef boost::adjacency_list<boost::setS, boost::setS, boost::undirectedS, PointT, float> pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::VoxelAdjacencyList |
Definition at line 98 of file octree_pointcloud_adjacency.h.
typedef VoxelAdjacencyList::vertex_descriptor pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::VoxelID |
Definition at line 99 of file octree_pointcloud_adjacency.h.
pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::OctreePointCloudAdjacency | ( | const double | resolution_arg | ) |
Constructor.
[in] | resolution_arg | Octree resolution at lowest octree level (voxel size) |
Definition at line 54 of file octree_pointcloud_adjacency.hpp.
Referenced by pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::size().
|
inline |
Empty class destructor.
Definition at line 122 of file octree_pointcloud_adjacency.h.
References pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::addPointsFromInputCloud(), pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::computeVoxelAdjacencyGraph(), and pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::getLeafContainerAtPoint().
|
overrideprotectedvirtual |
Add point at index from input pointcloud dataset to octree.
[in] | point_idx_arg | The index representing the point in the dataset given by setInputCloud() to be added |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >.
Definition at line 141 of file octree_pointcloud_adjacency.hpp.
References pcl::octree::OctreeBase< LeafContainerT, BranchContainerT >::createLeaf(), pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::genOctreeKeyforPoint(), pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >::input_, and pcl::isFinite().
Referenced by pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::setTransformFunction().
void pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::addPointsFromInputCloud | ( | ) |
Adds points from cloud to the octree.
Definition at line 63 of file octree_pointcloud_adjacency.hpp.
References pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::addPointsFromInputCloud(), pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::computeNeighbors(), pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >::defineBoundingBox(), pcl::octree::OctreeBase< LeafContainerT, BranchContainerT >::getLeafCount(), pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >::input_, pcl::isFinite(), pcl::octree::OctreeBase< LeafContainerT, BranchContainerT >::leaf_depth_begin(), and pcl::octree::OctreeBase< LeafContainerT, BranchContainerT >::leaf_depth_end().
Referenced by pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::~OctreePointCloudAdjacency().
|
inline |
Definition at line 111 of file octree_pointcloud_adjacency.h.
|
inline |
Definition at line 109 of file octree_pointcloud_adjacency.h.
|
protected |
Fills in the neighbors fields for new voxels.
[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 160 of file octree_pointcloud_adjacency.hpp.
References pcl::octree::OctreeBase< LeafContainerT, BranchContainerT >::findLeaf(), pcl::octree::OctreeBase< LeafContainerT, BranchContainerT >::max_key_, pcl::octree::OctreeKey::x, pcl::octree::OctreeKey::y, and pcl::octree::OctreeKey::z.
Referenced by pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::addPointsFromInputCloud(), and pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::setTransformFunction().
void pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::computeVoxelAdjacencyGraph | ( | VoxelAdjacencyList & | voxel_adjacency_graph | ) |
Computes an adjacency graph of voxel relations.
[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 215 of file octree_pointcloud_adjacency.hpp.
References pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >::genLeafNodeCenterFromOctreeKey(), pcl::octree::OctreeBase< LeafContainerT, BranchContainerT >::leaf_depth_begin(), and pcl::octree::OctreeBase< LeafContainerT, BranchContainerT >::leaf_depth_end().
Referenced by pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::~OctreePointCloudAdjacency().
|
inline |
Definition at line 110 of file octree_pointcloud_adjacency.h.
|
protected |
Generates octree key for specified point (uses transform if provided).
[in] | point_arg | Point to generate key for |
[out] | key_arg | Resulting octree key |
Definition at line 112 of file octree_pointcloud_adjacency.hpp.
References pcl::isFinite(), pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >::min_x_, pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >::min_y_, pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >::min_z_, pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >::resolution_, pcl::octree::OctreeKey::x, pcl::octree::OctreeKey::y, and pcl::octree::OctreeKey::z.
Referenced by pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::addPointIdx(), pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::getLeafContainerAtPoint(), pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::setTransformFunction(), and pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::testForOcclusion().
LeafContainerT * pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::getLeafContainerAtPoint | ( | const PointT & | point_arg | ) | const |
Gets the leaf container for a given point.
[in] | point_arg | Point to search for |
Definition at line 200 of file octree_pointcloud_adjacency.hpp.
References pcl::octree::OctreeBase< LeafContainerT, BranchContainerT >::findLeaf(), and pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::genOctreeKeyforPoint().
Referenced by pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::~OctreePointCloudAdjacency().
|
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.
[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 157 of file octree_pointcloud_adjacency.h.
References pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::addPointFromCloud(), pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::addPointIdx(), pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::addPointToCloud(), pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::computeNeighbors(), pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::genOctreeKeyforPoint(), pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::input_, pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::max_x_, pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::max_y_, pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::max_z_, pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::min_x_, pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::min_y_, pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::min_z_, pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::resolution_, and pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::testForOcclusion().
|
inline |
Definition at line 114 of file octree_pointcloud_adjacency.h.
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.
[in] | point_arg | Point to test for |
[in] | camera_pos | Position of camera, defaults to origin |
Definition at line 259 of file octree_pointcloud_adjacency.hpp.
References pcl::octree::OctreeBase< LeafContainerT, BranchContainerT >::findLeaf(), pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::genOctreeKeyforPoint(), pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >::resolution_, pcl::octree::OctreeKey::x, pcl::octree::OctreeKey::y, and pcl::octree::OctreeKey::z.
Referenced by pcl::octree::OctreePointCloudAdjacency< PointT, LeafContainerT, BranchContainerT >::setTransformFunction().