Point Cloud Library (PCL)  1.14.1-dev
Classes | Functions
Module filters

Detailed Description

Overview

The pcl_filters library contains outlier and noise removal mechanisms for 3D point cloud data filtering applications.

An example of noise removal is presented in the figure below. Due to measurement errors, certain datasets present a large number of shadow points. This complicates the estimation of local point cloud 3D features. Some of these outliers can be filtered by performing a statistical analysis on each point's neighborhood, and trimming those which do not meet a certain criteria. The sparse outlier removal implementation in PCL is based on the computation of the distribution of point to neighbors distances in the input dataset. For each point, the mean distance from it to all its neighbors is computed. By assuming that the resulted distribution is Gaussian with a mean and a standard deviation, all points whose mean distances are outside an interval defined by the global distances mean and standard deviation can be considered as outliers and trimmed from the dataset.

Requirements

Classes

class  pcl::ApproximateVoxelGrid< PointT >
 ApproximateVoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. More...
 
class  pcl::BilateralFilter< PointT >
 A bilateral filter implementation for point cloud data. More...
 
class  pcl::BoxClipper3D< PointT >
 Implementation of a box clipper in 3D. Actually it allows affine transformations, thus any parallelepiped in general pose. The affine transformation is used to transform the point before clipping it using a cube centered at origin and with an extend of -1 to +1 in each dimension. More...
 
class  pcl::Clipper3D< PointT >
 Base class for 3D clipper objects. More...
 
class  pcl::ConditionalRemoval< PointT >
 ConditionalRemoval filters data that satisfies certain conditions. More...
 
class  pcl::filters::Convolution< PointIn, PointOut >
 Convolution is a mathematical operation on two functions f and g, producing a third function that is typically viewed as a modified version of one of the original functions. More...
 
class  pcl::filters::ConvolvingKernel< PointInT, PointOutT >
 Class ConvolvingKernel base class for all convolving kernels. More...
 
class  pcl::filters::GaussianKernel< PointInT, PointOutT >
 Gaussian kernel implementation interface Use this as implementation reference. More...
 
class  pcl::filters::GaussianKernelRGB< PointInT, PointOutT >
 Gaussian kernel implementation interface with RGB channel handling Use this as implementation reference. More...
 
class  pcl::CropBox< PointT >
 CropBox is a filter that allows the user to filter all the data inside of a given box. More...
 
class  pcl::CropBox< pcl::PCLPointCloud2 >
 CropBox is a filter that allows the user to filter all the data inside of a given box. More...
 
class  pcl::CropHull< PointT >
 Filter points that lie inside or outside a 3D closed surface or 2D closed polygon, as generated by the ConvexHull or ConcaveHull classes. More...
 
class  pcl::experimental::advanced::FunctorFilter< PointT, FunctionObject >
 Filter point clouds and indices based on a function object passed in the ctor. More...
 
class  pcl::ExtractIndices< PointT >
 ExtractIndices extracts a set of indices from a point cloud. More...
 
class  pcl::ExtractIndices< pcl::PCLPointCloud2 >
 ExtractIndices extracts a set of indices from a point cloud. More...
 
class  pcl::FarthestPointSampling< PointT >
 FarthestPointSampling applies farthest point sampling using euclidean distance, starting with a random point, utilizing a naive method. More...
 
class  pcl::Filter< PointT >
 Filter represents the base filter class. More...
 
class  pcl::Filter< pcl::PCLPointCloud2 >
 Filter represents the base filter class. More...
 
class  pcl::FilterIndices< PointT >
 FilterIndices represents the base class for filters that are about binary point removal. More...
 
class  pcl::FilterIndices< pcl::PCLPointCloud2 >
 FilterIndices represents the base class for filters that are about binary point removal. More...
 
class  pcl::FrustumCulling< PointT >
 FrustumCulling filters points inside a frustum given by pose and field of view of the camera. More...
 
class  pcl::GridMinimum< PointT >
 GridMinimum assembles a local 2D grid over a given PointCloud, and downsamples the data. More...
 
class  pcl::LocalMaximum< PointT >
 LocalMaximum downsamples the cloud, by eliminating points that are locally maximal. More...
 
class  pcl::MedianFilter< PointT >
 Implementation of the median filter. More...
 
class  pcl::NormalRefinement< NormalT >
 Normal vector refinement class More...
 
class  pcl::NormalSpaceSampling< PointT, NormalT >
 NormalSpaceSampling samples the input point cloud in the space of normal directions computed at every point. More...
 
class  pcl::PassThrough< PointT >
 PassThrough passes points in a cloud based on constraints for one particular field of the point type. More...
 
