|
Point Cloud Library (PCL)
1.6.0
|
Filter represents the base filter class. More...
#include <pcl/filters/filter.h>


Public Types | |
| typedef sensor_msgs::PointCloud2 | PointCloud2 |
| typedef PointCloud2::Ptr | PointCloud2Ptr |
| typedef PointCloud2::ConstPtr | PointCloud2ConstPtr |
| typedef PointIndices::Ptr | PointIndicesPtr |
| typedef PointIndices::ConstPtr | PointIndicesConstPtr |
Public Member Functions | |
| Filter (bool extract_removed_indices=false) | |
| Empty constructor. | |
| IndicesConstPtr const | getRemovedIndices () |
| Get the point indices being removed. | |
| void | filter (PointCloud2 &output) |
| Calls the filtering method and returns the filtered dataset in output. | |
| void | setInputCloud (const PointCloud2ConstPtr &cloud) |
| Provide a pointer to the input dataset. | |
| PointCloud2ConstPtr const | getInputCloud () |
| Get a pointer to the input point cloud dataset. | |
| void | setIndices (const IndicesPtr &indices) |
| Provide a pointer to the vector of indices that represents the input data. | |
| void | setIndices (const PointIndicesConstPtr &indices) |
| Provide a pointer to the vector of indices that represents the input data. | |
| IndicesPtr const | getIndices () |
| Get a pointer to the vector of indices used. | |
Filter represents the base filter class.
All filters must inherit from this interface.
Reimplemented from pcl::PCLBase< sensor_msgs::PointCloud2 >.
Reimplemented in pcl::FilterIndices< sensor_msgs::PointCloud2 >, and pcl::ExtractIndices< sensor_msgs::PointCloud2 >.
Reimplemented from pcl::PCLBase< sensor_msgs::PointCloud2 >.
Reimplemented in pcl::ExtractIndices< sensor_msgs::PointCloud2 >.
Reimplemented from pcl::PCLBase< sensor_msgs::PointCloud2 >.
Reimplemented in pcl::ExtractIndices< sensor_msgs::PointCloud2 >.
typedef PointIndices::ConstPtr pcl::PCLBase< sensor_msgs::PointCloud2 >::PointIndicesConstPtr [inherited] |
Definition at line 280 of file pcl_base.h.
typedef PointIndices::Ptr pcl::PCLBase< sensor_msgs::PointCloud2 >::PointIndicesPtr [inherited] |
Definition at line 279 of file pcl_base.h.
| pcl::Filter< sensor_msgs::PointCloud2 >::Filter | ( | bool | extract_removed_indices = false | ) | [inline] |
| void pcl::Filter< sensor_msgs::PointCloud2 >::filter | ( | PointCloud2 & | output | ) |
Calls the filtering method and returns the filtered dataset in output.
| [out] | output | the resultant filtered point cloud dataset |
Reimplemented in pcl::FilterIndices< sensor_msgs::PointCloud2 >.
| IndicesPtr const pcl::PCLBase< sensor_msgs::PointCloud2 >::getIndices | ( | ) | [inline, inherited] |
Get a pointer to the vector of indices used.
Definition at line 329 of file pcl_base.h.
| PointCloud2ConstPtr const pcl::PCLBase< sensor_msgs::PointCloud2 >::getInputCloud | ( | ) | [inline, inherited] |
Get a pointer to the input point cloud dataset.
Definition at line 303 of file pcl_base.h.
| IndicesConstPtr const pcl::Filter< sensor_msgs::PointCloud2 >::getRemovedIndices | ( | ) | [inline] |
Get the point indices being removed.
Reimplemented in pcl::FilterIndices< sensor_msgs::PointCloud2 >.
| void pcl::PCLBase< sensor_msgs::PointCloud2 >::setIndices | ( | const IndicesPtr & | indices | ) | [inline, inherited] |
Provide a pointer to the vector of indices that represents the input data.
| indices | a pointer to the vector of indices that represents the input data. |
Definition at line 309 of file pcl_base.h.
| void pcl::PCLBase< sensor_msgs::PointCloud2 >::setIndices | ( | const PointIndicesConstPtr & | indices | ) | [inline, inherited] |
Provide a pointer to the vector of indices that represents the input data.
| indices | a pointer to the vector of indices that represents the input data. |
Definition at line 320 of file pcl_base.h.
| void pcl::PCLBase< sensor_msgs::PointCloud2 >::setInputCloud | ( | const PointCloud2ConstPtr & | cloud | ) | [inherited] |
Provide a pointer to the input dataset.
| cloud | the const boost shared pointer to a PointCloud message |
1.7.6.1