Public Types | Public Member Functions
pcl::octree::OctreePointCloudOccupancy< PointT, LeafContainerT, BranchContainerT > Class Template Reference

Octree pointcloud occupancy class More...

#include <octree_pointcloud_occupancy.h>

Inheritance diagram for pcl::octree::OctreePointCloudOccupancy< PointT, LeafContainerT, BranchContainerT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef
OctreePointCloudOccupancy
< PointT, LeafContainerT,
BranchContainerT > 
DoubleBuffer
typedef OctreePointCloud
< PointT, LeafContainerT,
BranchContainerT >::PointCloud 
PointCloud
typedef OctreePointCloud
< PointT, LeafContainerT,
BranchContainerT >
::PointCloudConstPtr 
PointCloudConstPtr
typedef OctreePointCloud
< PointT, LeafContainerT,
BranchContainerT >
::PointCloudPtr 
PointCloudPtr
typedef
OctreePointCloudOccupancy
< PointT, LeafContainerT,
BranchContainerT > 
SingleBuffer

Public Member Functions

 OctreePointCloudOccupancy (const double resolution_arg)
 Constructor.
void setOccupiedVoxelAtPoint (const PointT &point_arg)
 Set occupied voxel at point.
void setOccupiedVoxelsAtPointsFromCloud (PointCloudPtr cloud_arg)
 Set occupied voxels at all points from point cloud.
virtual ~OctreePointCloudOccupancy ()
 Empty class constructor.

Detailed Description

template<typename PointT, typename LeafContainerT = OctreeContainerEmpty, typename BranchContainerT = OctreeContainerEmpty>
class pcl::octree::OctreePointCloudOccupancy< PointT, LeafContainerT, BranchContainerT >

Octree pointcloud occupancy class

Note:
This pointcloud octree class generate an octrees from a point cloud (zero-copy). No information is stored at the lead nodes. It can be used of occupancy checks.
The octree pointcloud is initialized with its voxel resolution. Its bounding box is automatically adjusted or can be predefined.
typename: PointT: type of point used in pointcloud
Author:
Julius Kammerl (julius@kammerl.de)

Definition at line 62 of file octree_pointcloud_occupancy.h.


Member Typedef Documentation

template<typename PointT, typename LeafContainerT = OctreeContainerEmpty, typename BranchContainerT = OctreeContainerEmpty>
typedef OctreePointCloudOccupancy<PointT, LeafContainerT, BranchContainerT> pcl::octree::OctreePointCloudOccupancy< PointT, LeafContainerT, BranchContainerT >::DoubleBuffer

Definition at line 70 of file octree_pointcloud_occupancy.h.

template<typename PointT, typename LeafContainerT = OctreeContainerEmpty, typename BranchContainerT = OctreeContainerEmpty>
typedef OctreePointCloud<PointT, LeafContainerT, BranchContainerT>::PointCloud pcl::octree::OctreePointCloudOccupancy< PointT, LeafContainerT, BranchContainerT >::PointCloud
template<typename PointT, typename LeafContainerT = OctreeContainerEmpty, typename BranchContainerT = OctreeContainerEmpty>
typedef OctreePointCloud<PointT, LeafContainerT, BranchContainerT>::PointCloudConstPtr pcl::octree::OctreePointCloudOccupancy< PointT, LeafContainerT, BranchContainerT >::PointCloudConstPtr
template<typename PointT, typename LeafContainerT = OctreeContainerEmpty, typename BranchContainerT = OctreeContainerEmpty>
typedef OctreePointCloud<PointT, LeafContainerT, BranchContainerT>::PointCloudPtr pcl::octree::OctreePointCloudOccupancy< PointT, LeafContainerT, BranchContainerT >::PointCloudPtr
template<typename PointT, typename LeafContainerT = OctreeContainerEmpty, typename BranchContainerT = OctreeContainerEmpty>
typedef OctreePointCloudOccupancy<PointT, LeafContainerT, BranchContainerT> pcl::octree::OctreePointCloudOccupancy< PointT, LeafContainerT, BranchContainerT >::SingleBuffer

Constructor & Destructor Documentation

template<typename PointT, typename LeafContainerT = OctreeContainerEmpty, typename BranchContainerT = OctreeContainerEmpty>
pcl::octree::OctreePointCloudOccupancy< PointT, LeafContainerT, BranchContainerT >::OctreePointCloudOccupancy ( const double  resolution_arg) [inline]

Constructor.

Parameters:
resolution_arg,:octree resolution at lowest octree level

Definition at line 80 of file octree_pointcloud_occupancy.h.

template<typename PointT, typename LeafContainerT = OctreeContainerEmpty, typename BranchContainerT = OctreeContainerEmpty>
virtual pcl::octree::OctreePointCloudOccupancy< PointT, LeafContainerT, BranchContainerT >::~OctreePointCloudOccupancy ( ) [inline, virtual]

Empty class constructor.

Definition at line 88 of file octree_pointcloud_occupancy.h.


Member Function Documentation

template<typename PointT, typename LeafContainerT = OctreeContainerEmpty, typename BranchContainerT = OctreeContainerEmpty>
void pcl::octree::OctreePointCloudOccupancy< PointT, LeafContainerT, BranchContainerT >::setOccupiedVoxelAtPoint ( const PointT point_arg) [inline]

Set occupied voxel at point.

Parameters:
point_arg,:input point

Definition at line 95 of file octree_pointcloud_occupancy.h.

template<typename PointT, typename LeafContainerT = OctreeContainerEmpty, typename BranchContainerT = OctreeContainerEmpty>
void pcl::octree::OctreePointCloudOccupancy< PointT, LeafContainerT, BranchContainerT >::setOccupiedVoxelsAtPointsFromCloud ( PointCloudPtr  cloud_arg) [inline]

Set occupied voxels at all points from point cloud.

Parameters:
cloud_arg,:input point cloud

Definition at line 111 of file octree_pointcloud_occupancy.h.


The documentation for this class was generated from the following file:


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:44:31