Point Cloud Library (PCL)  1.14.0-dev
filter.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  */
35 
36 #pragma once
37 
38 #include <pcl_cuda/pcl_cuda_base.h>
39 #include <limits>
40 
41 namespace pcl_cuda
42 {
43  /** \brief Removes points with x, y, or z equal to NaN
44  * \param cloud_in the input point cloud
45  * \param cloud_out the input point cloud
46  * \param index the mapping (ordered): cloud_out[i] = cloud_in[index[i]]
47  * \note The density of the point cloud is lost.
48  * \note Can be called with cloud_in == cloud_out
49  */
50 // template <typename PointT> void removeNaNFromPointCloud (const pcl::PointCloud<PointT> &cloud_in, pcl::PointCloud<PointT> &cloud_out, std::vector<int> &index);
51 
52  ////////////////////////////////////////////////////////////////////////////////////////////
53  /** \brief @b Filter represents the base filter class. Some generic 3D
54  * operations that are applicable to all filters are defined here as static
55  * methods.
56  */
57  template <typename CloudT>
58  class Filter : public PCLCUDABase<CloudT>
59  {
60  using PCLCUDABase<CloudT>::initCompute;
61  using PCLCUDABase<CloudT>::deinitCompute;
62 
63  public:
64  using PCLCUDABase<CloudT>::input_;
65 
66  using PointCloud = typename PCLCUDABase<CloudT>::PointCloud;
67  using PointCloudPtr = typename PointCloud::Ptr;
69 
70  /** \brief Empty constructor. */
72  filter_limit_min_ (std::numeric_limits<float>::lowest()),
73  filter_limit_max_ (std::numeric_limits<float>::max()),
75  {};
76 
77  /** \brief Provide the name of the field to be used for filtering data.
78  * In conjunction with \a setFilterLimits, points having values outside
79  * this interval will be discarded.
80  * \param field_name the name of the field that contains values used for filtering
81  */
82  inline void
83  setFilterFieldName (const std::string &field_name) { filter_field_name_ = field_name; }
84 
85  /** \brief Get the name of the field used for filtering. */
86  inline std::string const
88 
89  /** \brief Set the field filter limits. All points having field values
90  * outside this interval will be discarded.
91  * \param limit_min the minimum allowed field value
92  * \param limit_max the maximum allowed field value
93  */
94  inline void
95  setFilterLimits (const double &limit_min, const double &limit_max)
96  {
97  filter_limit_min_ = limit_min;
98  filter_limit_max_ = limit_max;
99  }
100 
101  /** \brief Get the field filter limits (min/max) set by the user.
102  * The default values are std::numeric_limits<float>::lowest(), std::numeric_limits<float>::max().
103  * \param limit_min the minimum limit
104  * \param limit_max the maximum limit
105  */
106  inline void
107  getFilterLimits (double &limit_min, double &limit_max)
108  {
109  limit_min = filter_limit_min_;
110  limit_max = filter_limit_max_;
111  }
112 
113  /** \brief Set to true if we want to return the data outside the interval
114  * specified by setFilterLimits (min, max). Default: false.
115  * \param limit_negative return data inside the interval (false) or outside (true)
116  */
117  inline void
118  setFilterLimitsNegative (const bool limit_negative)
119  {
120  filter_limit_negative_ = limit_negative;
121  }
122 
123  /** \brief Get whether the data outside the interval (min/max) is to be
124  * returned (true) or inside (false).
125  * \param limit_negative the limit_negative flag
126  */
127  PCL_DEPRECATED(1, 16, "use bool getFilterLimitsNegative() instead")
128  inline void
129  getFilterLimitsNegative (bool &limit_negative) { limit_negative = filter_limit_negative_; }
130 
131  /** \brief Get whether the data outside the interval (min/max) is to be
132  * returned (true) or inside (false).
133  * \return true if data \b outside the interval [min; max] is to be returned, false otherwise
134  */
135  inline bool
137 
138  /** \brief Calls the filtering method and returns the filtered dataset on the device
139  * \param output the resultant filtered point cloud dataset on the device
140  */
141  inline void
142  filter (PointCloud &output)
143  {
144  if (!initCompute ()) return;
145 
146  // Copy header at a minimum
147  //output.header = input_->header;
148  //output.sensor_origin_ = input_->sensor_origin_;
149  //output.sensor_orientation_ = input_->sensor_orientation_;
150 
151  // Apply the actual filter
152  applyFilter (output);
153 
154  deinitCompute ();
155  }
156 
157  protected:
158  /** \brief The filter name. */
159  std::string filter_name_;
160 
161  /** \brief The desired user filter field name. */
162  std::string filter_field_name_;
163 
164  /** \brief The minimum allowed filter value a point will be considered from. */
166 
167  /** \brief The maximum allowed filter value a point will be considered from. */
169 
170  /** \brief Set to true if we want to return the data outside (\a filter_limit_min_;\a filter_limit_max_). Default: false. */
172 
173  /** \brief Abstract filter method.
174  *
175  * The implementation needs to set output.{points, width, height, is_dense}.
176  */
177  virtual void
178  applyFilter (PointCloud &output) = 0;
179 
180  /** \brief Get a string representation of the name of this class. */
181  inline const std::string&
182  getClassName () const { return (filter_name_); }
183  };
184 }
shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:413
shared_ptr< const PointCloud< PointT > > ConstPtr
Definition: point_cloud.h:414
Removes points with x, y, or z equal to NaN.
Definition: filter.h:59
void setFilterLimitsNegative(const bool limit_negative)
Set to true if we want to return the data outside the interval specified by setFilterLimits (min,...
Definition: filter.h:118
bool filter_limit_negative_
Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_).
Definition: filter.h:171
typename PointCloud::ConstPtr PointCloudConstPtr
Definition: filter.h:68
std::string const getFilterFieldName()
Get the name of the field used for filtering.
Definition: filter.h:87
virtual void applyFilter(PointCloud &output)=0
Abstract filter method.
typename PointCloud::Ptr PointCloudPtr
Definition: filter.h:67
std::string filter_field_name_
The desired user filter field name.
Definition: filter.h:162
typename PCLCUDABase< CloudT >::PointCloud PointCloud
Definition: filter.h:66
void setFilterFieldName(const std::string &field_name)
Provide the name of the field to be used for filtering data.
Definition: filter.h:83
double filter_limit_max_
The maximum allowed filter value a point will be considered from.
Definition: filter.h:168
const std::string & getClassName() const
Get a string representation of the name of this class.
Definition: filter.h:182
Filter()
Empty constructor.
Definition: filter.h:71
void filter(PointCloud &output)
Calls the filtering method and returns the filtered dataset on the device.
Definition: filter.h:142
double filter_limit_min_
The minimum allowed filter value a point will be considered from.
Definition: filter.h:165
void setFilterLimits(const double &limit_min, const double &limit_max)
Set the field filter limits.
Definition: filter.h:95
void getFilterLimits(double &limit_min, double &limit_max)
Get the field filter limits (min/max) set by the user.
Definition: filter.h:107
std::string filter_name_
The filter name.
Definition: filter.h:159
bool getFilterLimitsNegative()
Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
Definition: filter.h:136
#define PCL_DEPRECATED(Major, Minor, Message)
macro for compatibility across compilers and help remove old deprecated items for the Major....
Definition: pcl_macros.h:156