|
Point Cloud Library (PCL) 1.15.1
|
Filter represents the base filter class. More...
#include <pcl/filters/filter.h>
Public Types | |
| using | Ptr = shared_ptr<Filter<PointT> > |
| using | ConstPtr = shared_ptr<const Filter<PointT> > |
| using | PointCloud = pcl::PointCloud<PointT> |
| using | PointCloudPtr = typename PointCloud::Ptr |
| using | PointCloudConstPtr = typename PointCloud::ConstPtr |
| Public Types inherited from pcl::PCLBase< PointT > | |
| 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 | |
| Filter (bool extract_removed_indices=false) | |
| Empty constructor. | |
| IndicesConstPtr const | getRemovedIndices () const |
| Get the point indices being removed. | |
| void | getRemovedIndices (PointIndices &pi) |
| Get the point indices being removed. | |
| void | filter (PointCloud &output) |
| Calls the filtering method and returns the filtered dataset in output. | |
| Public Member Functions inherited from pcl::PCLBase< PointT > | |
| 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 | |
| virtual void | applyFilter (PointCloud &output)=0 |
| Abstract filter method. | |
| const std::string & | getClassName () const |
| Get a string representation of the name of this class. | |
| Protected Member Functions inherited from pcl::PCLBase< PointT > | |
| 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 | |
| IndicesPtr | removed_indices_ |
| Indices of the points that are removed. | |
| std::string | filter_name_ |
| The filter name. | |
| bool | extract_removed_indices_ |
| Set to true if we want to return the indices of the removed points. | |
| Protected Attributes inherited from pcl::PCLBase< PointT > | |
| 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. | |
Filter represents the base filter class.
All filters must inherit from this interface.
| using pcl::Filter< PointT >::ConstPtr = shared_ptr<const Filter<PointT> > |
| using pcl::Filter< PointT >::PointCloud = pcl::PointCloud<PointT> |
| using pcl::Filter< PointT >::PointCloudConstPtr = typename PointCloud::ConstPtr |
| using pcl::Filter< PointT >::PointCloudPtr = typename PointCloud::Ptr |
| using pcl::Filter< PointT >::Ptr = shared_ptr<Filter<PointT> > |
|
inline |
Empty constructor.
| [in] | extract_removed_indices | set to true if the filtered data indices should be saved in a separate list. Default: false. |
Definition at line 95 of file filter.h.
References extract_removed_indices_, and removed_indices_.
Referenced by pcl::ApproximateVoxelGrid< PointT >::ApproximateVoxelGrid(), pcl::ApproximateVoxelGrid< PointT >::ApproximateVoxelGrid(), pcl::ConditionalRemoval< PointT >::ConditionalRemoval(), and pcl::FilterIndices< PointT >::FilterIndices().
|
protectedpure virtual |
Abstract filter method.
The implementation needs to set output.{points, width, height, is_dense}.
| [out] | output | the resultant filtered point cloud |
Implemented in pcl::ApproximateVoxelGrid< PointT >, pcl::BilateralFilter< PointT >, pcl::ConditionalRemoval< PointT >, pcl::Convolution< ImageType >, pcl::Convolution< pcl::PointXYZ >, pcl::Convolution< PointInT >, pcl::CovarianceSampling< PointT, PointNT >, pcl::ExtractIndices< PointT >, pcl::FastBilateralFilter< PointT >, pcl::FastBilateralFilterOMP< PointT >, pcl::FilterIndices< PointT >, pcl::GridMinimum< PointT >, pcl::LocalMaximum< PointT >, pcl::MedianFilter< PointT >, pcl::ProjectInliers< PointT >, pcl::SamplingSurfaceNormal< PointT >, pcl::ShadowPoints< PointT, NormalT >, pcl::VoxelGrid< PointT >, pcl::VoxelGridCovariance< PointT >, and pcl::VoxelGridCovariance< PointTarget >.
Referenced by filter().
|
inline |
Calls the filtering method and returns the filtered dataset in output.
| [out] | output | the resultant filtered point cloud dataset |
Definition at line 121 of file filter.h.
References applyFilter(), pcl::copyPointCloud(), pcl::PCLBase< PointT >::deinitCompute(), pcl::PointCloud< PointT >::header, pcl::PCLBase< PointT >::initCompute(), pcl::PCLBase< PointT >::input_, pcl::PointCloud< PointT >::sensor_orientation_, and pcl::PointCloud< PointT >::sensor_origin_.
Referenced by pcl::LocalMaximum< PointT >::applyFilterIndices(), pcl::GRSDEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::CrfSegmentation< PointT >::createVoxelGrid(), pcl::SIFTKeypoint< PointInT, PointOutT >::detectKeypoints(), pcl::people::GroundBasedPeopleDetectionApp< PointT >::filter(), pcl::kinfuLS::WorldModel< PointT >::getExistingData(), pcl::VoxelGridOcclusionEstimation< PointT >::initializeVoxelGrid(), pcl::HypothesisVerification< ModelT, SceneT >::setSceneCloud(), pcl::kinfuLS::WorldModel< PointT >::setSliceAsNans(), and pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::simplifyCloud().
|
inlineprotected |
Get a string representation of the name of this class.
Definition at line 174 of file filter.h.
References filter_name_.
Referenced by pcl::ConditionalRemoval< PointT >::applyFilter(), pcl::ExtractIndices< PointT >::applyFilter(), pcl::GridMinimum< PointT >::applyFilter(), pcl::LocalMaximum< PointT >::applyFilter(), pcl::ProjectInliers< PointT >::applyFilter(), pcl::VoxelGrid< PointT >::applyFilter(), pcl::VoxelGridCovariance< PointT >::applyFilter(), pcl::ExtractIndices< PointT >::applyFilterIndices(), pcl::GridMinimum< PointT >::applyFilterIndices(), pcl::LocalMaximum< PointT >::applyFilterIndices(), pcl::PassThrough< PointT >::applyFilterIndices(), pcl::RadiusOutlierRemoval< PointT >::applyFilterIndices(), pcl::StatisticalOutlierRemoval< PointT >::applyFilterIndices(), pcl::VoxelGridCovariance< PointTarget >::filter(), pcl::VoxelGridCovariance< PointTarget >::filter(), pcl::ExtractIndices< PointT >::filterDirectly(), pcl::VoxelGridCovariance< PointTarget >::nearestKSearch(), pcl::VoxelGridCovariance< PointTarget >::radiusSearch(), and pcl::VoxelGridCovariance< PointTarget >::setMinPointPerVoxel().
|
inline |
Get the point indices being removed.
Definition at line 103 of file filter.h.
References removed_indices_.
Referenced by pcl::kinfuLS::WorldModel< PointT >::setSliceAsNans().
|
inline |
Get the point indices being removed.
| [out] | pi | the resultant point indices that have been removed |
Definition at line 112 of file filter.h.
References pcl::PointIndices::indices, and removed_indices_.
|
protected |
Set to true if we want to return the indices of the removed points.
Definition at line 161 of file filter.h.
Referenced by pcl::ConditionalRemoval< PointT >::applyFilter(), pcl::CropBox< PointT >::applyFilter(), pcl::experimental::advanced::FunctorFilter< PointT, FilterFunction< PointT > >::applyFilter(), pcl::ExtractIndices< PointT >::applyFilter(), pcl::FarthestPointSampling< PointT >::applyFilter(), pcl::FilterIndices< PointT >::applyFilter(), pcl::FrustumCulling< PointT >::applyFilter(), pcl::NormalSpaceSampling< PointT, NormalT >::applyFilter(), pcl::RandomSample< PointT >::applyFilter(), pcl::ShadowPoints< PointT, NormalT >::applyFilter(), pcl::ShadowPoints< PointT, NormalT >::applyFilter(), pcl::UniformSampling< PointT >::applyFilter(), pcl::ExtractIndices< PointT >::applyFilterIndices(), pcl::LocalMaximum< PointT >::applyFilterIndices(), pcl::ModelOutlierRemoval< PointT >::applyFilterIndices(), pcl::PassThrough< PointT >::applyFilterIndices(), pcl::RadiusOutlierRemoval< PointT >::applyFilterIndices(), pcl::StatisticalOutlierRemoval< PointT >::applyFilterIndices(), Filter(), and pcl::ExtractIndices< PointT >::filterDirectly().
|
protected |
The filter name.
Definition at line 158 of file filter.h.
Referenced by pcl::ApproximateVoxelGrid< PointT >::ApproximateVoxelGrid(), pcl::ConditionalRemoval< PointT >::ConditionalRemoval(), pcl::CovarianceSampling< PointT, PointNT >::CovarianceSampling(), pcl::CropBox< PointT >::CropBox(), pcl::CropHull< PointT >::CropHull(), pcl::ExtractIndices< PointT >::ExtractIndices(), pcl::FarthestPointSampling< PointT >::FarthestPointSampling(), pcl::FrustumCulling< PointT >::FrustumCulling(), pcl::experimental::advanced::FunctorFilter< PointT, FilterFunction< PointT > >::FunctorFilter(), pcl::experimental::advanced::FunctorFilter< PointT, FilterFunction< PointT > >::FunctorFilter(), getClassName(), pcl::GridMinimum< PointT >::GridMinimum(), pcl::LocalMaximum< PointT >::LocalMaximum(), pcl::ModelOutlierRemoval< PointT >::ModelOutlierRemoval(), pcl::NormalSpaceSampling< PointT, NormalT >::NormalSpaceSampling(), pcl::PassThrough< PointT >::PassThrough(), pcl::ProjectInliers< PointT >::ProjectInliers(), pcl::RadiusOutlierRemoval< PointT >::RadiusOutlierRemoval(), pcl::RandomSample< PointT >::RandomSample(), pcl::SamplingSurfaceNormal< PointT >::SamplingSurfaceNormal(), pcl::ShadowPoints< PointT, NormalT >::ShadowPoints(), pcl::StatisticalOutlierRemoval< PointT >::StatisticalOutlierRemoval(), pcl::UniformSampling< PointT >::UniformSampling(), pcl::VoxelGrid< PointT >::VoxelGrid(), and pcl::VoxelGridCovariance< PointTarget >::VoxelGridCovariance().
|
protected |
Indices of the points that are removed.
Definition at line 155 of file filter.h.
Referenced by pcl::ConditionalRemoval< PointT >::applyFilter(), pcl::CropBox< PointT >::applyFilter(), pcl::CropHull< PointT >::applyFilter(), pcl::experimental::advanced::FunctorFilter< PointT, FilterFunction< PointT > >::applyFilter(), pcl::ExtractIndices< PointT >::applyFilter(), pcl::FarthestPointSampling< PointT >::applyFilter(), pcl::FilterIndices< PointT >::applyFilter(), pcl::FrustumCulling< PointT >::applyFilter(), pcl::NormalSpaceSampling< PointT, NormalT >::applyFilter(), pcl::RandomSample< PointT >::applyFilter(), pcl::ShadowPoints< PointT, NormalT >::applyFilter(), pcl::ShadowPoints< PointT, NormalT >::applyFilter(), pcl::UniformSampling< PointT >::applyFilter(), pcl::ExtractIndices< PointT >::applyFilterIndices(), pcl::LocalMaximum< PointT >::applyFilterIndices(), pcl::ModelOutlierRemoval< PointT >::applyFilterIndices(), pcl::PassThrough< PointT >::applyFilterIndices(), pcl::RadiusOutlierRemoval< PointT >::applyFilterIndices(), pcl::StatisticalOutlierRemoval< PointT >::applyFilterIndices(), Filter(), pcl::ExtractIndices< PointT >::filterDirectly(), getRemovedIndices(), and getRemovedIndices().