Point Cloud Library (PCL)  1.8.1-dev
List of all members | Public Types | Public Member Functions | Protected Types | Protected Member Functions
pcl::PassThrough< PointT > Class Template Reference

PassThrough passes points in a cloud based on constraints for one particular field of the point type. More...

#include <pcl/filters/passthrough.h>

+ Inheritance diagram for pcl::PassThrough< PointT >:

Public Types

typedef boost::shared_ptr
< PassThrough< PointT > > 
Ptr
 
typedef boost::shared_ptr
< const PassThrough< PointT > > 
ConstPtr
 
- Public Types inherited from pcl::FilterIndices< PointT >
typedef pcl::PointCloud< PointTPointCloud
 
typedef boost::shared_ptr
< FilterIndices< PointT > > 
Ptr
 
typedef boost::shared_ptr
< const FilterIndices< PointT > > 
ConstPtr
 
- Public Types inherited from pcl::Filter< PointT >
typedef boost::shared_ptr
< Filter< PointT > > 
Ptr
 
typedef boost::shared_ptr
< const Filter< PointT > > 
ConstPtr
 
typedef pcl::PointCloud< PointTPointCloud
 
typedef PointCloud::Ptr PointCloudPtr
 
typedef PointCloud::ConstPtr PointCloudConstPtr
 
- Public Types inherited from pcl::PCLBase< PointT >
typedef pcl::PointCloud< PointTPointCloud
 
typedef PointCloud::Ptr PointCloudPtr
 
typedef PointCloud::ConstPtr PointCloudConstPtr
 
typedef boost::shared_ptr
< PointIndices
PointIndicesPtr
 
typedef boost::shared_ptr
< PointIndices const > 
PointIndicesConstPtr
 

Public Member Functions

 PassThrough (bool extract_removed_indices=false)
 Constructor. More...
 
void setFilterFieldName (const std::string &field_name)
 Provide the name of the field to be used for filtering data. More...
 
std::string const getFilterFieldName ()
 Retrieve the name of the field to be used for filtering data. More...
 
void setFilterLimits (const float &limit_min, const float &limit_max)
 Set the numerical limits for the field for filtering data. More...
 
void getFilterLimits (float &limit_min, float &limit_max)
 Get the numerical limits for the field for filtering data. More...
 
void setFilterLimitsNegative (const bool limit_negative)
 Set to true if we want to return the data outside the interval specified by setFilterLimits (min, max) Default: false. More...
 
void getFilterLimitsNegative (bool &limit_negative)
 Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). More...
 
bool getFilterLimitsNegative ()
 Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). More...
 
- Public Member Functions inherited from pcl::FilterIndices< PointT >
 FilterIndices (bool extract_removed_indices=false)
 Constructor. More...
 
virtual ~FilterIndices ()
 Empty virtual destructor. More...
 
void filter (PointCloud &output)
 
void filter (std::vector< int > &indices)
 Calls the filtering method and returns the filtered point cloud indices. More...
 
void setNegative (bool negative)
 Set whether the regular conditions for points filtering should apply, or the inverted conditions. More...
 
bool getNegative ()
 Get whether the regular conditions for points filtering should apply, or the inverted conditions. More...
 
void setKeepOrganized (bool keep_organized)
 Set whether the filtered points should be kept and set to the value given through setUserFilterValue (default: NaN), or removed from the PointCloud, thus potentially breaking its organized structure. More...
 
bool getKeepOrganized ()
 Get whether the filtered points should be kept and set to the value given through setUserFilterValue (default = NaN), or removed from the PointCloud, thus potentially breaking its organized structure. More...
 
void setUserFilterValue (float value)
 Provide a value that the filtered points should be set to instead of removing them. More...
 
- Public Member Functions inherited from pcl::Filter< PointT >
 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 (PointCloud &output)
 Calls the filtering method and returns the filtered dataset in output. More...
 
- Public Member Functions inherited from pcl::PCLBase< PointT >
 PCLBase ()
 Empty constructor. More...
 
 PCLBase (const PCLBase &base)
 Copy constructor. More...
 
virtual ~PCLBase ()
 Destructor. More...
 
virtual void setInputCloud (const PointCloudConstPtr &cloud)
 Provide a pointer to the input dataset. More...
 
PointCloudConstPtr const getInputCloud () const
 Get a pointer to the input point cloud dataset. More...
 
virtual void setIndices (const IndicesPtr &indices)
 Provide a pointer to the vector of indices that represents the input data. More...
 
virtual void setIndices (const IndicesConstPtr &indices)
 Provide a pointer to the vector of indices that represents the input data. More...
 
