Outlier removal filter based on region growing (speckles). More...
#include <speckle_filter.h>
Public Types | |
typedef pcl::Filter< PointT > ::PointCloud | PointCloud |
typedef PointCloud::ConstPtr | PointCloudConstPtr |
typedef PointCloud::Ptr | PointCloudPtr |
Public Member Functions | |
pcl::PointIndices::Ptr | getRemovedIndices () |
Get the indices of the removed points. | |
double | getSpeckleRange () |
Get the speckle range parameter. | |
int | getSpeckleSize () |
Get the speckle size parameter. | |
void | setFilterParam (int speckle_s, double speckle_r) |
Set the filter parameters. | |
SpeckleFilter () | |
Protected Member Functions | |
void | applyFilter (PointCloud &output) |
Apply the filter. | |
Protected Attributes | |
pcl::PointIndices::Ptr | points_to_remove_ |
The indices of the removed points. | |
double | speckle_range_ |
The minimum distance between two speckles. | |
int | speckle_size_ |
The minimum speckle size. |
Outlier removal filter based on region growing (speckles).
See Fischer, Jan ; Arbeiter, Georg ; Verl, Alexander: Combination of Time-of-Flight Depth and Stereo using Semiglobal Optimization In: IEEE / Robotics and Automation Society: 2011 IEEE International Conference on Robotics and Automation ICRA : Better Robots, Better Life. May 9-13, 2011, Shanghai, China. Piscataway, NJ, USA : IEEE Press, 2011, S. 3548-3553. - URN urn:nbn:de:0011-n-1901013 for details.
Definition at line 82 of file speckle_filter.h.
typedef pcl::Filter<PointT>::PointCloud cob_3d_mapping_filters::SpeckleFilter< PointT >::PointCloud |
Definition at line 87 of file speckle_filter.h.
typedef PointCloud::ConstPtr cob_3d_mapping_filters::SpeckleFilter< PointT >::PointCloudConstPtr |
Definition at line 89 of file speckle_filter.h.
typedef PointCloud::Ptr cob_3d_mapping_filters::SpeckleFilter< PointT >::PointCloudPtr |
Definition at line 88 of file speckle_filter.h.
cob_3d_mapping_filters::SpeckleFilter< PointT >::SpeckleFilter | ( | ) | [inline] |
Definition at line 91 of file speckle_filter.h.
void SpeckleFilter::applyFilter | ( | PointCloud & | output | ) | [protected] |
Apply the filter.
[out] | output | The filtered point cloud. |
Definition at line 77 of file speckle_filter.hpp.
pcl::PointIndices::Ptr cob_3d_mapping_filters::SpeckleFilter< PointT >::getRemovedIndices | ( | ) | [inline] |
Get the indices of the removed points.
Definition at line 141 of file speckle_filter.h.
double cob_3d_mapping_filters::SpeckleFilter< PointT >::getSpeckleRange | ( | ) | [inline] |
Get the speckle range parameter.
Definition at line 130 of file speckle_filter.h.
int cob_3d_mapping_filters::SpeckleFilter< PointT >::getSpeckleSize | ( | ) | [inline] |
Get the speckle size parameter.
Definition at line 119 of file speckle_filter.h.
void cob_3d_mapping_filters::SpeckleFilter< PointT >::setFilterParam | ( | int | speckle_s, |
double | speckle_r | ||
) | [inline] |
Set the filter parameters.
[in] | speckle_s | The minimum speckle size. |
[in] | speckle_r | The minimum distance between speckles. |
Definition at line 107 of file speckle_filter.h.
pcl::PointIndices::Ptr cob_3d_mapping_filters::SpeckleFilter< PointT >::points_to_remove_ [protected] |
The indices of the removed points.
Definition at line 158 of file speckle_filter.h.
double cob_3d_mapping_filters::SpeckleFilter< PointT >::speckle_range_ [protected] |
The minimum distance between two speckles.
Definition at line 157 of file speckle_filter.h.
int cob_3d_mapping_filters::SpeckleFilter< PointT >::speckle_size_ [protected] |
The minimum speckle size.
Definition at line 156 of file speckle_filter.h.