pcl::Filter< sensor_msgs::PointCloud2 > Class Template Reference
Filter represents the base filter class. Some generic 3D operations that are applicable to all filters are defined here as static methods.
More...
#include <filter.h>
List of all members.
Public Types |
typedef sensor_msgs::PointCloud2 | PointCloud2 |
typedef PointCloud2::ConstPtr | PointCloud2ConstPtr |
typedef PointCloud2::Ptr | PointCloud2Ptr |
Public Member Functions |
void | filter (PointCloud2 &output) |
| Calls the filtering method and returns the filtered dataset in output.
|
| Filter () |
| Empty constructor.
|
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.
|
bool | getFilterLimitsNegative () |
void | getFilterLimitsNegative (bool &limit_negative) |
| Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
|
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.
|
Protected Member Functions |
virtual void | applyFilter (PointCloud2 &output)=0 |
| Abstract filter method.
|
const std::string & | getClassName () const |
| Get a string representation of the name of this class.
|
Protected 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.
|
std::string | filter_name_ |
| The filter name.
|
Detailed Description
template<>
class pcl::Filter< sensor_msgs::PointCloud2 >
Filter represents the base filter class. Some generic 3D operations that are applicable to all filters are defined here as static methods.
- Author:
- Radu Bogdan Rusu
Definition at line 175 of file filter.h.
Member Typedef Documentation
Constructor & Destructor Documentation
Empty constructor.
Definition at line 183 of file filter.h.
Member Function Documentation
Abstract filter method.
The implementation needs to set output.{data, row_step, point_step, width, height, is_dense}.
Implemented in pcl::ExtractIndices< sensor_msgs::PointCloud2 >, pcl::PassThrough< sensor_msgs::PointCloud2 >, pcl::ProjectInliers< sensor_msgs::PointCloud2 >, pcl::RadiusOutlierRemoval< sensor_msgs::PointCloud2 >, pcl::StatisticalOutlierRemoval< sensor_msgs::PointCloud2 >, and pcl::VoxelGrid< sensor_msgs::PointCloud2 >.
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 ().
- Parameters:
-
| output | the resultant filtered point cloud dataset |
Definition at line 63 of file filter.cpp.
Get a string representation of the name of this class.
Definition at line 254 of file filter.h.
Get the name of the field used for filtering.
Definition at line 195 of file filter.h.
Get the field filter limits (min/max) set by the user. The default values are -FLT_MAX, FLT_MAX.
Definition at line 210 of file filter.h.
Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
Definition at line 223 of file filter.h.
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.
- Parameters:
-
| field_name | the name of the field that contains values used for filtering |
Definition at line 192 of file filter.h.
Set the field filter limits. All points having field values outside this interval will be discarded.
- Parameters:
-
| limit_min | the minimum allowed field value |
| limit_max | the maximum allowed field value |
Definition at line 202 of file filter.h.
Set to true if we want to return the data outside the interval specified by setFilterLimits (min, max). Default: false.
- Parameters:
-
| limit_negative | return data inside the interval (false) or outside (true) |
Definition at line 220 of file filter.h.
Member Data Documentation
The desired user filter field name.
Definition at line 236 of file filter.h.
The maximum allowed filter value a point will be considered from.
Definition at line 242 of file filter.h.
The minimum allowed filter value a point will be considered from.
Definition at line 239 of file filter.h.
Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_). Default: false.
Definition at line 245 of file filter.h.
The filter name.
Definition at line 233 of file filter.h.
The documentation for this class was generated from the following files: