Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040 #ifndef PCL_OCTREE_VOXELCENTROID_HPP
00041 #define PCL_OCTREE_VOXELCENTROID_HPP
00042
00043 #include <pcl/octree/octree_pointcloud_voxelcentroid.h>
00044
00046 template<typename PointT, typename LeafContainerT, typename BranchContainerT> bool
00047 pcl::octree::OctreePointCloudVoxelCentroid<PointT, LeafContainerT, BranchContainerT>::getVoxelCentroidAtPoint (
00048 const PointT& point_arg, PointT& voxel_centroid_arg) const
00049 {
00050 OctreeKey key;
00051 LeafNode* leaf = 0;
00052
00053
00054 genOctreeKeyforPoint (point_arg, key);
00055
00056 leaf = this->findLeaf (key);
00057
00058 if (leaf)
00059 {
00060 LeafContainerT* container = leaf;
00061 container->getCentroid (voxel_centroid_arg);
00062 }
00063
00064 return (leaf != 0);
00065 }
00066
00068 template<typename PointT, typename LeafContainerT, typename BranchContainerT> size_t
00069 pcl::octree::OctreePointCloudVoxelCentroid<PointT, LeafContainerT, BranchContainerT>::getVoxelCentroids (
00070 typename OctreePointCloud<PointT, LeafContainerT, BranchContainerT>::AlignedPointTVector &voxel_centroid_list_arg) const
00071 {
00072 OctreeKey new_key;
00073
00074
00075 voxel_centroid_list_arg.clear ();
00076 voxel_centroid_list_arg.reserve (this->leaf_count_);
00077
00078 getVoxelCentroidsRecursive (this->root_node_, new_key, voxel_centroid_list_arg );
00079
00080
00081 return (voxel_centroid_list_arg.size ());
00082 }
00083
00085 template<typename PointT, typename LeafContainerT, typename BranchContainerT> void
00086 pcl::octree::OctreePointCloudVoxelCentroid<PointT, LeafContainerT, BranchContainerT>::getVoxelCentroidsRecursive (
00087 const BranchNode* branch_arg, OctreeKey& key_arg,
00088 typename OctreePointCloud<PointT, LeafContainerT, BranchContainerT>::AlignedPointTVector &voxel_centroid_list_arg) const
00089 {
00090
00091 unsigned char child_idx;
00092
00093
00094 for (child_idx = 0; child_idx < 8; child_idx++)
00095 {
00096
00097 if (branch_arg->hasChild (child_idx))
00098 {
00099
00100 key_arg.pushBranch (child_idx);
00101
00102 OctreeNode *child_node = branch_arg->getChildPtr (child_idx);
00103
00104 switch (child_node->getNodeType ())
00105 {
00106 case BRANCH_NODE:
00107 {
00108
00109 getVoxelCentroidsRecursive (static_cast<const BranchNode*> (child_node), key_arg, voxel_centroid_list_arg);
00110 break;
00111 }
00112 case LEAF_NODE:
00113 {
00114 PointT new_centroid;
00115
00116 LeafNode* container = static_cast<LeafNode*> (child_node);
00117
00118 container->getContainer().getCentroid (new_centroid);
00119
00120 voxel_centroid_list_arg.push_back (new_centroid);
00121 break;
00122 }
00123 default:
00124 break;
00125 }
00126
00127
00128 key_arg.popBranch ();
00129 }
00130 }
00131 }
00132
00133
00134 #define PCL_INSTANTIATE_OctreePointCloudVoxelCentroid(T) template class PCL_EXPORTS pcl::octree::OctreePointCloudVoxelCentroid<T>;
00135
00136 #endif
00137