virtual void setIndices (const PointIndicesConstPtr &indices)
 Provide a pointer to the vector of indices that represents the input data. More...
 
virtual void setIndices (size_t row_start, size_t col_start, size_t nb_rows, size_t nb_cols)
 Set the indices for the points laying within an interest region of the point cloud. More...
 
IndicesPtr const getIndices ()
 Get a pointer to the vector of indices used. More...
 
IndicesConstPtr const getIndices () const
 Get a pointer to the vector of indices used. More...
 
const PointToperator[] (size_t pos) const
 Override PointCloud operator[] to shorten code. More...
 

Protected Types

typedef FilterIndices< PointT >
::PointCloud 
PointCloud
 
typedef PointCloud::Ptr PointCloudPtr
 
typedef PointCloud::ConstPtr PointCloudConstPtr
 
typedef pcl::traits::fieldList
< PointT >::type 
FieldList
 

Protected Member Functions

void applyFilter (PointCloud &output)
 Filtered results are stored in a separate point cloud. More...
 
void applyFilter (std::vector< int > &indices)
 Filtered results are indexed by an indices array. More...
 
void applyFilterIndices (std::vector< int > &indices)
 Filtered results are indexed by an indices array. More...
 
- Protected Member Functions inherited from pcl::Filter< PointT >
const std::string & getClassName () const
 Get a string representation of the name of this class. More...
 
- Protected Member Functions inherited from pcl::PCLBase< PointT >
bool initCompute ()
 This method should get called before starting the actual computation. More...
 
bool deinitCompute ()
 This method should get called after finishing the actual computation. More...
 

Additional Inherited Members

- Protected Attributes inherited from pcl::FilterIndices< PointT >
bool negative_
 False = normal filter behavior (default), true = inverted behavior. More...
 
bool keep_organized_
 False = remove points (default), true = redefine points, keep structure. More...
 
float user_filter_value_
 The user given value that the filtered point dimensions should be set to (default = NaN). More...
 
- Protected Attributes inherited from pcl::Filter< PointT >
IndicesPtr removed_indices_
 Indices of the points that are removed. More...
 
std::string filter_name_
 The filter name. More...
 
bool extract_removed_indices_
 Set to true if we want to return the indices of the removed points. More...
 
- Protected Attributes inherited from pcl::PCLBase< PointT >
PointCloudConstPtr 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...
 

Detailed Description

template<typename PointT>
class pcl::PassThrough< PointT >

PassThrough passes points in a cloud based on constraints for one particular field of the point type.

Iterates through the entire input once, automatically filtering non-finite points and the points outside the interval specified by setFilterLimits(), which applies only to the field specified by setFilterFieldName().

Usage example:

pcl::PassThrough<PointType> ptfilter (true); // Initializing with true will allow us to extract the removed indices
ptfilter.setInputCloud (cloud_in);
ptfilter.setFilterFieldName ("x");
ptfilter.setFilterLimits (0.0, 1000.0);
ptfilter.filter (*indices_x);
// The indices_x array indexes all points of cloud_in that have x between 0.0 and 1000.0
indices_rem = ptfilter.getRemovedIndices ();
// The indices_rem array indexes all points of cloud_in that have x smaller than 0.0 or larger than 1000.0
// and also indexes all non-finite points of cloud_in
ptfilter.setIndices (indices_x);
ptfilter.setFilterFieldName ("z");
ptfilter.setFilterLimits (-10.0, 10.0);
ptfilter.setNegative (true);
ptfilter.filter (*indices_xz);
// The indices_xz array indexes all points of cloud_in that have x between 0.0 and 1000.0 and z larger than 10.0 or smaller than -10.0
ptfilter.setIndices (indices_xz);
ptfilter.setFilterFieldName ("intensity");
ptfilter.setFilterLimits (FLT_MIN, 0.5);
ptfilter.setNegative (false);
ptfilter.filter (*cloud_out);
// The resulting cloud_out contains all points of cloud_in that are finite and have:
// x between 0.0 and 1000.0, z larger than 10.0 or smaller than -10.0 and intensity smaller than 0.5.
Author
Radu Bogdan Rusu

Definition at line 80 of file passthrough.h.

Member Typedef Documentation

template<typename PointT>
typedef boost::shared_ptr< const PassThrough<PointT> > pcl::PassThrough< PointT >::ConstPtr

Definition at line 91 of file passthrough.h.

template<typename PointT>
typedef pcl::traits::fieldList<PointT>::type pcl::PassThrough< PointT >::FieldList
protected

Definition at line 86 of file passthrough.h.

template<typename PointT>
typedef FilterIndices<PointT>::PointCloud pcl::PassThrough< PointT >::PointCloud
protected

