Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
pcl::PCLBase< PointT > Class Template Reference

PCL base class. Implements methods that are used by most PCL algorithms. More...

#include <pcl_base.h>

Inheritance diagram for pcl::PCLBase< PointT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef pcl::PointCloud< PointTPointCloud
typedef PointCloud::ConstPtr PointCloudConstPtr
typedef PointCloud::Ptr PointCloudPtr
typedef boost::shared_ptr
< PointIndices const > 
PointIndicesConstPtr
typedef boost::shared_ptr
< PointIndices
PointIndicesPtr

Public Member Functions

IndicesPtr const getIndices ()
 Get a pointer to the vector of indices used.
PointCloudConstPtr const getInputCloud ()
 Get a pointer to the input point cloud dataset.
const PointToperator[] (size_t pos)
 Override PointCloud operator[] to shorten code.
 PCLBase ()
 Empty constructor.
 PCLBase (const PCLBase &base)
 Copy constructor.
virtual void setIndices (const IndicesPtr &indices)
 Provide a pointer to the vector of indices that represents the input data.
virtual void setIndices (const IndicesConstPtr &indices)
 Provide a pointer to the vector of indices that represents the input data.
virtual void setIndices (const PointIndicesConstPtr &indices)
 Provide a pointer to the vector of indices that represents the input data.
virtual void setIndices (size_t row_start, size_t col_start, size_t nb_rows, size_t nb_cols)
 Set the indices for the points laying within an interest region of the point cloud.
virtual void setInputCloud (const PointCloudConstPtr &cloud)
 Provide a pointer to the input dataset.
virtual ~PCLBase ()
 Destructor.

Protected Member Functions

bool deinitCompute ()
 This method should get called after finishing the actual computation.
bool initCompute ()
 This method should get called before starting the actual computation.

Protected Attributes

bool fake_indices_
 If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud.
IndicesPtr indices_
 A pointer to the vector of point indices to use.
PointCloudConstPtr input_
 The input point cloud dataset.
bool use_indices_
 Set to true if point indices are used.

Detailed Description

template<typename PointT>
class pcl::PCLBase< PointT >

PCL base class. Implements methods that are used by most PCL algorithms.

Definition at line 68 of file pcl_base.h.


Member Typedef Documentation

template<typename PointT>
typedef pcl::PointCloud<PointT> pcl::PCLBase< PointT >::PointCloud

Reimplemented in pcl::ConditionalRemoval< PointT >, pcl::SACSegmentationFromNormals< PointT, PointNT >, pcl::SACSegmentationFromNormals< PointType, pcl::Normal >, pcl::EuclideanClusterExtraction< PointT >, pcl::EuclideanClusterExtraction< PointType >, pcl::NormalRefinement< NormalT >, pcl::VoxelGrid< PointT >, pcl::VoxelGrid< PointTarget >, pcl::VoxelGrid< pcl::PointXYZRGBL >, pcl::VoxelGrid< PointType >, pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >, pcl::ExtractPolygonalPrismData< PointT >, pcl::ExtractPolygonalPrismData< PointType >, pcl::ApproximateVoxelGrid< PointT >, pcl::ApproximateVoxelGrid< pcl::PointXYZRGBNormal >, pcl::SeededHueSegmentation, pcl::Filter< PointT >, pcl::Filter< pcl::PointXYZRGBNormal >, pcl::Filter< PointInT >, pcl::Filter< PointTarget >, pcl::Filter< pcl::PointXYZRGBA >, pcl::Filter< NormalT >, pcl::Filter< pcl::PointXYZRGBL >, pcl::Filter< PointXYZRGBA >, pcl::Filter< PointType >, pcl::StatisticalOutlierRemoval< PointT >, pcl::PassThrough< PointT >, pcl::PassThrough< PointInT >, pcl::PassThrough< pcl::PointXYZRGBA >, pcl::PassThrough< PointXYZRGBA >, pcl::PassThrough< PointType >, pcl::VoxelGridCovariance< PointT >, pcl::VoxelGridCovariance< PointTarget >, pcl::FrustumCulling< PointT >, pcl::SegmentDifferences< PointT >, pcl::ProjectInliers< PointT >, pcl::LabeledEuclideanClusterExtraction< PointT >, pcl::ProjectInliers< PointType >, pcl::RadiusOutlierRemoval< PointT >, pcl::SACSegmentation< PointT >, pcl::SACSegmentation< PointType >, pcl::ExtractIndices< PointT >, pcl::ExtractIndices< PointType >, pcl::FilterIndices< PointT >, pcl::FilterIndices< PointInT >, pcl::FilterIndices< pcl::PointXYZRGBA >, pcl::FilterIndices< PointXYZRGBA >, pcl::FilterIndices< PointType >, pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >, pcl::OrganizedMultiPlaneSegmentation< PointT, pcl::Normal, pcl::Label >, pcl::OrganizedMultiPlaneSegmentation< PointT, Normal, Label >, pcl::RegionGrowing< PointT, NormalT >, pcl::FastBilateralFilterOMP< PointT >, pcl::RandomSample< PointT >, pcl::registration::ELCH< PointT >, pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >, pcl::MedianFilter< PointT >, pcl::ShadowPoints< PointT, NormalT >, pcl::VoxelGridOcclusionEstimation< PointT >, pcl::PCA< PointT >, pcl::NormalSpaceSampling< PointT, NormalT >, pcl::FastBilateralFilter< PointT >, pcl::SamplingSurfaceNormal< PointT >, pcl::BilateralFilter< PointT >, pcl::CropBox< PointT >, pcl::CropHull< PointT >, and pcl::GeometricConsistencyGrouping< PointModelT, PointSceneT >.