class  pcl::PassThrough< pcl::PCLPointCloud2 >
 PassThrough uses the base Filter class methods to pass through all data that satisfies the user given constraints. More...
 
class  pcl::PlaneClipper3D< PointT >
 Implementation of a plane clipper in 3D. More...
 
class  pcl::ProjectInliers< PointT >
 ProjectInliers uses a model and a set of inlier indices from a PointCloud to project them into a separate PointCloud. More...
 
class  pcl::ProjectInliers< pcl::PCLPointCloud2 >
 ProjectInliers uses a model and a set of inlier indices from a PointCloud to project them into a separate PointCloud. More...
 
class  pcl::RadiusOutlierRemoval< PointT >
 RadiusOutlierRemoval filters points in a cloud based on the number of neighbors they have. More...
 
class  pcl::RadiusOutlierRemoval< pcl::PCLPointCloud2 >
 RadiusOutlierRemoval is a simple filter that removes outliers if the number of neighbors in a certain search radius is smaller than a given K. More...
 
class  pcl::RandomSample< PointT >
 RandomSample applies a random sampling with uniform probability. More...
 
class  pcl::RandomSample< pcl::PCLPointCloud2 >
 RandomSample applies a random sampling with uniform probability. More...
 
class  pcl::SamplingSurfaceNormal< PointT >
 SamplingSurfaceNormal divides the input space into grids until each grid contains a maximum of N points, and samples points randomly within each grid. More...
 
class  pcl::ShadowPoints< PointT, NormalT >
 ShadowPoints removes the ghost points appearing on edge discontinuties More...
 
class  pcl::StatisticalOutlierRemoval< PointT >
 StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. More...
 
class  pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 >
 StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. More...
 
class  pcl::UniformSampling< PointT >
 UniformSampling assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. More...
 
class  pcl::VoxelGrid< PointT >
 VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. More...
 
class  pcl::VoxelGrid< pcl::PCLPointCloud2 >
 VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. More...
 
class  pcl::VoxelGridOcclusionEstimation< PointT >
 VoxelGrid to estimate occluded space in the scene. More...
 

Functions

template<typename PointT >
void pcl::removeNaNFromPointCloud (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, Indices &index)
 Removes points with x, y, or z equal to NaN. More...
 
template<typename PointT >
void pcl::removeNaNNormalsFromPointCloud (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, Indices &index)
 Removes points that have their normals invalid (i.e., equal to NaN) More...
 
template<typename PointT >
void pcl::removeNaNFromPointCloud (const pcl::PointCloud< PointT > &cloud_in, Indices &index)
 Removes points with x, y, or z equal to NaN (dry run). More...
 
template<typename PointT >
PCL_EXPORTS void pcl::applyMorphologicalOperator (const typename pcl::PointCloud< PointT >::ConstPtr &cloud_in, float resolution, const int morphological_operator, pcl::PointCloud< PointT > &cloud_out)
 Apply morphological operator to the z dimension of the input point cloud. More...
 
template<typename NormalT >
std::vector< float > pcl::assignNormalWeights (const PointCloud< NormalT > &cloud, index_t index, const Indices &k_indices, const std::vector< float > &k_sqr_distances)
 Assign weights of nearby normals used for refinement. More...
 
template<typename NormalT >
bool pcl::refineNormal (const PointCloud< NormalT > &cloud, int index, const Indices &k_indices, const std::vector< float > &k_sqr_distances, NormalT &point)
 Refine an indexed point based on its neighbors, this function only writes to the normal_* fields. More...
 
Eigen::MatrixXi pcl::getHalfNeighborCellIndices ()
 Get the relative cell indices of the "upper half" 13 neighbors. More...
 
Eigen::MatrixXi pcl::getAllNeighborCellIndices ()
 Get the relative cell indices of all the 26 neighbors. More...
 
template<typename PointT >
void pcl::getMinMax3D (const typename pcl::PointCloud< PointT >::ConstPtr &cloud, const std::string &distance_field_name, float min_distance, float max_distance, Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative=false)
 Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud, without considering points outside of a distance threshold from the laser origin. More...
 
template<typename PointT >
void pcl::getMinMax3D (const typename pcl::PointCloud< PointT >::ConstPtr &cloud, const Indices &indices, const std::string &distance_field_name, float min_distance, float max_distance, Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative=false)
 Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud, without considering points outside of a distance threshold from the laser origin. More...
 

Function Documentation

◆ applyMorphologicalOperator()

