Point Cloud Library (PCL)
1.11.1
|
3 #include <pcl/filters/passthrough.h>
4 #include <pcl/filters/voxel_grid.h>
5 #include <pcl/filters/radius_outlier_removal.h>
11 thresholdDepth (
const PointCloudPtr & input,
float min_depth,
float max_depth)
18 pass_through.
filter (*thresholded);
25 downsample (
const PointCloudPtr & input,
float leaf_size)
29 voxel_grid.
setLeafSize (leaf_size, leaf_size, leaf_size);
31 voxel_grid.
filter (*downsampled);
38 removeOutliers (
const PointCloudPtr & input,
float radius,
int min_neighbors)
45 radius_outlier_removal.
filter (*inliers);
52 applyFilters (
const PointCloudPtr & input,
float min_depth,
float max_depth,
float leaf_size,
float radius,
55 PointCloudPtr filtered;
56 filtered = thresholdDepth (input, min_depth, max_depth);
57 filtered = downsample (filtered, leaf_size);
58 filtered = removeOutliers (filtered, radius, min_neighbors);
VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data.
void setMinNeighborsInRadius(int min_pts)
Set the number of neighbors that need to be present in order to be classified as an inlier.
void setFilterFieldName(const std::string &field_name)
Provide the name of the field to be used for filtering data.
void setLeafSize(const Eigen::Vector4f &leaf_size)
Set the voxel grid leaf size.
void filter(PointCloud &output)
Calls the filtering method and returns the filtered dataset in output.
PointCloud represents the base class in PCL for storing collections of 3D points.
virtual void setInputCloud(const PointCloudConstPtr &cloud)
Provide a pointer to the input dataset.
void setRadiusSearch(double radius)
Set the radius of the sphere that will determine which points are neighbors.
RadiusOutlierRemoval filters points in a cloud based on the number of neighbors they have.
PassThrough passes points in a cloud based on constraints for one particular field of the point type.
void setFilterLimits(const float &limit_min, const float &limit_max)
Set the numerical limits for the field for filtering data.
void filter(std::vector< int > &indices)
Calls the filtering method and returns the filtered point cloud indices.