Definition at line 71 of file pcl_base.h.

template<typename PointT>
typedef PointCloud::ConstPtr pcl::PCLBase< PointT >::PointCloudConstPtr

Reimplemented in pcl::ConditionalRemoval< PointT >, pcl::GrabCut< PointT >, pcl::SACSegmentationFromNormals< PointT, PointNT >, pcl::SACSegmentationFromNormals< PointType, pcl::Normal >, pcl::EuclideanClusterExtraction< PointT >, pcl::EuclideanClusterExtraction< PointType >, pcl::NormalEstimation< PointInT, PointOutT >, pcl::NormalEstimation< PointType, pcl::Normal >, pcl::NormalRefinement< NormalT >, pcl::VoxelGrid< PointT >, pcl::VoxelGrid< PointTarget >, pcl::VoxelGrid< pcl::PointXYZRGBL >, pcl::VoxelGrid< PointType >, pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >, pcl::ExtractPolygonalPrismData< PointT >, pcl::ExtractPolygonalPrismData< PointType >, pcl::ApproximateVoxelGrid< PointT >, pcl::ApproximateVoxelGrid< pcl::PointXYZRGBNormal >, pcl::SeededHueSegmentation, pcl::Filter< PointT >, pcl::Filter< pcl::PointXYZRGBNormal >, pcl::Filter< PointInT >, pcl::Filter< PointTarget >, pcl::Filter< pcl::PointXYZRGBA >, pcl::Filter< NormalT >, pcl::Filter< pcl::PointXYZRGBL >, pcl::Filter< PointXYZRGBA >, pcl::Filter< PointType >, pcl::StatisticalOutlierRemoval< PointT >, pcl::PassThrough< PointT >, pcl::PassThrough< PointInT >, pcl::PassThrough< pcl::PointXYZRGBA >, pcl::PassThrough< PointXYZRGBA >, pcl::PassThrough< PointType >, pcl::VoxelGridCovariance< PointT >, pcl::VoxelGridCovariance< PointTarget >, pcl::FrustumCulling< PointT >, pcl::SegmentDifferences< PointT >, pcl::ProjectInliers< PointT >, pcl::LabeledEuclideanClusterExtraction< PointT >, pcl::ProjectInliers< PointType >, pcl::RadiusOutlierRemoval< PointT >, pcl::SACSegmentation< PointT >, pcl::SACSegmentation< PointType >, pcl::ExtractIndices< PointT >, pcl::ExtractIndices< PointType >, pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >, pcl::OrganizedMultiPlaneSegmentation< PointT, pcl::Normal, pcl::Label >, pcl::OrganizedMultiPlaneSegmentation< PointT, Normal, Label >, pcl::RandomSample< PointT >, pcl::registration::ELCH< PointT >, pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >, pcl::ShadowPoints< PointT, NormalT >, pcl::VoxelGridOcclusionEstimation< PointT >, pcl::PCA< PointT >, pcl::NormalSpaceSampling< PointT, NormalT >, pcl::SamplingSurfaceNormal< PointT >, pcl::CropBox< PointT >, pcl::CropHull< PointT >, and pcl::GeometricConsistencyGrouping< PointModelT, PointSceneT >.

