Octree pointcloud class More...
#include <octree_pointcloud.h>
Public Types | |
typedef std::vector< PointT, Eigen::aligned_allocator < PointT > > | AlignedPointTVector |
typedef OctreeT | Base |
typedef OctreeT::BranchNode | BranchNode |
typedef OctreeBreadthFirstIterator < int, OctreeT > | BreadthFirstIterator |
typedef const OctreeBreadthFirstIterator < int, OctreeT > | ConstBreadthFirstIterator |
typedef const OctreeDepthFirstIterator< int, OctreeT > | ConstDepthFirstIterator |
typedef const OctreeDepthFirstIterator< int, OctreeT > | ConstIterator |
typedef const OctreeLeafNodeIterator< int, OctreeT > | ConstLeafNodeIterator |
typedef boost::shared_ptr < const OctreePointCloud < PointT, LeafT, OctreeT > > | ConstPtr |
typedef OctreeDepthFirstIterator< int, OctreeT > | DepthFirstIterator |
typedef OctreePointCloud < PointT, LeafT, Octree2BufBase< int, LeafT > > | DoubleBuffer |
typedef boost::shared_ptr < const std::vector< int > > | IndicesConstPtr |
typedef boost::shared_ptr < std::vector< int > > | IndicesPtr |
typedef OctreeDepthFirstIterator< int, OctreeT > | Iterator |
typedef OctreeT::LeafNode | LeafNode |
typedef OctreeLeafNodeIterator < int, OctreeT > | LeafNodeIterator |
typedef pcl::PointCloud< PointT > | PointCloud |
typedef boost::shared_ptr < const PointCloud > | PointCloudConstPtr |
typedef boost::shared_ptr < PointCloud > | PointCloudPtr |
typedef boost::shared_ptr < OctreePointCloud< PointT, LeafT, OctreeT > > | Ptr |
typedef OctreePointCloud < PointT, LeafT, OctreeBase < int, LeafT > > | SingleBuffer |
Public Member Functions | |
void | addPointFromCloud (const int pointIdx_arg, IndicesPtr indices_arg) |
Add point at given index from input point cloud to octree. Index will be also added to indices vector. | |
void | addPointsFromInputCloud () |
Add points from input point cloud to octree. | |
void | addPointToCloud (const PointT &point_arg, PointCloudPtr cloud_arg) |
Add point simultaneously to octree and input point cloud. | |
void | addPointToCloud (const PointT &point_arg, PointCloudPtr cloud_arg, IndicesPtr indices_arg) |
Add point simultaneously to octree and input point cloud. A corresponding index will be added to the indices vector. | |
void | defineBoundingBox () |
Investigate dimensions of pointcloud data set and define corresponding bounding box for octree. | |
void | defineBoundingBox (const double minX_arg, const double minY_arg, const double minZ_arg, const double maxX_arg, const double maxY_arg, const double maxZ_arg) |
Define bounding box for octree. | |
void | defineBoundingBox (const double maxX_arg, const double maxY_arg, const double maxZ_arg) |
Define bounding box for octree. | |
void | defineBoundingBox (const double cubeLen_arg) |
Define bounding box cube for octree. | |
void | deleteTree (bool freeMemory_arg=false) |
Delete the octree structure and its leaf nodes. | |
void | deleteVoxelAtPoint (const PointT &point_arg) |
Delete leaf node / voxel at given point. | |
void | deleteVoxelAtPoint (const int &pointIdx_arg) |
Delete leaf node / voxel at given point from input cloud. | |
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. This returns a approximation of the actual intersected voxels by walking along the line with small steps. Voxels are ordered, from closest to furthest w.r.t. the origin. | |
void | getBoundingBox (double &minX_arg, double &minY_arg, double &minZ_arg, double &maxX_arg, double &maxY_arg, double &maxZ_arg) const |
Get bounding box for octree. | |
double | getEpsilon () const |
Get the search epsilon precision (error bound) for nearest neighbors searches. | |
IndicesConstPtr const | getIndices () const |
Get a pointer to the vector of indices used. | |
PointCloudConstPtr | getInputCloud () const |
Get a pointer to the input point cloud dataset. | |
int | getOccupiedVoxelCenters (AlignedPointTVector &voxelCenterList_arg) const |
Get a PointT vector of centers of all occupied voxels. | |
double | getResolution () const |
Get octree voxel resolution. | |
unsigned int | getTreeDepth () const |
Get the maximum depth of the octree. | |
void | getVoxelBounds (OctreeIteratorBase< int, OctreeT > &iterator, Eigen::Vector3f &min_pt, Eigen::Vector3f &max_pt) |
Generate bounds of the current voxel of an octree iterator. | |
double | getVoxelSquaredDiameter (unsigned int treeDepth_arg) const |
Calculates the squared diameter of a voxel at given tree depth. | |
double | getVoxelSquaredDiameter () const |
Calculates the squared diameter of a voxel at leaf depth. | |
double | getVoxelSquaredSideLen (unsigned int treeDepth_arg) const |
Calculates the squared voxel cube side length at given tree depth. | |
double | getVoxelSquaredSideLen () const |
Calculates the squared voxel cube side length at leaf level. | |
bool | isVoxelOccupiedAtPoint (const PointT &point_arg) const |
Check if voxel at given point exist. | |
bool | isVoxelOccupiedAtPoint (const double pointX_arg, const double pointY_arg, const double pointZ_arg) const |
Check if voxel at given point coordinates exist. | |
bool | isVoxelOccupiedAtPoint (const int &pointIdx_arg) const |
Check if voxel at given point from input cloud exist. | |
OctreePointCloud (const double resolution_arg) | |
Octree pointcloud constructor. | |
void | setEpsilon (double eps) |
Set the search epsilon precision (error bound) for nearest neighbors searches. | |
void | setInputCloud (const PointCloudConstPtr &cloud_arg, const IndicesConstPtr &indices_arg=IndicesConstPtr()) |
Provide a pointer to the input data set. | |
void | setResolution (double resolution_arg) |
Set/change the octree voxel resolution. | |
virtual | ~OctreePointCloud () |
Empty deconstructor. | |
Protected Member Functions | |
void | addPointIdx (const int pointIdx_arg) |
Add point at index from input pointcloud dataset to octree. | |
void | adoptBoundingBoxToPoint (const PointT &pointIdx_arg) |
Grow the bounding box/octree until point fits. | |
LeafT * | findLeafAtPoint (const PointT &point_arg) const |
Find octree leaf node at a given point. | |
void | genLeafNodeCenterFromOctreeKey (const OctreeKey &key_arg, PointT &point_arg) const |
Generate a point at center of leaf node voxel. | |
virtual bool | genOctreeKeyForDataT (const int &data_arg, OctreeKey &key_arg) const |
Virtual method for generating octree key for a given point index. | |
void | genOctreeKeyforPoint (const PointT &point_arg, OctreeKey &key_arg) const |
Generate octree key for voxel at a given point. | |
void | genOctreeKeyforPoint (const double pointX_arg, const double pointY_arg, const double pointZ_arg, OctreeKey &key_arg) const |
Generate octree key for voxel at a given point. | |
void | genVoxelBoundsFromOctreeKey (const OctreeKey &key_arg, unsigned int treeDepth_arg, Eigen::Vector3f &min_pt, Eigen::Vector3f &max_pt) const |
Generate bounds of an octree voxel using octree key and tree depth arguments. | |
void | genVoxelCenterFromOctreeKey (const OctreeKey &key_arg, unsigned int treeDepth_arg, PointT &point_arg) const |
Generate a point at center of octree voxel at given tree level. | |
void | getKeyBitSize () |
Define octree key setting and octree depth based on defined bounding box. | |
int | getOccupiedVoxelCentersRecursive (const BranchNode *node_arg, const OctreeKey &key_arg, AlignedPointTVector &voxelCenterList_arg) const |
Recursively search the tree for all leaf nodes and return a vector of voxel centers. | |
const PointT & | getPointByIndex (const unsigned int index_arg) const |
Get point at index from input pointcloud dataset. | |
bool | isPointWithinBoundingBox (const PointT &pointIdx_arg) const |
Checks if given point is within the bounding box of the octree. | |
Protected Attributes | |
bool | boundingBoxDefined_ |
Flag indicating if octree has defined bounding box. | |
double | epsilon_ |
Epsilon precision (error bound) for nearest neighbors searches. | |
IndicesConstPtr | indices_ |
A pointer to the vector of point indices to use. | |
PointCloudConstPtr | input_ |
Pointer to input point cloud dataset. | |
double | maxX_ |
double | maxY_ |
double | maxZ_ |
double | minX_ |
double | minY_ |
double | minZ_ |
double | resolution_ |
Octree resolution. | |
Friends | |
class | OctreeBreadthFirstIterator< int, OctreeT > |
class | OctreeDepthFirstIterator< int, OctreeT > |
class | OctreeIteratorBase< int, OctreeT > |
class | OctreeLeafNodeIterator< int, OctreeT > |
Octree pointcloud class
Definition at line 80 of file octree_pointcloud.h.
typedef std::vector<PointT, Eigen::aligned_allocator<PointT> > pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::AlignedPointTVector |
Reimplemented in pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >, pcl::octree::OctreePointCloudVoxelCentroid< PointT, LeafT, BranchT >, and pcl::octree::OctreePointCloudVoxelCentroid< pcl::PointXYZ >.
Definition at line 132 of file octree_pointcloud.h.
typedef OctreeT pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::Base |
Definition at line 89 of file octree_pointcloud.h.
typedef OctreeT::BranchNode pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::BranchNode |
Reimplemented in pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >, pcl::octree::PointCloudCompression< PointT, LeafT, BranchT, OctreeT >, and pcl::octree::PointCloudCompression< pcl::PointXYZRGBA >.
Definition at line 92 of file octree_pointcloud.h.
typedef OctreeBreadthFirstIterator<int, OctreeT> pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::BreadthFirstIterator |
Definition at line 103 of file octree_pointcloud.h.
typedef const OctreeBreadthFirstIterator<int, OctreeT> pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::ConstBreadthFirstIterator |
Definition at line 104 of file octree_pointcloud.h.
typedef const OctreeDepthFirstIterator<int, OctreeT> pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::ConstDepthFirstIterator |
Definition at line 102 of file octree_pointcloud.h.
typedef const OctreeDepthFirstIterator<int, OctreeT> pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::ConstIterator |
Definition at line 96 of file octree_pointcloud.h.
typedef const OctreeLeafNodeIterator<int, OctreeT> pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::ConstLeafNodeIterator |
Definition at line 99 of file octree_pointcloud.h.
typedef boost::shared_ptr<const OctreePointCloud<PointT, LeafT, OctreeT> > pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::ConstPtr |
Reimplemented in pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >.
Definition at line 129 of file octree_pointcloud.h.
typedef OctreeDepthFirstIterator<int, OctreeT> pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::DepthFirstIterator |
Definition at line 101 of file octree_pointcloud.h.
typedef OctreePointCloud<PointT, LeafT, Octree2BufBase<int, LeafT> > pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::DoubleBuffer |
typedef boost::shared_ptr<const std::vector<int> > pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::IndicesConstPtr |
Reimplemented in pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >.
Definition at line 117 of file octree_pointcloud.h.
typedef boost::shared_ptr<std::vector<int> > pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::IndicesPtr |
Reimplemented in pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >.
Definition at line 116 of file octree_pointcloud.h.
typedef OctreeDepthFirstIterator<int, OctreeT> pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::Iterator |
Definition at line 95 of file octree_pointcloud.h.
typedef OctreeT::LeafNode pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::LeafNode |
Reimplemented in pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >, pcl::octree::PointCloudCompression< PointT, LeafT, BranchT, OctreeT >, and pcl::octree::PointCloudCompression< pcl::PointXYZRGBA >.
Definition at line 91 of file octree_pointcloud.h.
typedef OctreeLeafNodeIterator<int, OctreeT> pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::LeafNodeIterator |
Definition at line 98 of file octree_pointcloud.h.
typedef pcl::PointCloud<PointT> pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::PointCloud |
Reimplemented in pcl::octree::PointCloudCompression< PointT, LeafT, BranchT, OctreeT >, pcl::octree::PointCloudCompression< pcl::PointXYZRGBA >, pcl::octree::OctreePointCloudOccupancy< PointT, LeafT, BranchT >, and pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >.
Definition at line 119 of file octree_pointcloud.h.
typedef boost::shared_ptr<const PointCloud> pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::PointCloudConstPtr |
Reimplemented in pcl::octree::PointCloudCompression< PointT, LeafT, BranchT, OctreeT >, pcl::octree::PointCloudCompression< pcl::PointXYZRGBA >, pcl::octree::OctreePointCloudOccupancy< PointT, LeafT, BranchT >, and pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >.
Definition at line 121 of file octree_pointcloud.h.
typedef boost::shared_ptr<PointCloud> pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::PointCloudPtr |
Reimplemented in pcl::octree::PointCloudCompression< PointT, LeafT, BranchT, OctreeT >, pcl::octree::PointCloudCompression< pcl::PointXYZRGBA >, pcl::octree::OctreePointCloudOccupancy< PointT, LeafT, BranchT >, and pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >.
Definition at line 120 of file octree_pointcloud.h.
typedef boost::shared_ptr<OctreePointCloud<PointT, LeafT, OctreeT> > pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::Ptr |
Reimplemented in pcl::octree::OctreePointCloudSearch< PointT, LeafT, BranchT >.
Definition at line 128 of file octree_pointcloud.h.
typedef OctreePointCloud<PointT, LeafT, OctreeBase<int, LeafT> > pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::SingleBuffer |
pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::OctreePointCloud | ( | const double | resolution_arg | ) |
Octree pointcloud constructor.
[in] | resolution_arg | octree resolution at lowest octree level |
Definition at line 49 of file octree_pointcloud.hpp.
pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::~OctreePointCloud | ( | ) | [virtual] |
Empty deconstructor.
Definition at line 59 of file octree_pointcloud.hpp.
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::addPointFromCloud | ( | const int | pointIdx_arg, |
IndicesPtr | indices_arg | ||
) |
Add point at given index from input point cloud to octree. Index will be also added to indices vector.
[in] | pointIdx_arg | index of point to be added |
[in] | indices_arg | pointer to indices vector of the dataset (given by setInputCloud) |
Definition at line 98 of file octree_pointcloud.hpp.
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::addPointIdx | ( | const int | pointIdx_arg | ) | [protected] |
Add point at index from input pointcloud dataset to octree.
[in] | pointIdx_arg | the index representing the point in the dataset given by setInputCloud to be added |
Definition at line 507 of file octree_pointcloud.hpp.
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::addPointsFromInputCloud | ( | ) |
Add points from input point cloud to octree.
Definition at line 65 of file octree_pointcloud.hpp.
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::addPointToCloud | ( | const PointT & | point_arg, |
PointCloudPtr | cloud_arg | ||
) |
Add point simultaneously to octree and input point cloud.
[in] | point_arg | point to be added |
[in] | cloud_arg | pointer to input point cloud dataset (given by setInputCloud) |
Definition at line 107 of file octree_pointcloud.hpp.
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::addPointToCloud | ( | const PointT & | point_arg, |
PointCloudPtr | cloud_arg, | ||
IndicesPtr | indices_arg | ||
) |
Add point simultaneously to octree and input point cloud. A corresponding index will be added to the indices vector.
[in] | point_arg | point to be added |
[in] | cloud_arg | pointer to input point cloud dataset (given by setInputCloud) |
[in] | indices_arg | pointer to indices vector of the dataset (given by setInputCloud) |
Definition at line 118 of file octree_pointcloud.hpp.
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::adoptBoundingBoxToPoint | ( | const PointT & | pointIdx_arg | ) | [protected] |
Grow the bounding box/octree until point fits.
[in] | pointIdx_arg | point that should be within bounding box; |
Definition at line 417 of file octree_pointcloud.hpp.
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::defineBoundingBox | ( | ) |
Investigate dimensions of pointcloud data set and define corresponding bounding box for octree.
Definition at line 266 of file octree_pointcloud.hpp.
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::defineBoundingBox | ( | const double | minX_arg, |
const double | minY_arg, | ||
const double | minZ_arg, | ||
const double | maxX_arg, | ||
const double | maxY_arg, | ||
const double | maxZ_arg | ||
) |
Define bounding box for octree.
[in] | minX_arg | X coordinate of lower bounding box corner |
[in] | minY_arg | Y coordinate of lower bounding box corner |
[in] | minZ_arg | Z coordinate of lower bounding box corner |
[in] | maxX_arg | X coordinate of upper bounding box corner |
[in] | maxY_arg | Y coordinate of upper bounding box corner |
[in] | maxZ_arg | Z coordinate of upper bounding box corner |
Definition at line 295 of file octree_pointcloud.hpp.
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::defineBoundingBox | ( | const double | maxX_arg, |
const double | maxY_arg, | ||
const double | maxZ_arg | ||
) |
Define bounding box for octree.
[in] | maxX_arg | X coordinate of upper bounding box corner |
[in] | maxY_arg | Y coordinate of upper bounding box corner |
[in] | maxZ_arg | Z coordinate of upper bounding box corner |
Definition at line 334 of file octree_pointcloud.hpp.
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::defineBoundingBox | ( | const double | cubeLen_arg | ) |
Define bounding box cube for octree.
[in] | cubeLen_arg | side length of bounding box cube. |
Definition at line 369 of file octree_pointcloud.hpp.
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::deleteTree | ( | bool | freeMemory_arg = false | ) | [inline] |
Delete the octree structure and its leaf nodes.
freeMemory_arg,: | if "true", allocated octree nodes are deleted, otherwise they are pushed to the octree node pool |
Definition at line 243 of file octree_pointcloud.h.
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::deleteVoxelAtPoint | ( | const PointT & | point_arg | ) |
Delete leaf node / voxel at given point.
[in] | point_arg | point addressing the voxel to be deleted. |
Definition at line 168 of file octree_pointcloud.hpp.
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::deleteVoxelAtPoint | ( | const int & | pointIdx_arg | ) |
Delete leaf node / voxel at given point from input cloud.
[in] | pointIdx_arg | index of point addressing the voxel to be deleted. |
Definition at line 180 of file octree_pointcloud.hpp.
LeafT * pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::findLeafAtPoint | ( | const PointT & | point_arg | ) | const [protected] |
Find octree leaf node at a given point.
[in] | point_arg | query point |
Definition at line 536 of file octree_pointcloud.hpp.
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::genLeafNodeCenterFromOctreeKey | ( | const OctreeKey & | key_arg, |
PointT & | point_arg | ||
) | const [protected] |
Generate a point at center of leaf node voxel.
[in] | key_arg | octree key addressing a leaf node. |
[out] | point_arg | write leaf node voxel center to this point reference |
Definition at line 646 of file octree_pointcloud.hpp.
bool pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::genOctreeKeyForDataT | ( | const int & | data_arg, |
OctreeKey & | key_arg | ||
) | const [protected, virtual] |
Virtual method for generating octree key for a given point index.
[in] | data_arg | index value representing a point in the dataset given by setInputCloud |
[out] | key_arg | write octree key to this reference |
Definition at line 634 of file octree_pointcloud.hpp.
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::genOctreeKeyforPoint | ( | const PointT & | point_arg, |
OctreeKey & | key_arg | ||
) | const [protected] |
Generate octree key for voxel at a given point.
[in] | point_arg | the point addressing a voxel |
[out] | key_arg | write octree key to this reference |
Definition at line 607 of file octree_pointcloud.hpp.
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::genOctreeKeyforPoint | ( | const double | pointX_arg, |
const double | pointY_arg, | ||
const double | pointZ_arg, | ||
OctreeKey & | key_arg | ||
) | const [protected] |
Generate octree key for voxel at a given point.
[in] | pointX_arg | X coordinate of point addressing a voxel |
[in] | pointY_arg | Y coordinate of point addressing a voxel |
[in] | pointZ_arg | Z coordinate of point addressing a voxel |
[out] | key_arg | write octree key to this reference |
Definition at line 618 of file octree_pointcloud.hpp.
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::genVoxelBoundsFromOctreeKey | ( | const OctreeKey & | key_arg, |
unsigned int | treeDepth_arg, | ||
Eigen::Vector3f & | min_pt, | ||
Eigen::Vector3f & | max_pt | ||
) | const [protected] |
Generate bounds of an octree voxel using octree key and tree depth arguments.
[in] | key_arg | octree key addressing an octree node. |
[in] | treeDepth_arg | octree depth of query voxel |
[out] | min_pt | lower bound of voxel |
[out] | max_pt | upper bound of voxel |
Definition at line 669 of file octree_pointcloud.hpp.
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::genVoxelCenterFromOctreeKey | ( | const OctreeKey & | key_arg, |
unsigned int | treeDepth_arg, | ||
PointT & | point_arg | ||
) | const [protected] |
Generate a point at center of octree voxel at given tree level.
[in] | key_arg | octree key addressing an octree node. |
[in] | treeDepth_arg | octree depth of query voxel |
[out] | point_arg | write leaf node center point to this reference |
Definition at line 656 of file octree_pointcloud.hpp.
int pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::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. This returns a approximation of the actual intersected voxels by walking along the line with small steps. Voxels are ordered, from closest to furthest w.r.t. the origin.
[in] | origin | origin of the line segment |
[in] | end | end of the line segment |
[out] | voxel_center_list | results are written to this vector of PointT elements |
[in] | precision | determines the size of the steps: step_size = octree_resolution x precision |
Definition at line 205 of file octree_pointcloud.hpp.
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getBoundingBox | ( | double & | minX_arg, |
double & | minY_arg, | ||
double & | minZ_arg, | ||
double & | maxX_arg, | ||
double & | maxY_arg, | ||
double & | maxZ_arg | ||
) | const |
Get bounding box for octree.
[in] | minX_arg | X coordinate of lower bounding box corner |
[in] | minY_arg | Y coordinate of lower bounding box corner |
[in] | minZ_arg | Z coordinate of lower bounding box corner |
[in] | maxX_arg | X coordinate of upper bounding box corner |
[in] | maxY_arg | Y coordinate of upper bounding box corner |
[in] | maxZ_arg | Z coordinate of upper bounding box corner |
Definition at line 401 of file octree_pointcloud.hpp.
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getEpsilon | ( | ) | const [inline] |
Get the search epsilon precision (error bound) for nearest neighbors searches.
Definition at line 172 of file octree_pointcloud.h.
IndicesConstPtr const pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getIndices | ( | ) | const [inline] |
Get a pointer to the vector of indices used.
Definition at line 150 of file octree_pointcloud.h.
PointCloudConstPtr pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getInputCloud | ( | ) | const [inline] |
Get a pointer to the input point cloud dataset.
Definition at line 158 of file octree_pointcloud.h.
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getKeyBitSize | ( | ) | [protected] |
Define octree key setting and octree depth based on defined bounding box.
Definition at line 548 of file octree_pointcloud.hpp.
int pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getOccupiedVoxelCenters | ( | AlignedPointTVector & | voxelCenterList_arg | ) | const |
Get a PointT vector of centers of all occupied voxels.
[out] | voxelCenterList_arg | results are written to this vector of PointT elements |
Definition at line 191 of file octree_pointcloud.hpp.
int pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getOccupiedVoxelCentersRecursive | ( | const BranchNode * | node_arg, |
const OctreeKey & | key_arg, | ||
AlignedPointTVector & | voxelCenterList_arg | ||
) | const [protected] |
Recursively search the tree for all leaf nodes and return a vector of voxel centers.
[in] | node_arg | current octree node to be explored |
[in] | key_arg | octree key addressing a leaf node. |
[out] | voxelCenterList_arg | results are written to this vector of PointT elements |
Definition at line 713 of file octree_pointcloud.hpp.
const PointT & pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getPointByIndex | ( | const unsigned int | index_arg | ) | const [protected] |
Get point at index from input pointcloud dataset.
[in] | index_arg | index representing the point in the dataset given by setInputCloud |
Definition at line 527 of file octree_pointcloud.hpp.
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getResolution | ( | ) | const [inline] |
Get octree voxel resolution.
Definition at line 193 of file octree_pointcloud.h.
unsigned int pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getTreeDepth | ( | ) | const [inline] |
Get the maximum depth of the octree.
Definition at line 201 of file octree_pointcloud.h.
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getVoxelBounds | ( | OctreeIteratorBase< int, OctreeT > & | iterator, |
Eigen::Vector3f & | min_pt, | ||
Eigen::Vector3f & | max_pt | ||
) | [inline] |
Generate bounds of the current voxel of an octree iterator.
[in] | iterator,: | octree iterator |
[out] | min_pt | lower bound of voxel |
[out] | max_pt | upper bound of voxel |
Definition at line 393 of file octree_pointcloud.h.
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getVoxelSquaredDiameter | ( | unsigned int | treeDepth_arg | ) | const |
Calculates the squared diameter of a voxel at given tree depth.
[in] | treeDepth_arg | depth/level in octree |
Definition at line 705 of file octree_pointcloud.hpp.
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getVoxelSquaredDiameter | ( | ) | const [inline] |
Calculates the squared diameter of a voxel at leaf depth.
Definition at line 368 of file octree_pointcloud.h.
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getVoxelSquaredSideLen | ( | unsigned int | treeDepth_arg | ) | const |
Calculates the squared voxel cube side length at given tree depth.
[in] | treeDepth_arg | depth/level in octree |
Definition at line 690 of file octree_pointcloud.hpp.
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::getVoxelSquaredSideLen | ( | ) | const [inline] |
Calculates the squared voxel cube side length at leaf level.
Definition at line 383 of file octree_pointcloud.h.
bool pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::isPointWithinBoundingBox | ( | const PointT & | pointIdx_arg | ) | const [inline, protected] |
Checks if given point is within the bounding box of the octree.
[in] | pointIdx_arg | point to be checked for bounding box violations |
Definition at line 440 of file octree_pointcloud.h.
bool pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::isVoxelOccupiedAtPoint | ( | const PointT & | point_arg | ) | const |
Check if voxel at given point exist.
[in] | point_arg | point to be checked |
Definition at line 131 of file octree_pointcloud.hpp.
bool pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::isVoxelOccupiedAtPoint | ( | const double | pointX_arg, |
const double | pointY_arg, | ||
const double | pointZ_arg | ||
) | const |
Check if voxel at given point coordinates exist.
[in] | pointX_arg | X coordinate of point to be checked |
[in] | pointY_arg | Y coordinate of point to be checked |
[in] | pointZ_arg | Z coordinate of point to be checked |
Definition at line 155 of file octree_pointcloud.hpp.
bool pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::isVoxelOccupiedAtPoint | ( | const int & | pointIdx_arg | ) | const |
Check if voxel at given point from input cloud exist.
[in] | pointIdx_arg | point to be checked |
Definition at line 144 of file octree_pointcloud.hpp.
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::setEpsilon | ( | double | eps | ) | [inline] |
Set the search epsilon precision (error bound) for nearest neighbors searches.
[in] | eps | precision (error bound) for nearest neighbors searches |
Definition at line 166 of file octree_pointcloud.h.
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::setInputCloud | ( | const PointCloudConstPtr & | cloud_arg, |
const IndicesConstPtr & | indices_arg = IndicesConstPtr () |
||
) | [inline] |
Provide a pointer to the input data set.
[in] | cloud_arg | the const boost shared pointer to a PointCloud message |
[in] | indices_arg | the point indices subset that is to be used from cloud - if 0 the whole point cloud is used |
Definition at line 138 of file octree_pointcloud.h.
void pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::setResolution | ( | double | resolution_arg | ) | [inline] |
Set/change the octree voxel resolution.
[in] | resolution_arg | side length of voxels at lowest tree level |
Definition at line 180 of file octree_pointcloud.h.
friend class OctreeBreadthFirstIterator< int, OctreeT > [friend] |
Definition at line 85 of file octree_pointcloud.h.
friend class OctreeDepthFirstIterator< int, OctreeT > [friend] |
Definition at line 84 of file octree_pointcloud.h.
friend class OctreeIteratorBase< int, OctreeT > [friend] |
Definition at line 83 of file octree_pointcloud.h.
friend class OctreeLeafNodeIterator< int, OctreeT > [friend] |
Definition at line 86 of file octree_pointcloud.h.
bool pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::boundingBoxDefined_ [protected] |
Flag indicating if octree has defined bounding box.
Definition at line 539 of file octree_pointcloud.h.
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::epsilon_ [protected] |
Epsilon precision (error bound) for nearest neighbors searches.
Definition at line 523 of file octree_pointcloud.h.
IndicesConstPtr pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::indices_ [protected] |
A pointer to the vector of point indices to use.
Definition at line 520 of file octree_pointcloud.h.
PointCloudConstPtr pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::input_ [protected] |
Pointer to input point cloud dataset.
Definition at line 517 of file octree_pointcloud.h.
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::maxX_ [protected] |
Definition at line 530 of file octree_pointcloud.h.
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::maxY_ [protected] |
Definition at line 533 of file octree_pointcloud.h.
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::maxZ_ [protected] |
Definition at line 536 of file octree_pointcloud.h.
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::minX_ [protected] |
Definition at line 529 of file octree_pointcloud.h.
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::minY_ [protected] |
Definition at line 532 of file octree_pointcloud.h.
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::minZ_ [protected] |
Definition at line 535 of file octree_pointcloud.h.
double pcl::octree::OctreePointCloud< PointT, LeafT, BranchT, OctreeT >::resolution_ [protected] |
Octree resolution.
Definition at line 526 of file octree_pointcloud.h.