Point Cloud Library (PCL)  1.6.0
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.

filters_statistical_noise.png

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::ConditionalRemoval< PointT >
 ConditionalRemoval filters data that satisfies certain conditions. 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< sensor_msgs::PointCloud2 >
 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::ExtractIndices< PointT >
 ExtractIndices extracts a set of indices from a point cloud. More...
class  pcl::ExtractIndices< sensor_msgs::PointCloud2 >
 ExtractIndices extracts a set of indices from a point cloud. More...
class  pcl::Filter< PointT >
 Filter represents the base filter class. More...
class  pcl::Filter< sensor_msgs::PointCloud2 >
 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< sensor_msgs::PointCloud2 >
 FilterIndices represents the base class for filters that are about binary point removal. 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< sensor_msgs::PointCloud2 >
 PassThrough uses the base Filter class methods to pass through all data that satisfies the user given constraints. 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< sensor_msgs::PointCloud2 >
 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< sensor_msgs::PointCloud2 >
 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< sensor_msgs::PointCloud2 >
 RandomSample applies a random sampling with uniform probability. More...
class  pcl::StatisticalOutlierRemoval< PointT >
 StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. More...
class  pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >
 StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier 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< sensor_msgs::PointCloud2 >
 VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. More...

Functions

template<typename PointT >
void pcl::removeNaNFromPointCloud (const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, std::vector< int > &index)
 Removes points with x, y, or z equal to NaN.
template<typename PointT >
void pcl::removeNaNFromPointCloud (const pcl::PointCloud< PointT > &cloud_in, std::vector< int > &index)
 Removes points with x, y, or z equal to NaN.
Eigen::MatrixXi pcl::getHalfNeighborCellIndices ()
 Get the relative cell indices of the "upper half" 13 neighbors.
Eigen::MatrixXi pcl::getAllNeighborCellIndices ()
 Get the relative cell indices of all the 26 neighbors.
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.

Function Documentation

Eigen::MatrixXi pcl::getAllNeighborCellIndices ( ) [inline]

Get the relative cell indices of all the 26 neighbors.

Note:
Useful in combination with getNeighborCentroidIndices() from VoxelGrid

Definition at line 123 of file voxel_grid.h.

Eigen::MatrixXi pcl::getHalfNeighborCellIndices ( ) [inline]

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

Note:
Useful in combination with getNeighborCentroidIndices() from VoxelGrid

Definition at line 86 of file voxel_grid.h.

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.

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 46 of file voxel_grid.hpp.

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

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

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

Definition at line 45 of file filter_indices.hpp.

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

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

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

Definition at line 45 of file filter.hpp.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines