|
Point Cloud Library (PCL) 1.15.0
|
PCL base class. More...
#include <pcl/pcl_base.h>
Public Types | |
| using | PointCloud = pcl::PointCloud<PointT> |
| using | PointCloudPtr = typename PointCloud::Ptr |
| using | PointCloudConstPtr = typename PointCloud::ConstPtr |
| using | PointIndicesPtr = PointIndices::Ptr |
| using | PointIndicesConstPtr = PointIndices::ConstPtr |
Public Member Functions | |
| PCLBase () | |
| Empty constructor. | |
| PCLBase (const PCLBase &base) | |
| Copy constructor. | |
| virtual | ~PCLBase ()=default |
| Destructor. | |
| virtual void | setInputCloud (const PointCloudConstPtr &cloud) |
| Provide a pointer to the input dataset. | |
| PointCloudConstPtr const | getInputCloud () const |
| Get a pointer to the input point cloud dataset. | |
| 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 (std::size_t row_start, std::size_t col_start, std::size_t nb_rows, std::size_t nb_cols) |
| Set the indices for the points laying within an interest region of the point cloud. | |
| IndicesPtr | getIndices () |
| Get a pointer to the vector of indices used. | |
| IndicesConstPtr const | getIndices () const |
| Get a pointer to the vector of indices used. | |
| const PointT & | operator[] (std::size_t pos) const |
| Override PointCloud operator[] to shorten code. | |
Protected Member Functions | |
| bool | initCompute () |
| This method should get called before starting the actual computation. | |
| bool | deinitCompute () |
| This method should get called after finishing the actual computation. | |
Protected Attributes | |
| PointCloudConstPtr | input_ |
| The input point cloud dataset. | |
| IndicesPtr | indices_ |
| A pointer to the vector of point indices to use. | |
| bool | use_indices_ |
| Set to true if point indices are used. | |
| bool | fake_indices_ |
| If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud. | |
PCL base class.
Implements methods that are used by most PCL algorithms.
Definition at line 69 of file pcl_base.h.
| using pcl::PCLBase< PointT >::PointCloud = pcl::PointCloud<PointT> |
Definition at line 72 of file pcl_base.h.
| using pcl::PCLBase< PointT >::PointCloudConstPtr = typename PointCloud::ConstPtr |
Definition at line 74 of file pcl_base.h.
| using pcl::PCLBase< PointT >::PointCloudPtr = typename PointCloud::Ptr |
Definition at line 73 of file pcl_base.h.
| using pcl::PCLBase< PointT >::PointIndicesConstPtr = PointIndices::ConstPtr |
Definition at line 77 of file pcl_base.h.
| using pcl::PCLBase< PointT >::PointIndicesPtr = PointIndices::Ptr |
Definition at line 76 of file pcl_base.h.
| pcl::PCLBase< PointT >::PCLBase | ( | ) |
Empty constructor.
Definition at line 46 of file pcl_base.hpp.
References fake_indices_, input_, and use_indices_.
Referenced by PCLBase(), and pcl::SurfelSmoothing< PointT, PointNT >::SurfelSmoothing().
| pcl::PCLBase< PointT >::PCLBase | ( | const PCLBase< PointT > & | base | ) |
Copy constructor.
Definition at line 55 of file pcl_base.hpp.
References fake_indices_, indices_, input_, PCLBase(), and use_indices_.
|
virtualdefault |
Destructor.
|
protected |
This method should get called after finishing the actual computation.
Definition at line 175 of file pcl_base.hpp.
Referenced by pcl::MomentOfInertiaEstimation< PointT >::compute(), pcl::registration::ELCH< PointT >::compute(), pcl::ApproximateProgressiveMorphologicalFilter< PointT >::extract(), pcl::MinCutSegmentation< PointT >::extract(), pcl::ProgressiveMorphologicalFilter< PointT >::extract(), pcl::RegionGrowingRGB< PointT, NormalT >::extract(), pcl::SupervoxelClustering< PointT >::extract(), pcl::Filter< PointT >::filter(), pcl::FilterIndices< PointT >::filter(), pcl::RegionGrowing< PointT, pcl::Normal >::findPointNeighbours(), pcl::RegionGrowing< PointT, NormalT >::getSegmentFromPoint(), pcl::RegionGrowingRGB< PointT, NormalT >::getSegmentFromPoint(), pcl::registration::ELCH< PointT >::initCompute(), pcl::RegionGrowing< PointT, pcl::Normal >::prepareForSegmentation(), pcl::ConditionalEuclideanClustering< PointT >::segment(), pcl::ExtractPolygonalPrismData< PointT >::segment(), pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::segment(), pcl::SACSegmentation< PointT >::segment(), and pcl::RegionGrowing< PointT, pcl::Normal >::validatePoint().
|
inline |
Get a pointer to the vector of indices used.
Definition at line 129 of file pcl_base.h.
|
inline |
Get a pointer to the vector of indices used.
Definition at line 133 of file pcl_base.h.
|
inline |
Get a pointer to the input point cloud dataset.
Definition at line 96 of file pcl_base.h.
|
protected |
This method should get called before starting the actual computation.
Internally, initCompute() does the following:
Definition at line 138 of file pcl_base.hpp.
References fake_indices_, indices_, and input_.
Referenced by pcl::MomentOfInertiaEstimation< PointT >::compute(), pcl::ApproximateProgressiveMorphologicalFilter< PointT >::extract(), pcl::MinCutSegmentation< PointT >::extract(), pcl::ProgressiveMorphologicalFilter< PointT >::extract(), pcl::RegionGrowingRGB< PointT, NormalT >::extract(), pcl::SupervoxelClustering< PointT >::extract(), pcl::Filter< PointT >::filter(), pcl::FilterIndices< PointT >::filter(), pcl::PCA< PointT >::getCoefficients(), pcl::RegionGrowing< PointT, pcl::Normal >::getColoredCloudRGBA(), pcl::PCA< PointT >::getEigenValues(), pcl::PCA< PointT >::getEigenVectors(), pcl::PCA< PointT >::getMean(), pcl::RegionGrowing< PointT, NormalT >::getSegmentFromPoint(), pcl::RegionGrowingRGB< PointT, NormalT >::getSegmentFromPoint(), pcl::CorrespondenceGrouping< PointModelT, PointSceneT >::initCompute(), pcl::CovarianceSampling< PointT, PointNT >::initCompute(), pcl::Feature< PointInT, PointOutT >::initCompute(), pcl::filters::Convolution3D< PointIn, PointOut, KernelT >::initCompute(), pcl::GrabCut< PointT >::initCompute(), pcl::Keypoint< ImageType >::initCompute(), pcl::NormalSpaceSampling< PointT, NormalT >::initCompute(), pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::initCompute(), pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::initCompute(), pcl::Registration< PointSource, PointTarget, Scalar >::initCompute(), pcl::SurfelSmoothing< PointT, PointNT >::initCompute(), pcl::tracking::PyramidalKLTTracker< PointInT, IntensityT >::initCompute(), pcl::tracking::Tracker< PointInT, StateT >::initCompute(), pcl::TrajkovicKeypoint2D< PointInT, PointOutT, IntensityT >::initCompute(), pcl::TrajkovicKeypoint3D< PointInT, PointOutT, NormalT >::initCompute(), pcl::ConditionalEuclideanClustering< PointT >::segment(), pcl::ExtractPolygonalPrismData< PointT >::segment(), pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::segment(), and pcl::SACSegmentation< PointT >::segment().
|
inline |
Override PointCloud operator[] to shorten code.
| [in] | pos | position in indices_ vector |
Definition at line 140 of file pcl_base.h.
|
virtual |
Provide a pointer to the vector of indices that represents the input data.
| [in] | indices | a pointer to the indices that represent the input data. |
Reimplemented in pcl::MomentOfInertiaEstimation< PointT >, and pcl::PCA< PointT >.
Definition at line 81 of file pcl_base.hpp.
References fake_indices_, indices_, and use_indices_.
|
virtual |
Provide a pointer to the vector of indices that represents the input data.
| [in] | indices | a pointer to the indices that represent the input data. |
Reimplemented in pcl::MomentOfInertiaEstimation< PointT >, and pcl::PCA< PointT >.
Definition at line 72 of file pcl_base.hpp.
References fake_indices_, indices_, and use_indices_.
Referenced by pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::addPointCloud_and_genLOD(), pcl::people::GroundBasedPeopleDetectionApp< PointT >::compute(), pcl::outofcore::OutofcoreOctreeBase< OutofcoreOctreeDiskContainer< pcl::PointXYZ >, pcl::PointXYZRGB >::flushToDiskLazy(), pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::initCompute(), pcl::registration::KFPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::initCompute(), pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >::initCompute(), pcl::SHOTEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >::initCompute(), pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::initCompute(), pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::queryBBIncludes_subsample(), pcl::MomentOfInertiaEstimation< PointT >::setIndices(), pcl::MomentOfInertiaEstimation< PointT >::setIndices(), pcl::MomentOfInertiaEstimation< PointT >::setIndices(), pcl::MomentOfInertiaEstimation< PointT >::setIndices(), pcl::PCA< PointT >::setIndices(), pcl::PCA< PointT >::setIndices(), pcl::PCA< PointT >::setIndices(), pcl::PCA< PointT >::setIndices(), and pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::simplifyCloud().
|
virtual |
Provide a pointer to the vector of indices that represents the input data.
| [in] | indices | a pointer to the indices that represent the input data. |
Reimplemented in pcl::MomentOfInertiaEstimation< PointT >, and pcl::PCA< PointT >.
Definition at line 90 of file pcl_base.hpp.
|
virtual |
Set the indices for the points laying within an interest region of the point cloud.
| [in] | row_start | the offset on rows |
| [in] | col_start | the offset on columns |
| [in] | nb_rows | the number of rows to be considered row_start included |
| [in] | nb_cols | the number of columns to be considered col_start included |
Reimplemented in pcl::MomentOfInertiaEstimation< PointT >, and pcl::PCA< PointT >.
Definition at line 99 of file pcl_base.hpp.
References input_.
|
virtual |
Provide a pointer to the input dataset.
| [in] | cloud | the const boost shared pointer to a PointCloud message |
Reimplemented in pcl::GrabCut< PointT >, pcl::MinCutSegmentation< PointT >, pcl::MomentOfInertiaEstimation< PointT >, pcl::NormalEstimation< PointInT, PointOutT >, pcl::NormalEstimation< PointInT, PointNT >, pcl::NormalEstimation< SceneT, pcl::Normal >, and pcl::PCA< PointT >.
Definition at line 65 of file pcl_base.hpp.
References input_.
Referenced by pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::addPointCloud_and_genLOD(), pcl::LocalMaximum< PointT >::applyFilterIndices(), pcl::Morphology< PointT >::closingBinary(), pcl::Morphology< PointT >::closingGray(), pcl::people::GroundBasedPeopleDetectionApp< PointT >::compute(), pcl::GRSDEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::UnaryClassifier< PointT >::computeFPFH(), pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::computeRf(), pcl::CrfSegmentation< PointT >::createVoxelGrid(), pcl::HarrisKeypoint6D< PointInT, PointOutT, NormalT >::detectKeypoints(), pcl::SIFTKeypoint< PointInT, PointOutT >::detectKeypoints(), pcl::people::GroundBasedPeopleDetectionApp< PointT >::filter(), pcl::ExtractIndices< PointT >::filterDirectly(), pcl::outofcore::OutofcoreOctreeBase< OutofcoreOctreeDiskContainer< pcl::PointXYZ >, pcl::PointXYZRGB >::flushToDiskLazy(), pcl::ISSKeypoint3D< PointInT, PointOutT, NormalT >::getBoundaryPoints(), pcl::kinfuLS::WorldModel< PointT >::getExistingData(), pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::initCompute(), pcl::registration::KFPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >::initCompute(), pcl::SHOTColorEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >::initCompute(), pcl::SHOTEstimationOMP< PointInT, PointNT, PointOutT, PointRFT >::initCompute(), pcl::UniqueShapeContext< PointInT, PointOutT, PointRFT >::initCompute(), pcl::Morphology< PointT >::openingBinary(), pcl::Morphology< PointT >::openingGray(), pcl::outofcore::OutofcoreOctreeBaseNode< ContainerT, PointT >::queryBBIncludes_subsample(), pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::segment(), pcl::Hough3DGrouping< PointModelT, PointSceneT, PointModelRfT, PointSceneRfT >::setInputCloud(), pcl::MomentOfInertiaEstimation< PointT >::setInputCloud(), pcl::PCA< PointT >::setInputCloud(), pcl::registration::CorrespondenceEstimationBase< PointSource, PointTarget, Scalar >::setInputSource(), pcl::Registration< PointSource, PointTarget, Scalar >::setInputSource(), pcl::HypothesisVerification< ModelT, SceneT >::setSceneCloud(), pcl::kinfuLS::WorldModel< PointT >::setSliceAsNans(), and pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::simplifyCloud().
|
protected |
If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud.
Definition at line 156 of file pcl_base.h.
Referenced by initCompute(), PCLBase(), PCLBase(), setIndices(), and setIndices().
|
protected |
A pointer to the vector of point indices to use.
Definition at line 150 of file pcl_base.h.
Referenced by pcl::BilateralFilter< PointT >::applyFilter(), pcl::ConditionalRemoval< PointT >::applyFilter(), pcl::CovarianceSampling< PointT, PointNT >::applyFilter(), pcl::CropBox< PointT >::applyFilter(), pcl::CropHull< PointT >::applyFilter(), pcl::FarthestPointSampling< PointT >::applyFilter(), pcl::FrustumCulling< PointT >::applyFilter(), pcl::NormalSpaceSampling< PointT, NormalT >::applyFilter(), pcl::ProjectInliers< PointT >::applyFilter(), pcl::RandomSample< PointT >::applyFilter(), pcl::ShadowPoints< PointT, NormalT >::applyFilter(), pcl::UniformSampling< PointT >::applyFilter(), pcl::VoxelGrid< PointT >::applyFilter(), pcl::ExtractIndices< PointT >::applyFilterIndices(), pcl::GridMinimum< PointT >::applyFilterIndices(), pcl::LocalMaximum< PointT >::applyFilterIndices(), pcl::ModelOutlierRemoval< PointT >::applyFilterIndices(), pcl::PassThrough< PointT >::applyFilterIndices(), pcl::RadiusOutlierRemoval< PointT >::applyFilterIndices(), pcl::StatisticalOutlierRemoval< PointT >::applyFilterIndices(), pcl::RegionGrowingRGB< PointT, NormalT >::applyRegionMergingAlgorithm(), pcl::RegionGrowing< PointT, NormalT >::applySmoothRegionGrowingAlgorithm(), pcl::MinCutSegmentation< PointT >::assembleLabels(), pcl::RegionGrowingRGB< PointT, NormalT >::assembleRegions(), pcl::MinCutSegmentation< PointT >::buildGraph(), pcl::MomentOfInertiaEstimation< PointT >::compute(), pcl::GrabCut< PointT >::computeBetaNonOrganized(), pcl::CovarianceSampling< PointT, PointNT >::computeCovarianceMatrix(), pcl::NormalBasedSignatureEstimation< PointT, PointNT, PointFeature >::computeFeature(), pcl::GrabCut< PointT >::computeNLinksNonOrganized(), pcl::ApproximateProgressiveMorphologicalFilter< PointT >::extract(), pcl::GrabCut< PointT >::extract(), pcl::ProgressiveMorphologicalFilter< PointT >::extract(), pcl::RegionGrowing< PointT, NormalT >::findPointNeighbours(), pcl::RegionGrowingRGB< PointT, NormalT >::findPointNeighbours(), pcl::GrabCut< PointT >::fitGMMs(), pcl::RegionGrowing< PointT, NormalT >::getSegmentFromPoint(), pcl::RegionGrowingRGB< PointT, NormalT >::getSegmentFromPoint(), pcl::CovarianceSampling< PointT, PointNT >::initCompute(), pcl::GrabCut< PointT >::initCompute(), initCompute(), pcl::GrabCut< PointT >::initGraph(), pcl::SACSegmentation< PointT >::initSACModel(), pcl::SACSegmentationFromNormals< PointT, PointNT >::initSACModel(), PCLBase(), pcl::RegionGrowing< PointT, NormalT >::prepareForSegmentation(), pcl::RegionGrowingRGB< PointT, NormalT >::prepareForSegmentation(), pcl::GrabCut< PointT >::refine(), pcl::GrabCut< PointT >::refineOnce(), pcl::ConditionalEuclideanClustering< PointT >::segment(), pcl::ExtractPolygonalPrismData< PointT >::segment(), setIndices(), setIndices(), and pcl::GrabCut< PointT >::updateHardSegmentation().
|
protected |
The input point cloud dataset.
Definition at line 147 of file pcl_base.h.
Referenced by pcl::ApproximateVoxelGrid< PointT >::applyFilter(), pcl::BilateralFilter< PointT >::applyFilter(), pcl::ConditionalRemoval< PointT >::applyFilter(), pcl::CovarianceSampling< PointT, PointNT >::applyFilter(), pcl::CropBox< PointT >::applyFilter(), pcl::ExtractIndices< PointT >::applyFilter(), pcl::FarthestPointSampling< PointT >::applyFilter(), pcl::FastBilateralFilter< PointT >::applyFilter(), pcl::FastBilateralFilterOMP< PointT >::applyFilter(), pcl::FilterIndices< PointT >::applyFilter(), pcl::FrustumCulling< PointT >::applyFilter(), pcl::GridMinimum< PointT >::applyFilter(), pcl::LocalMaximum< PointT >::applyFilter(), pcl::MedianFilter< PointT >::applyFilter(), pcl::SamplingSurfaceNormal< PointT >::applyFilter(), pcl::ShadowPoints< PointT, NormalT >::applyFilter(), pcl::ShadowPoints< PointT, NormalT >::applyFilter(), pcl::UniformSampling< PointT >::applyFilter(), pcl::VoxelGrid< PointT >::applyFilter(), pcl::VoxelGridCovariance< PointT >::applyFilter(), pcl::ExtractIndices< PointT >::applyFilterIndices(), pcl::GridMinimum< PointT >::applyFilterIndices(), pcl::LocalMaximum< PointT >::applyFilterIndices(), pcl::ModelOutlierRemoval< PointT >::applyFilterIndices(), pcl::PassThrough< PointT >::applyFilterIndices(), pcl::RadiusOutlierRemoval< PointT >::applyFilterIndices(), pcl::StatisticalOutlierRemoval< PointT >::applyFilterIndices(), pcl::RegionGrowing< PointT, NormalT >::applySmoothRegionGrowingAlgorithm(), pcl::MinCutSegmentation< PointT >::assembleLabels(), pcl::RegionGrowing< PointT, NormalT >::assembleRegions(), pcl::OrganizedEdgeBase< PointT, PointLT >::assignLabelIndices(), pcl::MinCutSegmentation< PointT >::buildGraph(), pcl::MinCutSegmentation< PointT >::calculateBinaryPotential(), pcl::OrganizedEdgeBase< PointT, PointLT >::compute(), pcl::OrganizedEdgeFromNormals< PointT, PointNT, PointLT >::compute(), pcl::OrganizedEdgeFromRGB< PointT, PointLT >::compute(), pcl::OrganizedEdgeFromRGBNormals< PointT, PointNT, PointLT >::compute(), pcl::GrabCut< PointT >::computeBetaNonOrganized(), pcl::GrabCut< PointT >::computeBetaOrganized(), pcl::NormalBasedSignatureEstimation< PointT, PointNT, PointFeature >::computeFeature(), pcl::GrabCut< PointT >::computeNLinksOrganized(), pcl::BilateralFilter< PointT >::computePointWeight(), pcl::SurfelSmoothing< PointT, PointNT >::computeSmoothedCloud(), pcl::Morphology< PointT >::dilationBinary(), pcl::Morphology< PointT >::dilationGray(), pcl::Morphology< PointT >::erosionBinary(), pcl::Morphology< PointT >::erosionGray(), pcl::ApproximateProgressiveMorphologicalFilter< PointT >::extract(), pcl::ProgressiveMorphologicalFilter< PointT >::extract(), pcl::OrganizedEdgeBase< PointT, PointLT >::extractEdges(), pcl::OrganizedEdgeFromRGB< PointT, PointLT >::extractEdges(), pcl::Convolution< PointT >::filter(), pcl::Filter< PointT >::filter(), pcl::ExtractIndices< PointT >::filterDirectly(), pcl::RegionGrowing< PointT, NormalT >::findPointNeighbours(), pcl::RegionGrowingRGB< PointT, NormalT >::findPointNeighbours(), pcl::StatisticalMultiscaleInterestRegionExtraction< PointT >::generateCloudGraph(), pcl::MinCutSegmentation< PointT >::getColoredCloud(), pcl::RegionGrowing< PointT, NormalT >::getColoredCloud(), pcl::RegionGrowing< PointT, NormalT >::getColoredCloudRGBA(), pcl::Registration< PointT, PointT >::getInputSource(), pcl::SupervoxelClustering< PointT >::getLabeledCloud(), pcl::CovarianceSampling< PointT, PointNT >::initCompute(), pcl::GrabCut< PointT >::initCompute(), pcl::NormalSpaceSampling< PointT, NormalT >::initCompute(), initCompute(), pcl::SurfelSmoothing< PointT, PointNT >::initCompute(), pcl::SACSegmentation< PointT >::initSACModel(), pcl::SACSegmentationFromNormals< PointT, PointNT >::initSACModel(), PCLBase(), PCLBase(), pcl::RegionGrowing< PointT, NormalT >::prepareForSegmentation(), pcl::RegionGrowingRGB< PointT, NormalT >::prepareForSegmentation(), pcl::MinCutSegmentation< PointT >::recalculateBinaryPotentials(), pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::refine(), pcl::Registration< PointT, PointT >::registerVisualizationCallback(), pcl::Feature< PointWithRange, Narf36 >::searchForNeighbors(), pcl::ConditionalEuclideanClustering< PointT >::segment(), pcl::ExtractPolygonalPrismData< PointT >::segment(), pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::segment(), pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::segment(), pcl::SACSegmentation< PointT >::segment(), pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::segmentAndRefine(), setIndices(), pcl::GrabCut< PointT >::setInputCloud(), pcl::MinCutSegmentation< PointT >::setInputCloud(), setInputCloud(), pcl::SupervoxelClustering< PointT >::setInputCloud(), and pcl::SurfelSmoothing< PointT, PointNT >::smoothCloudIteration().
|
protected |
Set to true if point indices are used.
Definition at line 153 of file pcl_base.h.
Referenced by pcl::ExtractIndices< PointT >::ExtractIndices(), PCLBase(), PCLBase(), setIndices(), and setIndices().