Definition at line 73 of file pcl_base.h.

template<typename PointT>
typedef PointCloud::Ptr pcl::PCLBase< PointT >::PointCloudPtr

Reimplemented in pcl::ConditionalRemoval< PointT >, pcl::MarchingCubes< PointNT >, pcl::GrabCut< PointT >, pcl::SACSegmentationFromNormals< PointT, PointNT >, pcl::SACSegmentationFromNormals< PointType, pcl::Normal >, pcl::EuclideanClusterExtraction< PointT >, pcl::EuclideanClusterExtraction< PointType >, pcl::NormalRefinement< NormalT >, pcl::VoxelGrid< PointT >, pcl::VoxelGrid< PointTarget >, pcl::VoxelGrid< pcl::PointXYZRGBL >, pcl::VoxelGrid< PointType >, pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >, pcl::ExtractPolygonalPrismData< PointT >, pcl::ExtractPolygonalPrismData< PointType >, pcl::ApproximateVoxelGrid< PointT >, pcl::ApproximateVoxelGrid< pcl::PointXYZRGBNormal >, pcl::SeededHueSegmentation, pcl::Filter< PointT >, pcl::Filter< pcl::PointXYZRGBNormal >, pcl::Filter< PointInT >, pcl::Filter< PointTarget >, pcl::Filter< pcl::PointXYZRGBA >, pcl::Filter< NormalT >, pcl::Filter< pcl::PointXYZRGBL >, pcl::Filter< PointXYZRGBA >, pcl::Filter< PointType >, pcl::StatisticalOutlierRemoval< PointT >, pcl::PassThrough< PointT >, pcl::PassThrough< PointInT >, pcl::PassThrough< pcl::PointXYZRGBA >, pcl::PassThrough< PointXYZRGBA >, pcl::PassThrough< PointType >, pcl::VoxelGridCovariance< PointT >, pcl::VoxelGridCovariance< PointTarget >, pcl::FrustumCulling< PointT >, pcl::GridProjection< PointNT >, pcl::SegmentDifferences< PointT >, pcl::ProjectInliers< PointT >, pcl::LabeledEuclideanClusterExtraction< PointT >, pcl::ProjectInliers< PointType >, pcl::RadiusOutlierRemoval< PointT >, pcl::SACSegmentation< PointT >, pcl::SACSegmentation< PointType >, pcl::ExtractIndices< PointT >, pcl::OrganizedFastMesh< PointInT >, pcl::ExtractIndices< PointType >, pcl::OrganizedFastMesh< PointType >, pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >, pcl::OrganizedMultiPlaneSegmentation< PointT, pcl::Normal, pcl::Label >, pcl::OrganizedMultiPlaneSegmentation< PointT, Normal, Label >, pcl::RandomSample< PointT >, pcl::registration::ELCH< PointT >, pcl::MarchingCubesRBF< PointNT >, pcl::Poisson< PointNT >, pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >, pcl::MarchingCubesHoppe< PointNT >, pcl::ShadowPoints< PointT, NormalT >, pcl::VoxelGridOcclusionEstimation< PointT >, pcl::PCA< PointT >, pcl::NormalSpaceSampling< PointT, NormalT >, pcl::SamplingSurfaceNormal< PointT >, pcl::CropBox< PointT >, pcl::CropHull< PointT >, and pcl::GeometricConsistencyGrouping< PointModelT, PointSceneT >.

Definition at line 72 of file pcl_base.h.

template<typename PointT>
typedef boost::shared_ptr<PointIndices const> pcl::PCLBase< PointT >::PointIndicesConstPtr
template<typename PointT>
typedef boost::shared_ptr<PointIndices> pcl::PCLBase< PointT >::PointIndicesPtr

Constructor & Destructor Documentation

template<typename PointT >
pcl::PCLBase< PointT >::PCLBase ( )

Empty constructor.

Definition at line 46 of file pcl_base.hpp.

template<typename PointT >
pcl::PCLBase< PointT >::PCLBase ( const PCLBase< PointT > &  base)

Copy constructor.

Definition at line 56 of file pcl_base.hpp.

template<typename PointT>
virtual pcl::PCLBase< PointT >::~PCLBase ( ) [inline, virtual]

Destructor.

Definition at line 85 of file pcl_base.h.


Member Function Documentation

