FilterIndices represents the base class for filters that are about binary point removal.
All derived classes have to implement the filter (PointCloud &output) and the filter (std::vector<int> &indices) methods. Ideally they also make use of the negative_, keep_organized_ and extract_removed_indices_ systems. The distinguishment between the negative_ and extract_removed_indices_ systems only makes sense if the class automatically filters non-finite entries in the filtering methods (recommended).
More...
#include <filter_indices.h>
Public Types | |
typedef sensor_msgs::PointCloud2 | PointCloud2 |
Public Member Functions | |
virtual void | filter (PointCloud2 &output) |
Calls the filtering method and returns the filtered dataset in output. | |
void | filter (std::vector< int > &indices) |
Calls the filtering method and returns the filtered point cloud indices. | |
FilterIndices (bool extract_removed_indices=false) | |
Constructor. | |
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. | |
bool | getNegative () |
Get whether the regular conditions for points filtering should apply, or the inverted conditions. | |
IndicesConstPtr const | getRemovedIndices () |
Get the point indices being removed. | |
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. | |
void | setNegative (bool negative) |
Set whether the regular conditions for points filtering should apply, or the inverted conditions. | |
void | setUserFilterValue (float value) |
Provide a value that the filtered points should be set to instead of removing them. Used in conjunction with setKeepOrganized (). | |
virtual | ~FilterIndices () |
Empty virtual destructor. | |
Protected Member Functions | |
virtual void | applyFilter (std::vector< int > &indices)=0 |
Abstract filter method for point cloud indices. | |
Protected Attributes | |
bool | extract_removed_indices_ |
Set to true if we want to return the indices of the removed points. | |
bool | keep_organized_ |
False = remove points (default), true = redefine points, keep structure. | |
bool | negative_ |
False = normal filter behavior (default), true = inverted behavior. | |
IndicesPtr | removed_indices_ |
Indices of the points that are removed. | |
float | user_filter_value_ |
The user given value that the filtered point dimensions should be set to (default = NaN). |
FilterIndices represents the base class for filters that are about binary point removal.
All derived classes have to implement the filter (PointCloud &output) and the filter (std::vector<int> &indices) methods. Ideally they also make use of the negative_, keep_organized_ and extract_removed_indices_ systems. The distinguishment between the negative_ and extract_removed_indices_ systems only makes sense if the class automatically filters non-finite entries in the filtering methods (recommended).
Definition at line 204 of file filter_indices.h.
typedef sensor_msgs::PointCloud2 pcl::FilterIndices< sensor_msgs::PointCloud2 >::PointCloud2 |
Reimplemented from pcl::Filter< sensor_msgs::PointCloud2 >.
Reimplemented in pcl::CropBox< sensor_msgs::PointCloud2 >, pcl::ExtractIndices< sensor_msgs::PointCloud2 >, and pcl::RandomSample< sensor_msgs::PointCloud2 >.
Definition at line 207 of file filter_indices.h.
pcl::FilterIndices< sensor_msgs::PointCloud2 >::FilterIndices | ( | bool | extract_removed_indices = false | ) | [inline] |
Constructor.
[in] | extract_removed_indices | Set to true if you want to extract the indices of points being removed (default = false). |
Definition at line 212 of file filter_indices.h.
virtual pcl::FilterIndices< sensor_msgs::PointCloud2 >::~FilterIndices | ( | ) | [inline, virtual] |
Empty virtual destructor.
Definition at line 223 of file filter_indices.h.
virtual void pcl::FilterIndices< sensor_msgs::PointCloud2 >::applyFilter | ( | std::vector< int > & | indices | ) | [protected, pure virtual] |
Abstract filter method for point cloud indices.
Implemented in pcl::CropBox< sensor_msgs::PointCloud2 >, pcl::RandomSample< sensor_msgs::PointCloud2 >, and pcl::ExtractIndices< sensor_msgs::PointCloud2 >.
virtual void pcl::FilterIndices< sensor_msgs::PointCloud2 >::filter | ( | PointCloud2 & | output | ) | [inline, virtual] |
Calls the filtering method and returns the filtered dataset in output.
Base method for feature estimation for all points given in <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ()
[out] | output | the resultant filtered point cloud dataset |
output | the resultant filtered point cloud dataset |
Reimplemented from pcl::Filter< sensor_msgs::PointCloud2 >.
Definition at line 228 of file filter_indices.h.
void pcl::FilterIndices< sensor_msgs::PointCloud2 >::filter | ( | std::vector< int > & | indices | ) |
Calls the filtering method and returns the filtered point cloud indices.
Base method for feature estimation for all points given in <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in setSearchMethod ()
[out] | indices | the resultant filtered point cloud indices |
output | the resultant filtered point cloud dataset |
Definition at line 50 of file filter_indices.cpp.
bool pcl::FilterIndices< sensor_msgs::PointCloud2 >::getKeepOrganized | ( | ) | [inline] |
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.
Definition at line 272 of file filter_indices.h.
bool pcl::FilterIndices< sensor_msgs::PointCloud2 >::getNegative | ( | ) | [inline] |
Get whether the regular conditions for points filtering should apply, or the inverted conditions.
Definition at line 252 of file filter_indices.h.
IndicesConstPtr const pcl::FilterIndices< sensor_msgs::PointCloud2 >::getRemovedIndices | ( | ) | [inline] |
Get the point indices being removed.
Reimplemented from pcl::Filter< sensor_msgs::PointCloud2 >.
Definition at line 291 of file filter_indices.h.
void pcl::FilterIndices< sensor_msgs::PointCloud2 >::setKeepOrganized | ( | bool | keep_organized | ) | [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.
[in] | keep_organized | false = remove points (default), true = redefine points, keep structure. |
Definition at line 262 of file filter_indices.h.
void pcl::FilterIndices< sensor_msgs::PointCloud2 >::setNegative | ( | bool | negative | ) | [inline] |
Set whether the regular conditions for points filtering should apply, or the inverted conditions.
[in] | negative | false = normal filter behavior (default), true = inverted behavior. |
Definition at line 243 of file filter_indices.h.
void pcl::FilterIndices< sensor_msgs::PointCloud2 >::setUserFilterValue | ( | float | value | ) | [inline] |
Provide a value that the filtered points should be set to instead of removing them. Used in conjunction with setKeepOrganized ().
[in] | value | the user given value that the filtered point dimensions should be set to (default = NaN). |
Definition at line 282 of file filter_indices.h.
bool pcl::FilterIndices< sensor_msgs::PointCloud2 >::extract_removed_indices_ [protected] |
Set to true if we want to return the indices of the removed points.
Reimplemented from pcl::Filter< sensor_msgs::PointCloud2 >.
Definition at line 304 of file filter_indices.h.
bool pcl::FilterIndices< sensor_msgs::PointCloud2 >::keep_organized_ [protected] |
False = remove points (default), true = redefine points, keep structure.
Definition at line 301 of file filter_indices.h.
bool pcl::FilterIndices< sensor_msgs::PointCloud2 >::negative_ [protected] |
False = normal filter behavior (default), true = inverted behavior.
Definition at line 298 of file filter_indices.h.
IndicesPtr pcl::FilterIndices< sensor_msgs::PointCloud2 >::removed_indices_ [protected] |
Indices of the points that are removed.
Reimplemented from pcl::Filter< sensor_msgs::PointCloud2 >.
Definition at line 310 of file filter_indices.h.
float pcl::FilterIndices< sensor_msgs::PointCloud2 >::user_filter_value_ [protected] |
The user given value that the filtered point dimensions should be set to (default = NaN).
Definition at line 307 of file filter_indices.h.