Point Cloud Library (PCL)
1.8.1
|
Filter represents the base filter class. More...
#include <pcl/filters/filter.h>
Public Types | |
typedef boost::shared_ptr< Filter< PointT > > | Ptr |
typedef boost::shared_ptr< const Filter< PointT > > | ConstPtr |
typedef pcl::PointCloud< PointT > | PointCloud |
typedef PointCloud::Ptr | PointCloudPtr |
typedef PointCloud::ConstPtr | PointCloudConstPtr |
![]() | |
typedef pcl::PointCloud< PointT > | PointCloud |
typedef PointCloud::Ptr | PointCloudPtr |
typedef PointCloud::ConstPtr | PointCloudConstPtr |
typedef boost::shared_ptr< PointIndices > | PointIndicesPtr |
typedef boost::shared_ptr< PointIndices const > | PointIndicesConstPtr |
Public Member Functions | |
Filter (bool extract_removed_indices=false) | |
Empty constructor. More... | |
virtual | ~Filter () |
Empty destructor. More... | |
IndicesConstPtr const | getRemovedIndices () |
Get the point indices being removed. More... | |
void | getRemovedIndices (PointIndices &pi) |
Get the point indices being removed. More... | |
void | filter (PointCloud &output) |
Calls the filtering method and returns the filtered dataset in output. More... | |
![]() | |
PCLBase () | |
Empty constructor. More... | |
PCLBase (const PCLBase &base) | |
Copy constructor. More... | |
virtual | ~PCLBase () |
Destructor. More... | |
virtual void | setInputCloud (const PointCloudConstPtr &cloud) |
Provide a pointer to the input dataset. More... | |
PointCloudConstPtr const | getInputCloud () const |
Get a pointer to the input point cloud dataset. More... | |
virtual void | setIndices (const IndicesPtr &indices) |
Provide a pointer to the vector of indices that represents the input data. More... | |
virtual void | setIndices (const IndicesConstPtr &indices) |
Provide a pointer to the vector of indices that represents the input data. More... | |
virtual void | setIndices (const PointIndicesConstPtr &indices) |
Provide a pointer to the vector of indices that represents the input data. More... | |
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. More... | |
IndicesPtr const | getIndices () |
Get a pointer to the vector of indices used. More... | |
IndicesConstPtr const | getIndices () const |
Get a pointer to the vector of indices used. More... | |
const PointT & | operator[] (size_t pos) const |
Override PointCloud operator[] to shorten code. More... | |
Protected Member Functions | |
virtual void | applyFilter (PointCloud &output)=0 |
Abstract filter method. More... | |
const std::string & | getClassName () const |
Get a string representation of the name of this class. More... | |
![]() | |
bool | initCompute () |
This method should get called before starting the actual computation. More... | |
bool | deinitCompute () |
This method should get called after finishing the actual computation. More... | |
Protected Attributes | |
IndicesPtr | removed_indices_ |
Indices of the points that are removed. More... | |
std::string | filter_name_ |
The filter name. More... | |
bool | extract_removed_indices_ |
Set to true if we want to return the indices of the removed points. More... | |
![]() | |
PointCloudConstPtr | input_ |
The input point cloud dataset. More... | |
IndicesPtr | indices_ |
A pointer to the vector of point indices to use. More... | |
bool | use_indices_ |
Set to true if point indices are used. More... | |
bool | fake_indices_ |
If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud. More... | |
Filter represents the base filter class.
All filters must inherit from this interface.
typedef boost::shared_ptr< const Filter<PointT> > pcl::Filter< PointT >::ConstPtr |
typedef pcl::PointCloud<PointT> pcl::Filter< PointT >::PointCloud |
typedef PointCloud::ConstPtr pcl::Filter< PointT >::PointCloudConstPtr |
typedef PointCloud::Ptr pcl::Filter< PointT >::PointCloudPtr |
typedef boost::shared_ptr< Filter<PointT> > pcl::Filter< PointT >::Ptr |
|
inline |
|
inlinevirtual |
|
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::ConditionalRemoval< PointT >, pcl::VoxelGridCovariance< PointT >, pcl::VoxelGridCovariance< PointTarget >, pcl::VoxelGrid< PointT >, pcl::VoxelGrid< pcl::PointXYZRGB >, pcl::VoxelGrid< PointTarget >, pcl::VoxelGrid< pcl::PointXYZRGBL >, pcl::ApproximateVoxelGrid< PointT >, pcl::FrustumCulling< PointT >, pcl::ModelOutlierRemoval< PointT >, pcl::PassThrough< PointT >, pcl::PassThrough< PointInT >, pcl::FilterIndices< PointT >, pcl::FilterIndices< PointInT >, pcl::CropBox< PointT >, pcl::NormalSpaceSampling< PointT, NormalT >, pcl::StatisticalOutlierRemoval< PointT >, pcl::RadiusOutlierRemoval< PointT >, pcl::CovarianceSampling< PointT, PointNT >, pcl::ProjectInliers< PointT >, pcl::SamplingSurfaceNormal< PointT >, pcl::Convolution< PointInT >, pcl::CropHull< PointT >, pcl::UniformSampling< PointT >, pcl::RandomSample< PointT >, pcl::ExtractIndices< PointT >, pcl::ShadowPoints< PointT, NormalT >, pcl::GridMinimum< PointT >, pcl::FastBilateralFilter< PointT >, pcl::MedianFilter< PointT >, pcl::LocalMaximum< PointT >, pcl::FastBilateralFilterOMP< PointT >, pcl::BilateralFilter< PointT >, and pcl::VoxelGridLabel.
Referenced by pcl::Filter< pcl::PointXYZRGBL >::filter().
|
inline |
Calls the filtering method and returns the filtered dataset in output.
[out] | output | the resultant filtered point cloud dataset |
Definition at line 132 of file filter.h.
Referenced by pcl::LocalMaximum< PointT >::applyFilterIndices(), pcl::GRSDEstimation< PointInT, PointNT, PointOutT >::computeFeature(), pcl::CrfSegmentation< PointT >::createVoxelGrid(), pcl::SIFTKeypoint< PointInT, PointOutT >::detectKeypoints(), pcl::FilterIndices< PointInT >::filter(), pcl::FilterIndices< pcl::PCLPointCloud2 >::filter(), pcl::people::GroundBasedPeopleDetectionApp< PointT >::filter(), pcl::kinfuLS::WorldModel< pcl::PointXYZI >::getExistingData(), pcl::Filter< pcl::PCLPointCloud2 >::getRemovedIndices(), pcl::kinfuLS::WorldModel< pcl::PointXYZI >::getWorldAsCubes(), pcl::HypothesisVerification< ModelT, SceneT >::setSceneCloud(), pcl::kinfuLS::WorldModel< pcl::PointXYZI >::setSliceAsNans(), pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::simplifyCloud(), and pcl::GlobalHypothesesVerification< ModelT, SceneT >::verify().
|
inlineprotected |
Get a string representation of the name of this class.
Definition at line 182 of file filter.h.
Referenced by pcl::VoxelGridCovariance< PointTarget >::nearestKSearch(), pcl::VoxelGridCovariance< PointTarget >::radiusSearch(), and pcl::VoxelGridCovariance< PointTarget >::setMinPointPerVoxel().
|
inline |
Get the point indices being removed.
Definition at line 114 of file filter.h.
Referenced by pcl::kinfuLS::WorldModel< pcl::PointXYZI >::setSliceAsNans().
|
inline |
|
protected |
Set to true if we want to return the indices of the removed points.
Definition at line 169 of file filter.h.
Referenced by pcl::FilterIndices< PointInT >::FilterIndices(), and pcl::FilterIndices< pcl::PCLPointCloud2 >::FilterIndices().
|
protected |
The filter name.
Definition at line 166 of file filter.h.
Referenced by pcl::CovarianceSampling< PointT, PointNT >::CovarianceSampling(), pcl::CropBox< PointT >::CropBox(), pcl::CropBox< pcl::PCLPointCloud2 >::CropBox(), pcl::CropHull< PointT >::CropHull(), pcl::ExtractIndices< PointT >::ExtractIndices(), pcl::ExtractIndices< pcl::PCLPointCloud2 >::ExtractIndices(), pcl::FrustumCulling< PointT >::FrustumCulling(), pcl::GridMinimum< PointT >::GridMinimum(), pcl::LocalMaximum< PointT >::LocalMaximum(), pcl::ModelOutlierRemoval< PointT >::ModelOutlierRemoval(), pcl::NormalSpaceSampling< PointT, NormalT >::NormalSpaceSampling(), pcl::PassThrough< PointInT >::PassThrough(), pcl::PassThrough< pcl::PCLPointCloud2 >::PassThrough(), pcl::ProjectInliers< PointT >::ProjectInliers(), pcl::ProjectInliers< pcl::PCLPointCloud2 >::ProjectInliers(), pcl::RadiusOutlierRemoval< PointT >::RadiusOutlierRemoval(), pcl::RadiusOutlierRemoval< pcl::PCLPointCloud2 >::RadiusOutlierRemoval(), pcl::RandomSample< PointT >::RandomSample(), pcl::RandomSample< pcl::PCLPointCloud2 >::RandomSample(), pcl::SamplingSurfaceNormal< PointT >::SamplingSurfaceNormal(), pcl::ShadowPoints< PointT, NormalT >::ShadowPoints(), pcl::StatisticalOutlierRemoval< PointT >::StatisticalOutlierRemoval(), pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >::StatisticalOutlierRemoval(), pcl::UniformSampling< PointT >::UniformSampling(), pcl::VoxelGrid< pcl::PointXYZRGBL >::VoxelGrid(), pcl::VoxelGrid< pcl::PCLPointCloud2 >::VoxelGrid(), and pcl::VoxelGridCovariance< PointTarget >::VoxelGridCovariance().
|
protected |
Indices of the points that are removed.
Definition at line 163 of file filter.h.
Referenced by pcl::Filter< pcl::PointXYZRGBL >::getRemovedIndices(), and pcl::Filter< pcl::PCLPointCloud2 >::getRemovedIndices().