PassThrough uses the base Filter class methods to pass through all data that satisfies the user given constraints. More...
#include <passthrough.h>
Public Member Functions | |
std::string const | getFilterFieldName () |
Get the name of the field used for filtering. | |
void | getFilterLimits (double &limit_min, double &limit_max) |
Get the field filter limits (min/max) set by the user. The default values are -FLT_MAX, FLT_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). | |
bool | getKeepOrganized () |
Obtain the value of the internal keep_organized_ parameter. | |
PassThrough (bool extract_removed_indices=false) | |
Constructor. | |
void | setFilterFieldName (const std::string &field_name) |
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. | |
void | setFilterLimits (const double &limit_min, const double &limit_max) |
Set the field filter limits. All points having field values outside this interval will be discarded. | |
void | setFilterLimitsNegative (const bool limit_negative) |
Set to true if we want to return the data outside the interval specified by setFilterLimits (min, max). Default: false. | |
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. By default, points are removed. | |
void | setUserFilterValue (float val) |
Provide a value that the filtered points should be set to instead of removing them. Used in conjunction with setKeepOrganized (). | |
Protected Member Functions | |
void | applyFilter (PointCloud2 &output) |
Abstract filter method. | |
Private Types | |
typedef sensor_msgs::PointCloud2 | PointCloud2 |
typedef PointCloud2::ConstPtr | PointCloud2ConstPtr |
typedef PointCloud2::Ptr | PointCloud2Ptr |
Private Attributes | |
std::string | filter_field_name_ |
The desired user filter field name. | |
double | filter_limit_max_ |
The maximum allowed filter value a point will be considered from. | |
double | filter_limit_min_ |
The minimum allowed filter value a point will be considered from. | |
bool | filter_limit_negative_ |
Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_). Default: false. | |
bool | keep_organized_ |
Keep the structure of the data organized, by setting the filtered points to the a user given value (NaN by default). | |
float | user_filter_value_ |
User given value to be set to any filtered point. Casted to the correct field type. |
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 sensor_msgs::PointCloud2 pcl::PassThrough< sensor_msgs::PointCloud2 >::PointCloud2 [private] |
Reimplemented from pcl::Filter< sensor_msgs::PointCloud2 >.
Definition at line 226 of file passthrough.h.
typedef PointCloud2::ConstPtr pcl::PassThrough< sensor_msgs::PointCloud2 >::PointCloud2ConstPtr [private] |
Reimplemented from pcl::Filter< sensor_msgs::PointCloud2 >.
Definition at line 228 of file passthrough.h.
typedef PointCloud2::Ptr pcl::PassThrough< sensor_msgs::PointCloud2 >::PointCloud2Ptr [private] |
Reimplemented from pcl::Filter< sensor_msgs::PointCloud2 >.
Definition at line 227 of file passthrough.h.
pcl::PassThrough< sensor_msgs::PointCloud2 >::PassThrough | ( | bool | extract_removed_indices = false | ) | [inline] |
Constructor.
Definition at line 235 of file passthrough.h.
void pcl::PassThrough< sensor_msgs::PointCloud2 >::applyFilter | ( | PointCloud2 & | output | ) | [protected, virtual] |
Abstract filter method.
The implementation needs to set output.{data, row_step, point_step, width, height, is_dense}.
[out] | output | the resultant filtered point cloud |
Implements pcl::Filter< sensor_msgs::PointCloud2 >.
Definition at line 45 of file filters/src/passthrough.cpp.
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.
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.
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::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.
std::string pcl::PassThrough< sensor_msgs::PointCloud2 >::filter_field_name_ [private] |
The desired user filter field name.
Definition at line 359 of file passthrough.h.
double pcl::PassThrough< sensor_msgs::PointCloud2 >::filter_limit_max_ [private] |
The maximum allowed filter value a point will be considered from.
Definition at line 365 of file passthrough.h.
double pcl::PassThrough< sensor_msgs::PointCloud2 >::filter_limit_min_ [private] |
The minimum allowed filter value a point will be considered from.
Definition at line 362 of file passthrough.h.
bool pcl::PassThrough< sensor_msgs::PointCloud2 >::filter_limit_negative_ [private] |
Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_). Default: false.
Definition at line 368 of file passthrough.h.
bool pcl::PassThrough< sensor_msgs::PointCloud2 >::keep_organized_ [private] |
Keep the structure of the data organized, by setting the filtered points to the a user given value (NaN by default).
Definition at line 351 of file passthrough.h.
float pcl::PassThrough< sensor_msgs::PointCloud2 >::user_filter_value_ [private] |
User given value to be set to any filtered point. Casted to the correct field type.
Definition at line 356 of file passthrough.h.