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

PassThrough uses the base Filter class methods to pass through all data that satisfies the user given constraints. More...

#include <pcl/filters/passthrough.h>

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

Public Member Functions

 PassThrough (bool extract_removed_indices=false)
 Constructor. More...
 
void setKeepOrganized (bool val)
 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 () const
 Obtain the value of the internal keep_organized_ parameter. More...
 
void setUserFilterValue (float val)
 Provide a value that the filtered points should be set to instead of removing them. 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 () const
 Get the name of the field used for filtering. More...
 
void setFilterLimits (const double &limit_min, const double &limit_max)
 Set the field filter limits. More...
 
void getFilterLimits (double &limit_min, double &limit_max) const
 Get the field filter limits (min/max) set by the user. 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). More...
 
void getFilterLimitsNegative (bool &limit_negative) const
 Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). More...
 
bool getFilterLimitsNegative () const
 Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). More...
 
- Public Member Functions inherited from pcl::Filter< pcl::PCLPointCloud2 >
 Filter (bool extract_removed_indices=false)
 Empty constructor. More...
 
virtual ~Filter ()
 Empty destructor. More...
 
IndicesConstPtr const 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 ()
 destructor. More...
 
void setInputCloud (const PCLPointCloud2ConstPtr &cloud)
 Provide a pointer to the input dataset. More...
 
PCLPointCloud2ConstPtr const 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...
 
IndicesPtr const getIndices () const
 Get a pointer to the vector of indices used. More...
 

Protected Member Functions

void applyFilter (PCLPointCloud2 &output)
 Abstract filter method. More...
 
- Protected Member Functions inherited from pcl::Filter< pcl::PCLPointCloud2 >
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 ()
 

Additional Inherited Members

- Public Types inherited from pcl::Filter< pcl::PCLPointCloud2 >
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
 
- Public Types inherited from pcl::PCLBase< pcl::PCLPointCloud2 >
typedef pcl::PCLPointCloud2 PCLPointCloud2
 
typedef boost::shared_ptr< PCLPointCloud2PCLPointCloud2Ptr
 
typedef boost::shared_ptr< PCLPointCloud2 const > PCLPointCloud2ConstPtr
 
typedef boost::shared_ptr< PointIndicesPointIndicesPtr
 
typedef boost::shared_ptr< PointIndices const > PointIndicesConstPtr
 
- Protected Attributes inherited from pcl::Filter< pcl::PCLPointCloud2 >
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< 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_
 

Detailed Description

template<>
class pcl::PassThrough< pcl::PCLPointCloud2 >

PassThrough uses the base Filter class methods to pass through all data that satisfies the user given constraints.

Author
Radu B. Rusu

Definition at line 228 of file passthrough.h.

Constructor & Destructor Documentation

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

Constructor.

Definition at line 239 of file passthrough.h.

References pcl::Filter< PointT >::filter_name_.

Member Function Documentation

void pcl::PassThrough< pcl::PCLPointCloud2 >::applyFilter ( PCLPointCloud2 output)
protectedvirtual

Abstract filter method.

The implementation needs to set output.{data, row_step, point_step, width, height, is_dense}.

Parameters
[out]outputthe resultant filtered point cloud

Implements pcl::Filter< pcl::PCLPointCloud2 >.

std::string const pcl::PassThrough< pcl::PCLPointCloud2 >::getFilterFieldName ( ) const
inline

Get the name of the field used for filtering.

Definition at line 292 of file passthrough.h.

void pcl::PassThrough< pcl::PCLPointCloud2 >::getFilterLimits ( double &  limit_min,
double &  limit_max 
) const
inline

Get the field filter limits (min/max) set by the user.

The default values are -FLT_MAX, FLT_MAX.

Parameters
[out]limit_minthe minimum allowed field value
[out]limit_maxthe maximum allowed field value

Definition at line 313 of file passthrough.h.

void pcl::PassThrough< pcl::PCLPointCloud2 >::getFilterLimitsNegative ( bool &  limit_negative) const
inline

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

Parameters
[out]limit_negativetrue if data outside the interval [min; max] is to be returned, false otherwise

Definition at line 333 of file passthrough.h.

bool pcl::PassThrough< pcl::PCLPointCloud2 >::getFilterLimitsNegative ( ) const
inline

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

Returns
true if data outside the interval [min; max] is to be returned, false otherwise

Definition at line 342 of file passthrough.h.

References pcl::PassThrough< PointT >::applyFilter(), pcl::FilterIndices< PointT >::keep_organized_, and pcl::FilterIndices< PointT >::user_filter_value_.

bool pcl::PassThrough< pcl::PCLPointCloud2 >::getKeepOrganized ( ) const
inline

Obtain the value of the internal keep_organized_ parameter.

Definition at line 264 of file passthrough.h.

References pcl::FilterIndices< PointT >::keep_organized_.

void pcl::PassThrough< pcl::PCLPointCloud2 >::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 will be discarded.

Parameters
[in]field_namethe name of the field that contains values used for filtering

Definition at line 285 of file passthrough.h.

void pcl::PassThrough< pcl::PCLPointCloud2 >::setFilterLimits ( const double &  limit_min,
const double &  limit_max 
)
inline

Set the field filter limits.

All points having field values outside this interval will be discarded.

Parameters
[in]limit_minthe minimum allowed field value
[in]limit_maxthe maximum allowed field value

Definition at line 302 of file passthrough.h.

void pcl::PassThrough< pcl::PCLPointCloud2 >::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.

Parameters
[in]limit_negativereturn data inside the interval (false) or outside (true)

Definition at line 324 of file passthrough.h.

void pcl::PassThrough< pcl::PCLPointCloud2 >::setKeepOrganized ( bool  val)
inline

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.

By default, points are removed.

Parameters
[in]valset to true whether the filtered points should be kept and set to a user given value (default: NaN)

Definition at line 257 of file passthrough.h.

References pcl::FilterIndices< PointT >::keep_organized_.

void pcl::PassThrough< pcl::PCLPointCloud2 >::setUserFilterValue ( float  val)
inline

Provide a value that the filtered points should be set to instead of removing them.

Used in conjunction with setKeepOrganized ().

Parameters
[in]valthe user given value that the filtered point dimensions should be set to

Definition at line 275 of file passthrough.h.

References pcl::FilterIndices< PointT >::user_filter_value_.


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