RaspiKinect  1.0
Filter Class Reference

#include <filter.h>

Public Member Functions

pcl::PointCloud< pcl::PointXYZRGB >::Ptr removeNaNPoints (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud)
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr passThrough (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, float min_val, float max_val)
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr voxelGrid (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, float leaf_size)
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr statisticalOutlierRemoval (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &input, float mean, float std_dev)
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr radiusOutlineRemoval (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, float radius, int neighbors)
 
pcl::PointCloud< pcl::PointNormal >::Ptr removeNaNNormals (const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud)
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr matrixTransform (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, char axis, float theta, float translation, bool centroid)
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr medianFilter (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud)
 
pcl::PointCloud< pcl::PointNormal >::Ptr movingLeastSquaresSmooth (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud)
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr movingLeastSquaresUpsample (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud)
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr applyFilters (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, float min_val, float max_val, float leaf_size, float radius, int neighbors)
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr bilateralFilter (const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud)
 

Detailed Description

A filter class which holds many useful filters

Member Function Documentation

§ applyFilters()

pcl::PointCloud< pcl::PointXYZRGB >::Ptr Filter::applyFilters ( const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  cloud,
float  min_val,
float  max_val,
float  leaf_size,
float  radius,
int  neighbors 
)

Apply the selected filters to the point cloud. Modify as required.

Parameters
[in]cloudinput point cloud
[in]min_valminimum value to apply the filter
[in]max_valmaximum value to apply the filter
[in]leaf_sizethe size of leaf
[in]radiusradius in meters

§ bilateralFilter()

pcl::PointCloud< pcl::PointXYZRGB >::Ptr Filter::bilateralFilter ( const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  cloud)

Apply bilateral filter to the point cloud. It smoothes the point cloud while preserving edges.

Parameters
[in]cloudinput point cloud

§ matrixTransform()

pcl::PointCloud< pcl::PointXYZRGB >::Ptr Filter::matrixTransform ( const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  cloud,
char  axis,
float  theta,
float  translation,
bool  centroid 
)

Apply Eigen Affine3D Matrix transformation to the point cloud.

Parameters
[in]cloudinput point cloud
[in]axisthe axis to rotate the cloud
[in]thetathe angle in radians
[in]translationapply translation if needed, otherwise pass zero
[in]centroidboolean value where if true: rotate around centroid if false: rotate around origin

§ medianFilter()

pcl::PointCloud< pcl::PointXYZRGB >::Ptr Filter::medianFilter ( const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  cloud)

Apply Median Filter to the point cloud

Parameters
[in]cloudinput point cloud

§ movingLeastSquaresSmooth()

pcl::PointCloud< pcl::PointNormal >::Ptr Filter::movingLeastSquaresSmooth ( const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  cloud)

Smooth Surface Normals using moving least squares algorithm. Returns a pointer to surface normals

Parameters
[in]cloudinput point cloud

§ movingLeastSquaresUpsample()

pcl::PointCloud< pcl::PointXYZRGB >::Ptr Filter::movingLeastSquaresUpsample ( const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  cloud)

Upsample the point cloud using least squares algorithm. Make sure to apply voxel grid filter first if the cloud is large.

Parameters
[in]cloudinput point cloud

§ passThrough()

pcl::PointCloud< pcl::PointXYZRGB >::Ptr Filter::passThrough ( const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  cloud,
float  min_val,
float  max_val 
)

Apply passthrough filter to get rid of unnecessary Z values. (background removal) Even background removal is not necessary, apply the min and max values as zero to remove blank points generated from libfreenect drivers.

Parameters
[in]cloudinput point cloud
[in]min_valminimum value to apply the filter
[in]max_valmaximum value to apply the filter

§ radiusOutlineRemoval()

pcl::PointCloud< pcl::PointXYZRGB >::Ptr Filter::radiusOutlineRemoval ( const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  cloud,
float  radius,
int  neighbors 
)

The user specifies a number of neighbors which every indice must have within a specified radius to remain in the PointCloud. For example if 1 neighbor is specified, only the yellow point will be removed from the PointCloud. If 2 neighbors are specified then both the yellow and green points will be removed from the PointCloud.

Parameters
[in]cloudinput point cloud
[in]radiusradius in meter
[in]neighborsnumber of neighbors required

§ removeNaNNormals()

pcl::PointCloud< pcl::PointNormal >::Ptr Filter::removeNaNNormals ( const pcl::PointCloud< pcl::PointNormal >::Ptr &  cloud)

Remove NaN values from surface normals

Parameters
[in]cloudinput point cloud

§ removeNaNPoints()

pcl::PointCloud< pcl::PointXYZRGB >::Ptr Filter::removeNaNPoints ( const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  cloud)

Remove NaN values generated by pcl algorithms.

Parameters
[in]pointsinput point cloud

§ statisticalOutlierRemoval()

pcl::PointCloud< pcl::PointXYZRGB >::Ptr Filter::statisticalOutlierRemoval ( const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  input,
float  mean,
float  std_dev 
)

remove noisy measurements, e.g. outliers, from a point cloud dataset using statistical analysis techniques.

Parameters
[in]cloudinput point cloud
[in]meanthe number of neighbors to analyze for each point
[in]std_devthe standard deviation multiplier

§ voxelGrid()

pcl::PointCloud< pcl::PointXYZRGB >::Ptr Filter::voxelGrid ( const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  cloud,
float  leaf_size 
)

Apply Voxel Grid filter to downsample data without losing necessary information

Parameters
[in]cloudinput point cloud
[in]leaf_sizethe size of leaf

The documentation for this class was generated from the following files: