Point Cloud Library (PCL)
1.14.1-dev
|
Removes points with x, y, or z equal to NaN. More...
#include </__w/1/s/cuda/filters/include/pcl/cuda/filters/filter.h>
Public Types | |
using | PointCloud = typename PCLCUDABase< CloudT >::PointCloud |
using | PointCloudPtr = typename PointCloud::Ptr |
using | PointCloudConstPtr = typename PointCloud::ConstPtr |
Public Member Functions | |
Filter () | |
Empty constructor. More... | |
void | setFilterFieldName (const std::string &field_name) |
Provide the name of the field to be used for filtering data. More... | |
std::string const | getFilterFieldName () |
Get the name of the field used for filtering. More... | |
void | setFilterLimits (const double &limit_min, const double &limit_max) |
Set the field filter limits. More... | |
void | getFilterLimits (double &limit_min, double &limit_max) |
Get the field filter limits (min/max) set by the user. More... | |
void | setFilterLimitsNegative (const bool limit_negative) |
Set to true if we want to return the data outside the interval specified by setFilterLimits (min, max). More... | |
void | getFilterLimitsNegative (bool &limit_negative) |
Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). More... | |
bool | getFilterLimitsNegative () |
Get whether the data outside the interval (min/max) is to be returned (true) or inside (false). More... | |
void | filter (PointCloud &output) |
Calls the filtering method and returns the filtered dataset on the device. More... | |
Protected Member Functions | |
virtual void | applyFilter (PointCloud &output)=0 |
Abstract filter method. More... | |
const std::string & | getClassName () const |
Get a string representation of the name of this class. More... | |
Protected Attributes | |
std::string | filter_name_ |
The filter name. More... | |
std::string | filter_field_name_ |
The desired user filter field name. More... | |
double | filter_limit_min_ |
The minimum allowed filter value a point will be considered from. More... | |
double | filter_limit_max_ |
The maximum allowed filter value a point will be considered from. More... | |
bool | filter_limit_negative_ |
Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_). More... | |
Removes points with x, y, or z equal to NaN.
cloud_in | the input point cloud |
cloud_out | the input point cloud |
index | the mapping (ordered): cloud_out[i] = cloud_in[index[i]] |
Filter represents the base filter class. Some generic 3D operations that are applicable to all filters are defined here as static methods.
using pcl_cuda::Filter< CloudT >::PointCloud = typename PCLCUDABase<CloudT>::PointCloud |
using pcl_cuda::Filter< CloudT >::PointCloudConstPtr = typename PointCloud::ConstPtr |
using pcl_cuda::Filter< CloudT >::PointCloudPtr = typename PointCloud::Ptr |
|
inline |
|
protectedpure virtual |
Abstract filter method.
The implementation needs to set output.{points, width, height, is_dense}.
Implemented in pcl_cuda::VoxelGrid< PointCloudSOA< Device > >, pcl_cuda::VoxelGrid< PointCloudAOS< Device > >, pcl_cuda::VoxelGrid< CloudT >, pcl_cuda::PassThrough< PointCloudSOA< Device > >, pcl_cuda::PassThrough< PointCloudAOS< Device > >, and pcl_cuda::PassThrough< CloudT >.
Referenced by pcl_cuda::Filter< CloudT >::filter().
|
inline |
Calls the filtering method and returns the filtered dataset on the device.
output | the resultant filtered point cloud dataset on the device |
Definition at line 142 of file filter.h.
References pcl_cuda::Filter< CloudT >::applyFilter().
|
inlineprotected |
Get a string representation of the name of this class.
Definition at line 182 of file filter.h.
References pcl_cuda::Filter< CloudT >::filter_name_.
|
inline |
Get the name of the field used for filtering.
Definition at line 87 of file filter.h.
References pcl_cuda::Filter< CloudT >::filter_field_name_.
|
inline |
Get the field filter limits (min/max) set by the user.
The default values are std::numeric_limits<float>::lowest(), std::numeric_limits<float>::max().
limit_min | the minimum limit |
limit_max | the maximum limit |
Definition at line 107 of file filter.h.
References pcl_cuda::Filter< CloudT >::filter_limit_max_, and pcl_cuda::Filter< CloudT >::filter_limit_min_.
|
inline |
Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
Definition at line 136 of file filter.h.
References pcl_cuda::Filter< CloudT >::filter_limit_negative_.
|
inline |
Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
limit_negative | the limit_negative flag |
Definition at line 129 of file filter.h.
References pcl_cuda::Filter< CloudT >::filter_limit_negative_.
|
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.
field_name | the name of the field that contains values used for filtering |
Definition at line 83 of file filter.h.
References pcl_cuda::Filter< CloudT >::filter_field_name_.
|
inline |
Set the field filter limits.
All points having field values outside this interval will be discarded.
limit_min | the minimum allowed field value |
limit_max | the maximum allowed field value |
Definition at line 95 of file filter.h.
References pcl_cuda::Filter< CloudT >::filter_limit_max_, and pcl_cuda::Filter< CloudT >::filter_limit_min_.
|
inline |
Set to true if we want to return the data outside the interval specified by setFilterLimits (min, max).
Default: false.
limit_negative | return data inside the interval (false) or outside (true) |
Definition at line 118 of file filter.h.
References pcl_cuda::Filter< CloudT >::filter_limit_negative_.
|
protected |
The desired user filter field name.
Definition at line 162 of file filter.h.
Referenced by pcl_cuda::Filter< CloudT >::getFilterFieldName(), and pcl_cuda::Filter< CloudT >::setFilterFieldName().
|
protected |
The maximum allowed filter value a point will be considered from.
Definition at line 168 of file filter.h.
Referenced by pcl_cuda::Filter< CloudT >::getFilterLimits(), and pcl_cuda::Filter< CloudT >::setFilterLimits().
|
protected |
The minimum allowed filter value a point will be considered from.
Definition at line 165 of file filter.h.
Referenced by pcl_cuda::Filter< CloudT >::getFilterLimits(), and pcl_cuda::Filter< CloudT >::setFilterLimits().
|
protected |
Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_).
Default: false.
Definition at line 171 of file filter.h.
Referenced by pcl_cuda::Filter< CloudT >::getFilterLimitsNegative(), and pcl_cuda::Filter< CloudT >::setFilterLimitsNegative().
|
protected |
The filter name.
Definition at line 159 of file filter.h.
Referenced by pcl_cuda::Filter< CloudT >::getClassName(), pcl_cuda::PassThrough< CloudT >::PassThrough(), pcl_cuda::PassThrough< PointCloudAOS< Device > >::PassThrough(), pcl_cuda::PassThrough< PointCloudSOA< Device > >::PassThrough(), pcl_cuda::VoxelGrid< CloudT >::VoxelGrid(), pcl_cuda::VoxelGrid< PointCloudAOS< Device > >::VoxelGrid(), and pcl_cuda::VoxelGrid< PointCloudSOA< Device > >::VoxelGrid().