Point Cloud Library (PCL)  1.7.1
List of all members | Public Types | Public Member Functions | Protected Member Functions
pcl::ExtractIndices< pcl::PCLPointCloud2 > Class Template Reference

ExtractIndices extracts a set of indices from a point cloud. More...

#include <pcl/filters/extract_indices.h>

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

Public Types

typedef pcl::PCLPointCloud2 PCLPointCloud2
 
typedef PCLPointCloud2::Ptr PCLPointCloud2Ptr
 
typedef PCLPointCloud2::ConstPtr PCLPointCloud2ConstPtr
 
- Public Types inherited from pcl::FilterIndices< pcl::PCLPointCloud2 >
typedef pcl::PCLPointCloud2 PCLPointCloud2
 
- 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
< PCLPointCloud2
PCLPointCloud2Ptr
 
typedef boost::shared_ptr
< PCLPointCloud2 const > 
PCLPointCloud2ConstPtr
 
typedef boost::shared_ptr
< PointIndices
PointIndicesPtr
 
typedef boost::shared_ptr
< PointIndices const > 
PointIndicesConstPtr
 

Public Member Functions

 ExtractIndices ()
 Empty constructor. More...
 
- Public Member Functions inherited from pcl::FilterIndices< pcl::PCLPointCloud2 >
 FilterIndices (bool extract_removed_indices=false)
 Constructor. More...
 
virtual ~FilterIndices ()
 Empty virtual destructor. More...
 
virtual void filter (PCLPointCloud2 &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< pcl::PCLPointCloud2 >
 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 (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 ()
 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 ()
 Get a pointer to the vector of indices used. More...
 

Protected Member Functions

void applyFilter (PCLPointCloud2 &output)
 Extract point indices into a separate PointCloud. More...
 
void applyFilter (std::vector< int > &indices)
 Extract point indices. More...
 

Additional Inherited Members

- Protected Attributes inherited from pcl::FilterIndices< pcl::PCLPointCloud2 >
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...
 

Detailed Description

template<>
class pcl::ExtractIndices< pcl::PCLPointCloud2 >

ExtractIndices extracts a set of indices from a point cloud.


Usage examples:

filter.setInputCloud (cloud_in);
filter.setIndices (indices_in);
// Extract the points in cloud_in referenced by indices_in as a separate point cloud:
filter.filter (*cloud_out);
// Retrieve indices to all points in cloud_in except those referenced by indices_in:
filter.setNegative (true);
filter.filter (*indices_out);
// The resulting cloud_out is identical to cloud_in, but all points referenced by indices_in are made NaN:
filter.setNegative (true);
filter.setKeepOrganized (true);
filter.filter (*cloud_out);
Note
Does not inherently remove NaNs from results, hence the extract_removed_indices_ system is not used.
Author
Radu Bogdan Rusu

Definition at line 161 of file extract_indices.h.

Member Typedef Documentation

Definition at line 164 of file extract_indices.h.

Definition at line 166 of file extract_indices.h.

Definition at line 165 of file extract_indices.h.

Constructor & Destructor Documentation

Empty constructor.

Definition at line 169 of file extract_indices.h.

Member Function Documentation

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

Extract point indices into a separate PointCloud.

Parameters
[out]outputthe resultant point cloud

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

void pcl::ExtractIndices< pcl::PCLPointCloud2 >::applyFilter ( std::vector< int > &  indices)
protectedvirtual

Extract point indices.

Parameters
indicesthe resultant indices

Implements pcl::FilterIndices< pcl::PCLPointCloud2 >.


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