Definition at line 83 of file passthrough.h.

template<typename PointT>
typedef PointCloud::ConstPtr pcl::PassThrough< PointT >::PointCloudConstPtr
protected

Definition at line 85 of file passthrough.h.

template<typename PointT>
typedef PointCloud::Ptr pcl::PassThrough< PointT >::PointCloudPtr
protected

Definition at line 84 of file passthrough.h.

template<typename PointT>
typedef boost::shared_ptr< PassThrough<PointT> > pcl::PassThrough< PointT >::Ptr

Definition at line 90 of file passthrough.h.

Constructor & Destructor Documentation

template<typename PointT>
pcl::PassThrough< PointT >::PassThrough ( bool  extract_removed_indices = false)
inline

Constructor.

Parameters
[in]extract_removed_indicesSet to true if you want to be able to extract the indices of points being removed (default = false).

Definition at line 97 of file passthrough.h.

Member Function Documentation

template<typename PointT >
void pcl::PassThrough< PointT >::applyFilter ( PointCloud output)
protectedvirtual

Filtered results are stored in a separate point cloud.

Parameters
[out]outputThe resultant point cloud.

Implements pcl::FilterIndices< PointT >.

Definition at line 48 of file passthrough.hpp.

References pcl::copyPointCloud(), pcl::PointCloud< T >::is_dense, and pcl::PointCloud< T >::points.

template<typename PointT>
void pcl::PassThrough< PointT >::applyFilter ( std::vector< int > &  indices)
inlineprotectedvirtual

Filtered results are indexed by an indices array.

Parameters
[out]indicesThe resultant indices.

Implements pcl::FilterIndices< PointT >.

Definition at line 200 of file passthrough.h.

template<typename PointT >
void pcl::PassThrough< PointT >::applyFilterIndices ( std::vector< int > &  indices)
protected

Filtered results are indexed by an indices array.

Parameters
[out]indicesThe resultant indices.

Definition at line 74 of file passthrough.hpp.

References pcl::getFieldIndex().

Referenced by pcl::PassThrough< PointInT >::applyFilter().

template<typename PointT>
std::string const pcl::PassThrough< PointT >::getFilterFieldName ( )
inline

Retrieve the name of the field to be used for filtering data.

Returns
The name of the field that will be used for filtering.

Definition at line 120 of file passthrough.h.

template<typename PointT>
void pcl::PassThrough< PointT >::getFilterLimits ( float &  limit_min,
float &  limit_max 
)
inline

Get the numerical limits for the field for filtering data.

Parameters
[out]limit_minThe minimum allowed field value (default = FLT_MIN).
[out]limit_maxThe maximum allowed field value (default = FLT_MAX).

Definition at line 142 of file passthrough.h.

template<typename PointT>
void pcl::PassThrough< PointT >::getFilterLimitsNegative ( bool &  limit_negative)
inline

Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).

Warning
This method will be removed in the future. Use getNegative() instead.
Parameters
[out]limit_negativetrue if data outside the interval [min; max] is to be returned, false otherwise

Definition at line 164 of file passthrough.h.

template<typename PointT>
bool pcl::PassThrough< PointT >::getFilterLimitsNegative ( )
inline

Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).

Warning
This method will be removed in the future. Use getNegative() instead.
Returns
true if data outside the interval [min; max] is to be returned, false otherwise

Definition at line 174 of file passthrough.h.

template<typename PointT>
void pcl::PassThrough< PointT >::setFilterFieldName ( const std::string &  field_name)
inline

Provide the name of the field to be used for filtering data.

In conjunction with setFilterLimits(), points having values outside this interval for this field will be discarded.

Parameters
[in]field_nameThe name of the field that will be used for filtering.

Definition at line 111 of file passthrough.h.

Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::ParticleFilterTracker().

template<typename PointT>
void pcl::PassThrough< PointT >::setFilterLimits ( const float &  limit_min,
const float &  limit_max 
)
inline

Set the numerical limits for the field for filtering data.

In conjunction with setFilterFieldName(), points having values outside this interval for this field will be discarded.

Parameters
[in]limit_minThe minimum allowed field value (default = FLT_MIN).
[in]limit_maxThe maximum allowed field value (default = FLT_MAX).

Definition at line 131 of file passthrough.h.

template<typename PointT>
void pcl::PassThrough< PointT >::setFilterLimitsNegative ( const bool  limit_negative)
inline

Set to true if we want to return the data outside the interval specified by setFilterLimits (min, max) Default: false.

Warning
This method will be removed in the future. Use setNegative() instead.
Parameters
[in]limit_negativereturn data inside the interval (false) or outside (true)

Definition at line 154 of file passthrough.h.


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