template<typename PointT >
PCL_EXPORTS void pcl::applyMorphologicalOperator ( const typename pcl::PointCloud< PointT >::ConstPtr &  cloud_in,
float  resolution,
const int  morphological_operator,
pcl::PointCloud< PointT > &  cloud_out 
)

#include <pcl/filters/morphological_filter.h>

Apply morphological operator to the z dimension of the input point cloud.

Parameters
[in]cloud_inthe input point cloud dataset
[in]resolutionthe window size to be used for the morphological operation
[in]morphological_operatorthe morphological operator to apply (open, close, dilate, erode)
[out]cloud_outthe resultant output point cloud dataset

Definition at line 57 of file morphological_filter.hpp.

References pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::addPointsFromInputCloud(), pcl::octree::OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT >::boxSearch(), pcl::copyPointCloud(), pcl::PointCloud< PointT >::empty(), pcl::MORPH_CLOSE, pcl::MORPH_DILATE, pcl::MORPH_ERODE, pcl::MORPH_OPEN, pcl::octree::OctreePointCloud< PointT, LeafContainerT, BranchContainerT, OctreeT >::setInputCloud(), pcl::PointCloud< PointT >::size(), and pcl::PointCloud< PointT >::swap().

◆ assignNormalWeights()

template<typename NormalT >
std::vector<float> pcl::assignNormalWeights ( const PointCloud< NormalT > &  cloud,
index_t  index,
const Indices k_indices,
const std::vector< float > &  k_sqr_distances 
)
inline

#include <pcl/filters/normal_refinement.h>

Assign weights of nearby normals used for refinement.

Todo:
Currently, this function equalizes all weights to 1
Parameters
cloudthe point cloud data
indexa valid index in cloud representing a valid (i.e., finite) query point
k_indicesindices of neighboring points
k_sqr_distancessquared distances to the neighboring points
Returns
weights

Definition at line 56 of file normal_refinement.h.

References pcl::utils::ignore().

Referenced by pcl::refineNormal().

◆ getAllNeighborCellIndices()

Eigen::MatrixXi pcl::getAllNeighborCellIndices ( )
inline

#include <pcl/filters/voxel_grid.h>

Get the relative cell indices of all the 26 neighbors.

Note
Useful in combination with getNeighborCentroidIndices() from VoxelGrid

Definition at line 153 of file voxel_grid.h.

References pcl::getHalfNeighborCellIndices().

Referenced by pcl::VoxelGridCovariance< PointT >::getAllNeighborsAtPoint(), and pcl::VoxelGridCovariance< PointTarget >::getFaceNeighborsAtPoint().

◆ getHalfNeighborCellIndices()

Eigen::MatrixXi pcl::getHalfNeighborCellIndices ( )
inline

#include <pcl/filters/voxel_grid.h>

Get the relative cell indices of the "upper half" 13 neighbors.

Note
Useful in combination with getNeighborCentroidIndices() from VoxelGrid

Definition at line 116 of file voxel_grid.h.

Referenced by pcl::getAllNeighborCellIndices().

◆ getMinMax3D() [1/2]

template<typename PointT >
void pcl::getMinMax3D ( const typename pcl::PointCloud< PointT >::ConstPtr &  cloud,
const Indices indices,
const std::string &  distance_field_name,
float  min_distance,
float  max_distance,
Eigen::Vector4f &  min_pt,
Eigen::Vector4f &  max_pt,
bool  limit_negative = false 
)

#include <pcl/filters/voxel_grid.h>

Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud, without considering points outside of a distance threshold from the laser origin.

Parameters
[in]cloudthe point cloud data message
[in]indicesthe vector of indices to use
[in]distance_field_namethe field name that contains the distance values
[in]min_distancethe minimum distance a point will be considered from
[in]max_distancethe maximum distance a point will be considered to
[out]min_ptthe resultant minimum bounds
[out]max_ptthe resultant maximum bounds
[in]limit_negativeif set to true, then all points outside of the interval (min_distance;max_distace) are considered

Definition at line 132 of file voxel_grid.hpp.

References pcl::PointCloud< PointT >::is_dense.

◆ getMinMax3D() [2/2]

template<typename PointT >
void pcl::getMinMax3D ( const typename pcl::PointCloud< PointT >::ConstPtr &  cloud,
const std::string &  distance_field_name,
float  min_distance,
float  max_distance,
Eigen::Vector4f &  min_pt,
Eigen::Vector4f &  max_pt,
bool  limit_negative = false 
)

#include <pcl/filters/voxel_grid.h>

Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud, without considering points outside of a distance threshold from the laser origin.