template<typename PointT >
bool pcl::PCLBase< PointT >::deinitCompute ( ) [protected]
template<typename PointT>
IndicesPtr const pcl::PCLBase< PointT >::getIndices ( ) [inline]

Get a pointer to the vector of indices used.

Definition at line 132 of file pcl_base.h.

template<typename PointT>
PointCloudConstPtr const pcl::PCLBase< PointT >::getInputCloud ( ) [inline]

Get a pointer to the input point cloud dataset.

Definition at line 99 of file pcl_base.h.

template<typename PointT >
bool pcl::PCLBase< PointT >::initCompute ( ) [protected]

This method should get called before starting the actual computation.

Internally, initCompute() does the following:

  • checks if an input dataset is given, and returns false otherwise
  • checks whether a set of input indices has been given. Returns true if yes.
  • if no input indices have been given, a fake set is created, which will be used until:
    • either a new set is given via setIndices(), or
    • a new cloud is given that has a different set of points. This will trigger an update on the set of fake indices

Reimplemented in pcl::AgastKeypoint2DBase< PointInT, PointOutT, IntensityT >, pcl::AgastKeypoint2DBase< PointInT, PointOutT, pcl::common::IntensityFieldAccessor< PointInT > >, pcl::AgastKeypoint2DBase< pcl::PointXYZ, pcl::PointUV, pcl::common::IntensityFieldAccessor< pcl::PointXYZ > >, pcl::FeatureFromLabels< PointInT, PointLT, PointOutT >, pcl::IntegralImageNormalEstimation< PointInT, PointOutT >, pcl::IntegralImageNormalEstimation< pcl::PointXYZRGB, pcl::PointXYZRGBNormal >, pcl::IntegralImageNormalEstimation< PointType, pcl::Normal >, pcl::IntegralImageNormalEstimation< PointT, Normal >, pcl::IntegralImageNormalEstimation< PointT, pcl::Normal >, pcl::Registration< PointSource, PointTarget, Scalar >, pcl::Registration< pcl::PointXYZ, pcl::PointXYZ >, pcl::Registration< PointSource, PointTarget, float >, pcl::Registration< PointT, PointT >, pcl::Registration< PointSource, PointTarget >, pcl::GrabCut< PointT >, pcl::FeatureFromNormals< PointInT, PointNT, PointOutT >, pcl::FeatureFromNormals< PointType, pcl::Normal, pcl::FPFHSignature33 >, pcl::FeatureFromNormals< PointT, PointNT, PointFeature >, pcl::FeatureFromNormals< pcl::PointXYZRGBNormal, pcl::PointXYZRGBNormal, pcl::Boundary >, pcl::tracking::ParticleFilterTracker< PointInT, StateT >, pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >, pcl::filters::Convolution3D< PointIn, PointOut, KernelT >, pcl::SpinImageEstimation< PointInT, PointNT, PointOutT >, pcl::Feature< PointInT, PointOutT >, pcl::Feature< PointT, PointFeature >, pcl::Feature< pcl::PointXYZRGB, pcl::PointXYZRGBNormal >, pcl::Feature< pcl::PointXYZRGB, FeatureType >, pcl::Feature< PointType, pcl::Normal >, pcl::Feature< PointSource, PointFeature >, pcl::Feature< PointT, Normal >, pcl::Feature< PointWithRange, BorderDescription >, pcl::Feature< PointT, pcl::Normal >, pcl::Feature< PointType, pcl::FPFHSignature33 >, pcl::Feature< PointWithRange, Narf36 >, pcl::Feature< pcl::PointXYZRGBNormal, pcl::Boundary >, pcl::PCA< PointT >, pcl::VFHEstimation< PointInT, PointNT, PointOutT >, pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >, pcl::registration::ELCH< PointT >, pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >, pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >, pcl::registration::CorrespondenceEstimationOrganizedProjection< PointSource, PointTarget, Scalar >, pcl::NormalSpaceSampling< PointT, NormalT >, pcl::registration::CorrespondenceEstimationNormalShooting< PointSource, PointTarget, NormalT, Scalar >, pcl::registration::CorrespondenceEstimationBackProjection< PointSource, PointTarget, NormalT, Scalar >, pcl::ShapeContext3DEstimation< PointInT, PointNT, PointOutT >, pcl::Keypoint< PointInT, PointOutT >, pcl::Keypoint< PointWithRange, int >, pcl::Keypoint< PointInT, int >, pcl::Keypoint< pcl::PointXYZRGBA, int >, pcl::Keypoint< pcl::PointXYZ, pcl::PointUV >, pcl::Keypoint< PointT, PointT >, pcl::SUSANKeypoint< PointInT, PointOutT, NormalT, IntensityT >, pcl::CorrespondenceGrouping< PointModelT, PointSceneT >, pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >, pcl::HarrisKeypoint3D< PointInT, PointOutT, NormalT >, pcl::MultiscaleFeaturePersistence< PointSource, PointFeature >, pcl::MultiscaleFeaturePersistence< PointType, pcl::FPFHSignature33 >, pcl::CovarianceSampling< PointT, PointNT >, pcl::SIFTKeypoint< PointInT, PointOutT >, pcl::HarrisKeypoint2D< PointInT, PointOutT, IntensityT >, pcl::SHOTEstimationBase< PointInT, PointNT, PointOutT, PointRFT >, pcl::DifferenceOfNormalsEstimation< PointInT, PointNT, PointOutT >, pcl::SHOTEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >, pcl::SmoothedSurfacesKeypoint< PointT, PointNT >, pcl::StatisticalMultiscaleInterestRegionExtraction< PointT >, pcl::tracking::Tracker< PointInT, StateT >, and pcl::SurfelSmoothing< PointT, PointNT >.

