|
Point Cloud Library (PCL)
1.6.0
|
PassThrough uses the base Filter class methods to pass through all data that satisfies the user given constraints. More...
#include <pcl/filters/passthrough.h>


Public Types | |
| typedef PointIndices::Ptr | PointIndicesPtr |
| typedef PointIndices::ConstPtr | PointIndicesConstPtr |
Public Member Functions | |
| PassThrough (bool extract_removed_indices=false) | |
| Constructor. | |
| 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. | |
| bool | getKeepOrganized () |
| Obtain the value of the internal keep_organized_ parameter. | |
| void | setUserFilterValue (float val) |
| Provide a value that the filtered points should be set to instead of removing them. | |
| void | setFilterFieldName (const std::string &field_name) |
| Provide the name of the field to be used for filtering data. | |
| std::string const | getFilterFieldName () |
| Get the name of the field used for filtering. | |
| void | setFilterLimits (const double &limit_min, const double &limit_max) |
| Set the field filter limits. | |
| void | getFilterLimits (double &limit_min, double &limit_max) |
| Get the field filter limits (min/max) set by the user. | |
| void | setFilterLimitsNegative (const bool limit_negative) |
| Set to true if we want to return the data outside the interval specified by setFilterLimits (min, max). | |
| void | getFilterLimitsNegative (bool &limit_negative) |
| Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). | |
| bool | getFilterLimitsNegative () |
| Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). | |
| 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. | |
PassThrough uses the base Filter class methods to pass through all data that satisfies the user given constraints.
Definition at line 224 of file passthrough.h.
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::PassThrough< sensor_msgs::PointCloud2 >::PassThrough | ( | bool | extract_removed_indices = false | ) | [inline] |
Constructor.
Definition at line 235 of file passthrough.h.
| void pcl::Filter< sensor_msgs::PointCloud2 >::filter | ( | PointCloud2 & | output | ) | [inherited] |
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 >.
| std::string const pcl::PassThrough< sensor_msgs::PointCloud2 >::getFilterFieldName | ( | ) | [inline] |
Get the name of the field used for filtering.
Definition at line 288 of file passthrough.h.
| void pcl::PassThrough< sensor_msgs::PointCloud2 >::getFilterLimits | ( | double & | limit_min, |
| double & | limit_max | ||
| ) | [inline] |
Get the field filter limits (min/max) set by the user.
The default values are -FLT_MAX, FLT_MAX.
| [out] | limit_min | the minimum allowed field value |
| [out] | limit_max | the maximum allowed field value |
Definition at line 309 of file passthrough.h.
| void pcl::PassThrough< sensor_msgs::PointCloud2 >::getFilterLimitsNegative | ( | bool & | limit_negative | ) | [inline] |
Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
| [out] | limit_negative | true if data outside the interval [min; max] is to be returned, false otherwise |
Definition at line 329 of file passthrough.h.
| bool pcl::PassThrough< sensor_msgs::PointCloud2 >::getFilterLimitsNegative | ( | ) | [inline] |
Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
Definition at line 338 of file passthrough.h.
| 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.
| bool pcl::PassThrough< sensor_msgs::PointCloud2 >::getKeepOrganized | ( | ) | [inline] |
Obtain the value of the internal keep_organized_ parameter.
Definition at line 260 of file passthrough.h.
| IndicesConstPtr const pcl::Filter< sensor_msgs::PointCloud2 >::getRemovedIndices | ( | ) | [inline, inherited] |
Get the point indices being removed.
Reimplemented in pcl::FilterIndices< sensor_msgs::PointCloud2 >.
| void pcl::PassThrough< sensor_msgs::PointCloud2 >::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.
| [in] | field_name | the name of the field that contains values used for filtering |
Definition at line 281 of file passthrough.h.
| void pcl::PassThrough< sensor_msgs::PointCloud2 >::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.
| [in] | limit_min | the minimum allowed field value |
| [in] | limit_max | the maximum allowed field value |
Definition at line 298 of file passthrough.h.
| void pcl::PassThrough< sensor_msgs::PointCloud2 >::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.
| [in] | limit_negative | return data inside the interval (false) or outside (true) |
Definition at line 320 of file passthrough.h.
| 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 |
| void pcl::PassThrough< sensor_msgs::PointCloud2 >::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.
| [in] | val | set to true whether the filtered points should be kept and set to a given user value (default: NaN) |
Definition at line 253 of file passthrough.h.
| void pcl::PassThrough< sensor_msgs::PointCloud2 >::setUserFilterValue | ( | float | val | ) | [inline] |
Provide a value that the filtered points should be set to instead of removing them.
Used in conjunction with setKeepOrganized ().
| [in] | val | the user given value that the filtered point dimensions should be set to |
Definition at line 271 of file passthrough.h.
1.7.6.1