Filter represents the base filter class. All filters must inherit from this interface. More...
#include <filter.h>
Public Types | |
typedef sensor_msgs::PointCloud2 | PointCloud2 |
typedef PointCloud2::ConstPtr | PointCloud2ConstPtr |
typedef PointCloud2::Ptr | PointCloud2Ptr |
Public Member Functions | |
Filter (bool extract_removed_indices=false) | |
Empty constructor. | |
void | filter (PointCloud2 &output) |
Calls the filtering method and returns the filtered dataset in output. | |
IndicesConstPtr const | getRemovedIndices () |
Get the point indices being removed. | |
Protected Member Functions | |
virtual void | applyFilter (PointCloud2 &output)=0 |
Abstract filter method. | |
const std::string & | getClassName () const |
Get a string representation of the name of this class. | |
Protected Attributes | |
bool | extract_removed_indices_ |
Set to true if we want to return the indices of the removed points. | |
std::string | filter_name_ |
The filter name. | |
IndicesPtr | removed_indices_ |
Indices of the points that are removed. |
Filter represents the base filter class. All filters must inherit from this interface.
typedef sensor_msgs::PointCloud2 pcl::Filter< sensor_msgs::PointCloud2 >::PointCloud2 |
Reimplemented from pcl::PCLBase< sensor_msgs::PointCloud2 >.
Reimplemented in pcl::VoxelGrid< sensor_msgs::PointCloud2 >, pcl::PassThrough< sensor_msgs::PointCloud2 >, pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >, pcl::FilterIndices< sensor_msgs::PointCloud2 >, pcl::CropBox< sensor_msgs::PointCloud2 >, pcl::RadiusOutlierRemoval< sensor_msgs::PointCloud2 >, pcl::ProjectInliers< sensor_msgs::PointCloud2 >, pcl::ExtractIndices< sensor_msgs::PointCloud2 >, and pcl::RandomSample< sensor_msgs::PointCloud2 >.
typedef PointCloud2::ConstPtr pcl::Filter< sensor_msgs::PointCloud2 >::PointCloud2ConstPtr |
Reimplemented from pcl::PCLBase< sensor_msgs::PointCloud2 >.
Reimplemented in pcl::VoxelGrid< sensor_msgs::PointCloud2 >, pcl::PassThrough< sensor_msgs::PointCloud2 >, pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >, pcl::CropBox< sensor_msgs::PointCloud2 >, pcl::RadiusOutlierRemoval< sensor_msgs::PointCloud2 >, pcl::ProjectInliers< sensor_msgs::PointCloud2 >, pcl::ExtractIndices< sensor_msgs::PointCloud2 >, and pcl::RandomSample< sensor_msgs::PointCloud2 >.
typedef PointCloud2::Ptr pcl::Filter< sensor_msgs::PointCloud2 >::PointCloud2Ptr |
Reimplemented from pcl::PCLBase< sensor_msgs::PointCloud2 >.
Reimplemented in pcl::VoxelGrid< sensor_msgs::PointCloud2 >, pcl::PassThrough< sensor_msgs::PointCloud2 >, pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >, pcl::CropBox< sensor_msgs::PointCloud2 >, pcl::RadiusOutlierRemoval< sensor_msgs::PointCloud2 >, pcl::ProjectInliers< sensor_msgs::PointCloud2 >, pcl::ExtractIndices< sensor_msgs::PointCloud2 >, and pcl::RandomSample< sensor_msgs::PointCloud2 >.
pcl::Filter< sensor_msgs::PointCloud2 >::Filter | ( | bool | extract_removed_indices = false | ) | [inline] |
virtual void pcl::Filter< sensor_msgs::PointCloud2 >::applyFilter | ( | PointCloud2 & | output | ) | [protected, pure virtual] |
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 |
Implemented in pcl::VoxelGrid< sensor_msgs::PointCloud2 >, pcl::PassThrough< sensor_msgs::PointCloud2 >, pcl::CropBox< sensor_msgs::PointCloud2 >, pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >, pcl::ProjectInliers< sensor_msgs::PointCloud2 >, pcl::RadiusOutlierRemoval< sensor_msgs::PointCloud2 >, pcl::RandomSample< sensor_msgs::PointCloud2 >, and pcl::ExtractIndices< sensor_msgs::PointCloud2 >.
void pcl::Filter< sensor_msgs::PointCloud2 >::filter | ( | PointCloud2 & | output | ) |
Calls the filtering method and returns the filtered dataset in output.
Base method for feature estimation for all points given in <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ()
[out] | output | the resultant filtered point cloud dataset |
output | the resultant filtered point cloud dataset |
Reimplemented in pcl::FilterIndices< sensor_msgs::PointCloud2 >.
Definition at line 63 of file filter.cpp.
const std::string& pcl::Filter< sensor_msgs::PointCloud2 >::getClassName | ( | ) | const [inline, protected] |
IndicesConstPtr const pcl::Filter< sensor_msgs::PointCloud2 >::getRemovedIndices | ( | ) | [inline] |
Get the point indices being removed.
Reimplemented in pcl::FilterIndices< sensor_msgs::PointCloud2 >.
bool pcl::Filter< sensor_msgs::PointCloud2 >::extract_removed_indices_ [protected] |
Set to true if we want to return the indices of the removed points.
Reimplemented in pcl::FilterIndices< sensor_msgs::PointCloud2 >.
std::string pcl::Filter< sensor_msgs::PointCloud2 >::filter_name_ [protected] |
IndicesPtr pcl::Filter< sensor_msgs::PointCloud2 >::removed_indices_ [protected] |
Indices of the points that are removed.
Reimplemented in pcl::FilterIndices< sensor_msgs::PointCloud2 >.