Definition at line 139 of file pcl_base.hpp.

template<typename PointT>
const PointT& pcl::PCLBase< PointT >::operator[] ( size_t  pos) [inline]

Override PointCloud operator[] to shorten code.

Note:
this method can be called instead of (*input_)[(*indices_)[pos]] or input_->points[(*indices_)[pos]]
Parameters:
[in]posposition in indices_ vector

Definition at line 139 of file pcl_base.h.

template<typename PointT >
void pcl::PCLBase< PointT >::setIndices ( const IndicesPtr indices) [virtual]

Provide a pointer to the vector of indices that represents the input data.

Parameters:
[in]indicesa pointer to the indices that represent the input data.

Definition at line 73 of file pcl_base.hpp.

template<typename PointT >
void pcl::PCLBase< PointT >::setIndices ( const IndicesConstPtr indices) [virtual]

Provide a pointer to the vector of indices that represents the input data.

Parameters:
[in]indicesa pointer to the indices that represent the input data.

Definition at line 82 of file pcl_base.hpp.

template<typename PointT >
void pcl::PCLBase< PointT >::setIndices ( const PointIndicesConstPtr indices) [virtual]

Provide a pointer to the vector of indices that represents the input data.

Parameters:
[in]indicesa pointer to the indices that represent the input data.

Definition at line 91 of file pcl_base.hpp.

template<typename PointT >
void pcl::PCLBase< PointT >::setIndices ( size_t  row_start,
size_t  col_start,
size_t  nb_rows,
size_t  nb_cols 
) [virtual]

Set the indices for the points laying within an interest region of the point cloud.

Note:
you shouldn't call this method on unorganized point clouds!
Parameters:
[in]row_startthe offset on rows
[in]col_startthe offset on columns
[in]nb_rowsthe number of rows to be considered row_start included
[in]nb_colsthe number of columns to be considered col_start included

Definition at line 100 of file pcl_base.hpp.

template<typename PointT >
void pcl::PCLBase< PointT >::setInputCloud ( const PointCloudConstPtr cloud) [virtual]

Provide a pointer to the input dataset.

Parameters:
[in]cloudthe const boost shared pointer to a PointCloud message

Reimplemented in pcl::GrabCut< PointT >, pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >, and pcl::PCA< PointT >.

Definition at line 66 of file pcl_base.hpp.


Member Data Documentation

template<typename PointT>
bool pcl::PCLBase< PointT >::fake_indices_ [protected]

If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud.

Definition at line 155 of file pcl_base.h.

template<typename PointT>
IndicesPtr pcl::PCLBase< PointT >::indices_ [protected]

A pointer to the vector of point indices to use.

Definition at line 149 of file pcl_base.h.

template<typename PointT>
PointCloudConstPtr pcl::PCLBase< PointT >::input_ [protected]

The input point cloud dataset.

Definition at line 146 of file pcl_base.h.

template<typename PointT>
bool pcl::PCLBase< PointT >::use_indices_ [protected]

Set to true if point indices are used.

Definition at line 152 of file pcl_base.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:42:48