point_cloud_library / 1.12.1 / classpcl_1_1_filter_3_01pcl_1_1_p_c_l_point_cloud2_01_4.html /

Filter represents the base filter class. More...

#include <pcl/filters/filter.h>

Public Types

using Ptr = shared_ptr< Filter< pcl::PCLPointCloud2 > >
using ConstPtr = shared_ptr< const Filter< pcl::PCLPointCloud2 > >
using PCLPointCloud2 = pcl::PCLPointCloud2
using PCLPointCloud2Ptr = PCLPointCloud2::Ptr
using PCLPointCloud2ConstPtr = PCLPointCloud2::ConstPtr
- Public Types inherited from pcl::PCLBase< pcl::PCLPointCloud2 >
using PCLPointCloud2 = pcl::PCLPointCloud2
using PCLPointCloud2Ptr = PCLPointCloud2::Ptr
using PCLPointCloud2ConstPtr = PCLPointCloud2::ConstPtr
using PointIndicesPtr = PointIndices::Ptr
using PointIndicesConstPtr = PointIndices::ConstPtr

Public Member Functions

Filter (bool extract_removed_indices=false)
Empty constructor. More...
const IndicesConstPtr getRemovedIndices () const
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...
- Public Member Functions inherited from pcl::PCLBase< pcl::PCLPointCloud2 >
PCLBase ()
Empty constructor. More...
virtual ~PCLBase ()=default
destructor. More...
void setInputCloud (const PCLPointCloud2ConstPtr &cloud)
Provide a pointer to the input dataset. More...
const PCLPointCloud2ConstPtr getInputCloud () const
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...
const IndicesPtr getIndices () const
Get a pointer to the vector of indices used. More...

Protected Member Functions

virtual void applyFilter (PCLPointCloud2 &output)=0
Abstract filter method. More...
const std::string & getClassName () const
Get a string representation of the name of this class. More...
- Protected Member Functions inherited from pcl::PCLBase< pcl::PCLPointCloud2 >
bool initCompute ()
bool deinitCompute ()

Protected Attributes

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...
- Protected Attributes inherited from pcl::PCLBase< pcl::PCLPointCloud2 >
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< uindex_t > field_sizes_
The size of each individual field. More...
index_t x_idx_
The x-y-z fields indices. More...
index_t y_idx_
index_t 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_

Detailed Description

Filter represents the base filter class.

All filters must inherit from this interface.

Author
Radu B. Rusu

Definition at line 186 of file filter.h.

Member Typedef Documentation

ConstPtr

Definition at line 190 of file filter.h.

PCLPointCloud2

PCLPointCloud2ConstPtr

PCLPointCloud2Ptr

Ptr

Definition at line 189 of file filter.h.

Constructor & Destructor Documentation

Filter()

pcl::Filter< pcl::PCLPointCloud2 >::Filter ( bool extract_removed_indices = false )
inline

Empty constructor.

Parameters
[in] extract_removed_indices set to true if the filtered data indices should be saved in a separate list. Default: false.

Definition at line 200 of file filter.h.

Member Function Documentation

applyFilter()

virtual void pcl::Filter< pcl::PCLPointCloud2 >::applyFilter ( PCLPointCloud2 & output )
protectedpure virtual

filter()

void pcl::Filter< pcl::PCLPointCloud2 >::filter ( PCLPointCloud2 & output )

Calls the filtering method and returns the filtered dataset in output.

Parameters
[out] output the resultant filtered point cloud dataset

getClassName()

const std::string& pcl::Filter< pcl::PCLPointCloud2 >::getClassName ( ) const
inlineprotected

Get a string representation of the name of this class.

Definition at line 250 of file filter.h.

getRemovedIndices() [1/2]

const IndicesConstPtr pcl::Filter< pcl::PCLPointCloud2 >::getRemovedIndices ( ) const
inline

Get the point indices being removed.

Definition at line 208 of file filter.h.

getRemovedIndices() [2/2]

void pcl::Filter< pcl::PCLPointCloud2 >::getRemovedIndices ( PointIndices & pi )
inline

Get the point indices being removed.

Parameters
[out] pi the resultant point indices that have been removed

Definition at line 217 of file filter.h.

References pcl::PointIndices::indices.

Member Data Documentation

extract_removed_indices_

bool pcl::Filter< pcl::PCLPointCloud2 >::extract_removed_indices_
protected

Set to true if we want to return the indices of the removed points.

Definition at line 234 of file filter.h.

filter_name_

std::string pcl::Filter< pcl::PCLPointCloud2 >::filter_name_
protected

The filter name.

Definition at line 237 of file filter.h.

removed_indices_

IndicesPtr pcl::Filter< pcl::PCLPointCloud2 >::removed_indices_
protected

Indices of the points that are removed.

Definition at line 231 of file filter.h.


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

© 2009–2012, Willow Garage, Inc.
© 2012–, Open Perception, Inc.
Licensed under the BSD License.
https://pointclouds.org/documentation/classpcl_1_1_filter_3_01pcl_1_1_p_c_l_point_cloud2_01_4.html