Parameters
[in]cloudthe point cloud data message
[in]distance_field_namethe field name that contains the distance values
[in]min_distancethe minimum distance a point will be considered from
[in]max_distancethe maximum distance a point will be considered to
[out]min_ptthe resultant minimum bounds
[out]max_ptthe resultant maximum bounds
[in]limit_negativeif set to true, then all points outside of the interval (min_distance;max_distace) are considered

Definition at line 51 of file voxel_grid.hpp.

References pcl::PointCloud< PointT >::is_dense, and pcl::isXYZFinite().

◆ refineNormal()

template<typename NormalT >
bool pcl::refineNormal ( const PointCloud< NormalT > &  cloud,
int  index,
const Indices k_indices,
const std::vector< float > &  k_sqr_distances,
NormalT point 
)
inline

#include <pcl/filters/normal_refinement.h>

Refine an indexed point based on its neighbors, this function only writes to the normal_* fields.

Note
If the indexed point has only NaNs in its neighborhood, the resulting normal will be zero.
Parameters
cloudthe point cloud data
indexa valid index in cloud representing a valid (i.e., finite) query point
k_indicesindices of neighboring points
k_sqr_distancessquared distances to the neighboring points
pointthe output point, only normal_* fields are written
Returns
false if an error occurred (norm of summed normals zero or all neighbors NaN)

Definition at line 87 of file normal_refinement.h.

References pcl::assignNormalWeights().

Referenced by pcl::NormalRefinement< NormalT >::applyFilter().

◆ removeNaNFromPointCloud() [1/2]

template<typename PointT >
void pcl::removeNaNFromPointCloud ( const pcl::PointCloud< PointT > &  cloud_in,
Indices index 
)

#include <pcl/filters/filter_indices.h>

Removes points with x, y, or z equal to NaN (dry run).

This function only computes the mapping between the points in the input cloud and the cloud that would result from filtering. It does not actually construct and output the filtered cloud.

Note
This function does not modify the input point cloud!
Parameters
cloud_inthe input point cloud
indexthe mapping (ordered): filtered_cloud[i] = cloud_in[index[i]]
See also
removeNaNFromPointCloud

Definition at line 44 of file filter_indices.hpp.

References pcl::PointCloud< PointT >::is_dense, and pcl::PointCloud< PointT >::size().

◆ removeNaNFromPointCloud() [2/2]

template<typename PointT >
void pcl::removeNaNFromPointCloud ( const pcl::PointCloud< PointT > &  cloud_in,
pcl::PointCloud< PointT > &  cloud_out,
Indices index 
)

#include <pcl/filters/filter.h>

Removes points with x, y, or z equal to NaN.

Parameters
[in]cloud_inthe input point cloud
[out]cloud_outthe output point cloud
[out]indexthe mapping (ordered): cloud_out[i] = cloud_in[index[i]]
Note
The density of the point cloud is lost.
Can be called with cloud_in == cloud_out

Definition at line 46 of file filter.hpp.

References pcl::PointCloud< PointT >::header, pcl::PointCloud< PointT >::height, pcl::PointCloud< PointT >::is_dense, pcl::PointCloud< PointT >::resize(), pcl::PointCloud< PointT >::sensor_orientation_, pcl::PointCloud< PointT >::sensor_origin_, pcl::PointCloud< PointT >::size(), and pcl::PointCloud< PointT >::width.

Referenced by pcl::kinfuLS::WorldModel< PointT >::cleanWorldFromNans(), and pcl::kinfuLS::WorldModel< PointT >::getWorldAsCubes().

◆ removeNaNNormalsFromPointCloud()

template<typename PointT >
void pcl::removeNaNNormalsFromPointCloud ( const pcl::PointCloud< PointT > &  cloud_in,
pcl::PointCloud< PointT > &  cloud_out,
Indices index 
)

#include <pcl/filters/filter.h>

Removes points that have their normals invalid (i.e., equal to NaN)

Parameters
[in]cloud_inthe input point cloud
[out]cloud_outthe output point cloud
[out]indexthe mapping (ordered): cloud_out[i] = cloud_in[index[i]]
Note
The density of the point cloud is lost.
Can be called with cloud_in == cloud_out

Definition at line 99 of file filter.hpp.

References pcl::PointCloud< PointT >::header, pcl::PointCloud< PointT >::height, pcl::PointCloud< PointT >::is_dense, pcl::isFinite(), pcl::PointCloud< PointT >::resize(), pcl::PointCloud< PointT >::sensor_orientation_, pcl::PointCloud< PointT >::sensor_origin_, pcl::PointCloud< PointT >::size(), and pcl::PointCloud< PointT >::width.