Point Cloud Library (PCL)  1.14.1-dev
List of all members | Public Types | Public Member Functions | Protected Member Functions
pcl::ExtractIndices< pcl::PCLPointCloud2 > Class 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 >:
+ Collaboration diagram for pcl::ExtractIndices< pcl::PCLPointCloud2 >:

Public Types

using PCLPointCloud2 = pcl::PCLPointCloud2
 
using PCLPointCloud2Ptr = PCLPointCloud2::Ptr
 
using PCLPointCloud2ConstPtr = PCLPointCloud2::ConstPtr
 
- Public Types inherited from pcl::FilterIndices< pcl::PCLPointCloud2 >
using PCLPointCloud2 = pcl::PCLPointCloud2
 
- Public Types inherited from pcl::Filter< pcl::PCLPointCloud2 >
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

 ExtractIndices ()
 Empty constructor. More...
 
- Public Member Functions inherited from pcl::FilterIndices< pcl::PCLPointCloud2 >
 FilterIndices (bool extract_removed_indices=false)
 Constructor. More...
 
void filter (Indices &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 () const
 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 () const
 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...
 
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 ()=default
 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) override
 Extract point indices into a separate PointCloud. More...
 
void applyFilter (Indices &indices) override
 Extract point indices. 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

- Protected Attributes inherited from pcl::FilterIndices< pcl::PCLPointCloud2 >
bool negative_ {false}
 False = normal filter behavior (default), true = inverted behavior. More...
 
bool keep_organized_ {false}
 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< 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< uindex_tfield_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

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);
ExtractIndices extracts a set of indices from a point cloud.
void filter(Indices &indices)
Calls the filtering method and returns the filtered point cloud indices.
Note
Does not inherently remove NaNs from results, hence the extract_removed_indices_ system is not used.
Author
Radu Bogdan Rusu

Definition at line 160 of file extract_indices.h.

Member Typedef Documentation

◆ PCLPointCloud2

Definition at line 163 of file extract_indices.h.

◆ PCLPointCloud2ConstPtr

Definition at line 165 of file extract_indices.h.

◆ PCLPointCloud2Ptr

Definition at line 164 of file extract_indices.h.

Constructor & Destructor Documentation

◆ ExtractIndices()

Empty constructor.

Definition at line 168 of file extract_indices.h.

Member Function Documentation

◆ applyFilter() [1/2]

void pcl::ExtractIndices< pcl::PCLPointCloud2 >::applyFilter ( Indices indices)
overrideprotectedvirtual

Extract point indices.

Parameters
indicesthe resultant indices

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

◆ applyFilter() [2/2]

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

Extract point indices into a separate PointCloud.

Parameters
[out]outputthe resultant point cloud

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


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