Point Cloud Library (PCL)
1.7.1
|
StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. More...
#include <pcl/filters/statistical_outlier_removal.h>
Public Member Functions | |
StatisticalOutlierRemoval (bool extract_removed_indices=false) | |
Empty constructor. More... | |
void | setMeanK (int nr_k) |
Set the number of points (k) to use for mean distance estimation. More... | |
int | getMeanK () |
Get the number of points to use for mean distance estimation. More... | |
void | setStddevMulThresh (double std_mul) |
Set the standard deviation multiplier threshold. More... | |
double | getStddevMulThresh () |
Get the standard deviation multiplier threshold as set by the user. More... | |
void | setNegative (bool negative) |
Set whether the indices should be returned, or all points except the indices. More... | |
bool | getNegative () |
Get the value of the internal negative_ parameter. More... | |
![]() | |
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 (PCLPointCloud2 &output) |
Calls the filtering method and returns the filtered dataset in output. More... | |
![]() | |
PCLBase () | |
Empty constructor. More... | |
virtual | ~PCLBase () |
destructor. More... | |
void | setInputCloud (const PCLPointCloud2ConstPtr &cloud) |
Provide a pointer to the input dataset. More... | |
PCLPointCloud2ConstPtr const | getInputCloud () |
Get a pointer to the input point cloud dataset. More... | |
void | setIndices (const IndicesPtr &indices) |
Provide a pointer to the vector of indices that represents the input data. More... | |
void | setIndices (const PointIndicesConstPtr &indices) |
Provide a pointer to the vector of indices that represents the input data. More... | |
IndicesPtr const | getIndices () |
Get a pointer to the vector of indices used. More... | |
Protected Member Functions | |
void | applyFilter (PCLPointCloud2 &output) |
Abstract filter method. More... | |
![]() | |
const std::string & | getClassName () const |
Get a string representation of the name of this class. More... | |
![]() | |
bool | initCompute () |
bool | deinitCompute () |
Protected Attributes | |
int | mean_k_ |
The number of points to use for mean distance estimation. More... | |
double | std_mul_ |
Standard deviations threshold (i.e., points outside of ![]() | |
KdTreePtr | tree_ |
A pointer to the spatial search object. More... | |
bool | negative_ |
If true, the outliers will be returned instead of the inliers (default: false). More... | |
![]() | |
IndicesPtr | removed_indices_ |
Indices of the points that are removed. More... | |
bool | extract_removed_indices_ |
Set to true if we want to return the indices of the removed points. More... | |
std::string | filter_name_ |
The filter name. More... | |
![]() | |
PCLPointCloud2ConstPtr | 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... | |
std::vector< int > | field_sizes_ |
The size of each individual field. More... | |
int | x_idx_ |
The x-y-z fields indices. More... | |
int | y_idx_ |
int | z_idx_ |
std::string | x_field_name_ |
The desired x-y-z field names. More... | |
std::string | y_field_name_ |
std::string | z_field_name_ |
Additional Inherited Members | |
![]() | |
typedef boost::shared_ptr < Filter< pcl::PCLPointCloud2 > > | Ptr |
typedef boost::shared_ptr < const Filter < pcl::PCLPointCloud2 > > | ConstPtr |
typedef pcl::PCLPointCloud2 | PCLPointCloud2 |
typedef PCLPointCloud2::Ptr | PCLPointCloud2Ptr |
typedef PCLPointCloud2::ConstPtr | PCLPointCloud2ConstPtr |
StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data.
For more information check:
Definition at line 202 of file statistical_outlier_removal.h.
|
inline |
Empty constructor.
Definition at line 219 of file statistical_outlier_removal.h.
|
protectedvirtual |
Abstract filter method.
The implementation needs to set output.{data, row_step, point_step, width, height, is_dense}.
[out] | output | the resultant filtered point cloud |
Implements pcl::Filter< pcl::PCLPointCloud2 >.
|
inline |
Get the number of points to use for mean distance estimation.
Definition at line 237 of file statistical_outlier_removal.h.
|
inline |
Get the value of the internal negative_ parameter.
If true, all points except the input indices will be returned.
Definition at line 275 of file statistical_outlier_removal.h.
|
inline |
Get the standard deviation multiplier threshold as set by the user.
Definition at line 256 of file statistical_outlier_removal.h.
|
inline |
Set the number of points (k) to use for mean distance estimation.
nr_k | the number of points to use for mean distance estimation |
Definition at line 230 of file statistical_outlier_removal.h.
|
inline |
Set whether the indices should be returned, or all points except the indices.
negative | true if all points except the input indices will be returned, false otherwise |
Definition at line 265 of file statistical_outlier_removal.h.
|
inline |
Set the standard deviation multiplier threshold.
All points outside the
will be considered outliers, where is the estimated mean, and
is the standard deviation.
std_mul | the standard deviation multiplier threshold |
Definition at line 249 of file statistical_outlier_removal.h.
|
protected |
The number of points to use for mean distance estimation.
Definition at line 282 of file statistical_outlier_removal.h.
|
protected |
If true, the outliers will be returned instead of the inliers (default: false).
Definition at line 293 of file statistical_outlier_removal.h.
|
protected |
Standard deviations threshold (i.e., points outside of will be marked as outliers).
Definition at line 287 of file statistical_outlier_removal.h.
|
protected |
A pointer to the spatial search object.
Definition at line 290 of file statistical_outlier_removal.h.