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 #ifndef PCL_OCTREE_OCCUPANCY_H
00040 #define PCL_OCTREE_OCCUPANCY_H
00041
00042 #include "octree_pointcloud.h"
00043
00044 namespace pcl
00045 {
00046 namespace octree
00047 {
00048
00050
00058
00059 template<typename PointT,
00060 typename LeafContainerT = OctreeContainerEmpty,
00061 typename BranchContainerT = OctreeContainerEmpty >
00062 class OctreePointCloudOccupancy : public OctreePointCloud<PointT, LeafContainerT,
00063 BranchContainerT, OctreeBase<LeafContainerT, BranchContainerT> >
00064
00065 {
00066
00067 public:
00068
00069 typedef OctreePointCloudOccupancy<PointT, LeafContainerT, BranchContainerT> SingleBuffer;
00070 typedef OctreePointCloudOccupancy<PointT, LeafContainerT, BranchContainerT> DoubleBuffer;
00071
00072
00073 typedef typename OctreePointCloud<PointT, LeafContainerT, BranchContainerT>::PointCloud PointCloud;
00074 typedef typename OctreePointCloud<PointT, LeafContainerT, BranchContainerT>::PointCloudPtr PointCloudPtr;
00075 typedef typename OctreePointCloud<PointT, LeafContainerT, BranchContainerT>::PointCloudConstPtr PointCloudConstPtr;
00076
00080 OctreePointCloudOccupancy (const double resolution_arg) :
00081 OctreePointCloud<PointT, LeafContainerT, BranchContainerT,
00082 OctreeBase<LeafContainerT, BranchContainerT> > (resolution_arg)
00083 {
00084 }
00085
00087 virtual
00088 ~OctreePointCloudOccupancy ()
00089 {
00090 }
00091
00095 void setOccupiedVoxelAtPoint( const PointT& point_arg ) {
00096 OctreeKey key;
00097
00098
00099 adoptBoundingBoxToPoint (point_arg);
00100
00101
00102 genOctreeKeyforPoint (point_arg, key);
00103
00104
00105 this->addData (key, 0);
00106 }
00107
00111 void setOccupiedVoxelsAtPointsFromCloud( PointCloudPtr cloud_arg ) {
00112 size_t i;
00113
00114 for (i = 0; i < cloud_arg->points.size (); i++)
00115 {
00116
00117 if (isFinite(cloud_arg->points[i])) {
00118
00119 this->setOccupiedVoxelAtPoint (cloud_arg->points[i]);
00120 }
00121 }
00122 }
00123
00124 };
00125 }
00126
00127 }
00128
00129 #define PCL_INSTANTIATE_OctreePointCloudOccupancy(T) template class PCL_EXPORTS pcl::octree::OctreePointCloudOccupancy<T>;
00130
00131 #endif
00132