Octree pointcloud voxel centroid class More...
#include <octree_pointcloud_voxelcentroid.h>
Public Types | |
typedef OctreeT::BranchNode | BranchNode |
typedef boost::shared_ptr < const OctreePointCloudVoxelCentroid < PointT, LeafContainerT > > | ConstPtr |
typedef OctreeT::LeafNode | LeafNode |
typedef OctreePointCloud < PointT, LeafContainerT, BranchContainerT > | OctreeT |
typedef boost::shared_ptr < OctreePointCloudVoxelCentroid < PointT, LeafContainerT > > | Ptr |
Public Member Functions | |
virtual void | addPointIdx (const int pointIdx_arg) |
Add DataT object to leaf node at octree key. | |
bool | getVoxelCentroidAtPoint (const PointT &point_arg, PointT &voxel_centroid_arg) const |
Get centroid for a single voxel addressed by a PointT point. | |
bool | getVoxelCentroidAtPoint (const int &point_idx_arg, PointT &voxel_centroid_arg) const |
Get centroid for a single voxel addressed by a PointT point from input cloud. | |
size_t | getVoxelCentroids (typename OctreePointCloud< PointT, LeafContainerT, BranchContainerT >::AlignedPointTVector &voxel_centroid_list_arg) const |
Get PointT vector of centroids for all occupied voxels. | |
void | getVoxelCentroidsRecursive (const BranchNode *branch_arg, OctreeKey &key_arg, typename OctreePointCloud< PointT, LeafContainerT, BranchContainerT >::AlignedPointTVector &voxel_centroid_list_arg) const |
Recursively explore the octree and output a PointT vector of centroids for all occupied voxels. | |
OctreePointCloudVoxelCentroid (const double resolution_arg) | |
OctreePointCloudVoxelCentroids class constructor. | |
virtual | ~OctreePointCloudVoxelCentroid () |
Empty class deconstructor. |
Octree pointcloud voxel centroid class
Definition at line 146 of file octree_pointcloud_voxelcentroid.h.
typedef OctreeT::BranchNode pcl::octree::OctreePointCloudVoxelCentroid< PointT, LeafContainerT, BranchContainerT >::BranchNode |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >.
Definition at line 154 of file octree_pointcloud_voxelcentroid.h.
typedef boost::shared_ptr<const OctreePointCloudVoxelCentroid<PointT, LeafContainerT> > pcl::octree::OctreePointCloudVoxelCentroid< PointT, LeafContainerT, BranchContainerT >::ConstPtr |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >.
Definition at line 150 of file octree_pointcloud_voxelcentroid.h.
typedef OctreeT::LeafNode pcl::octree::OctreePointCloudVoxelCentroid< PointT, LeafContainerT, BranchContainerT >::LeafNode |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >.
Definition at line 153 of file octree_pointcloud_voxelcentroid.h.
typedef OctreePointCloud<PointT, LeafContainerT, BranchContainerT> pcl::octree::OctreePointCloudVoxelCentroid< PointT, LeafContainerT, BranchContainerT >::OctreeT |
Reimplemented from pcl::octree::OctreeBase< LeafContainerT, BranchContainerT >.
Definition at line 152 of file octree_pointcloud_voxelcentroid.h.
typedef boost::shared_ptr<OctreePointCloudVoxelCentroid<PointT, LeafContainerT> > pcl::octree::OctreePointCloudVoxelCentroid< PointT, LeafContainerT, BranchContainerT >::Ptr |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >.
Definition at line 149 of file octree_pointcloud_voxelcentroid.h.
pcl::octree::OctreePointCloudVoxelCentroid< PointT, LeafContainerT, BranchContainerT >::OctreePointCloudVoxelCentroid | ( | const double | resolution_arg | ) | [inline] |
OctreePointCloudVoxelCentroids class constructor.
[in] | resolution_arg | octree resolution at lowest octree level |
Definition at line 159 of file octree_pointcloud_voxelcentroid.h.
virtual pcl::octree::OctreePointCloudVoxelCentroid< PointT, LeafContainerT, BranchContainerT >::~OctreePointCloudVoxelCentroid | ( | ) | [inline, virtual] |
Empty class deconstructor.
Definition at line 166 of file octree_pointcloud_voxelcentroid.h.
virtual void pcl::octree::OctreePointCloudVoxelCentroid< PointT, LeafContainerT, BranchContainerT >::addPointIdx | ( | const int | pointIdx_arg | ) | [inline, virtual] |
Add DataT object to leaf node at octree key.
[in] | key_arg | octree key addressing a leaf node. |
[in] | data_arg | DataT object to be added. |
Reimplemented from pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT >.
Definition at line 175 of file octree_pointcloud_voxelcentroid.h.
bool pcl::octree::OctreePointCloudVoxelCentroid< PointT, LeafContainerT, BranchContainerT >::getVoxelCentroidAtPoint | ( | const PointT & | point_arg, |
PointT & | voxel_centroid_arg | ||
) | const |
Get centroid for a single voxel addressed by a PointT point.
[in] | point_arg | point addressing a voxel in octree |
[out] | voxel_centroid_arg | centroid is written to this PointT reference |
Definition at line 47 of file octree_pointcloud_voxelcentroid.hpp.
bool pcl::octree::OctreePointCloudVoxelCentroid< PointT, LeafContainerT, BranchContainerT >::getVoxelCentroidAtPoint | ( | const int & | point_idx_arg, |
PointT & | voxel_centroid_arg | ||
) | const [inline] |
Get centroid for a single voxel addressed by a PointT point from input cloud.
[in] | point_idx_arg | point index from input cloud addressing a voxel in octree |
[out] | voxel_centroid_arg | centroid is written to this PointT reference |
Definition at line 209 of file octree_pointcloud_voxelcentroid.h.
size_t pcl::octree::OctreePointCloudVoxelCentroid< PointT, LeafContainerT, BranchContainerT >::getVoxelCentroids | ( | typename OctreePointCloud< PointT, LeafContainerT, BranchContainerT >::AlignedPointTVector & | voxel_centroid_list_arg | ) | const |
Get PointT vector of centroids for all occupied voxels.
[out] | voxel_centroid_list_arg | results are written to this vector of PointT elements |
Definition at line 69 of file octree_pointcloud_voxelcentroid.hpp.
void pcl::octree::OctreePointCloudVoxelCentroid< PointT, LeafContainerT, BranchContainerT >::getVoxelCentroidsRecursive | ( | const BranchNode * | branch_arg, |
OctreeKey & | key_arg, | ||
typename OctreePointCloud< PointT, LeafContainerT, BranchContainerT >::AlignedPointTVector & | voxel_centroid_list_arg | ||
) | const |
Recursively explore the octree and output a PointT vector of centroids for all occupied voxels.
[in] | branch_arg,: | current branch node |
[in] | key_arg,: | current key |
[out] | voxel_centroid_list_arg | results are written to this vector of PointT elements |
Definition at line 86 of file octree_pointcloud_voxelcentroid.hpp.