Point Cloud Library (PCL)  1.9.1
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 #ifndef PCL_CUDA_FILTER_H_
37 #define PCL_CUDA_FILTER_H_
38 
39 #include <pcl_cuda/pcl_cuda_base.h>
40 #include <float.h>
41 
42 namespace pcl_cuda
43 {
44  /** \brief Removes points with x, y, or z equal to NaN
45  * \param cloud_in the input point cloud
46  * \param cloud_out the input point cloud
47  * \param index the mapping (ordered): cloud_out.points[i] = cloud_in.points[index[i]]
48  * \note The density of the point cloud is lost.
49  * \note Can be called with cloud_in == cloud_out
50  */
51 // template <typename PointT> void removeNaNFromPointCloud (const pcl::PointCloud<PointT> &cloud_in, pcl::PointCloud<PointT> &cloud_out, std::vector<int> &index);
52 
53  ////////////////////////////////////////////////////////////////////////////////////////////
54  /** \brief @b Filter represents the base filter class. Some generic 3D
55  * operations that are applicable to all filters are defined here as static
56  * methods.
57  */
58  template <typename CloudT>
59  class Filter : public PCLCUDABase<CloudT>
60  {
61  using PCLCUDABase<CloudT>::initCompute;
62  using PCLCUDABase<CloudT>::deinitCompute;
63 
64  public:
65  using PCLCUDABase<CloudT>::input_;
66 
67  typedef typename PCLCUDABase<CloudT>::PointCloud PointCloud;
68  typedef typename PointCloud::Ptr PointCloudPtr;
70 
71  /** \brief Empty constructor. */
73  filter_limit_min_ (-FLT_MAX), filter_limit_max_ (FLT_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 -FLT_MAX, FLT_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  inline void
128  getFilterLimitsNegative (bool &limit_negative) { limit_negative = filter_limit_negative_; }
129  inline bool
131 
132  /** \brief Calls the filtering method and returns the filtered dataset on the device
133  * \param output the resultant filtered point cloud dataset on the device
134  */
135  inline void
136  filter (PointCloud &output)
137  {
138  if (!initCompute ()) return;
139 
140  // Copy header at a minimum
141  //output.header = input_->header;
142  //output.sensor_origin_ = input_->sensor_origin_;
143  //output.sensor_orientation_ = input_->sensor_orientation_;
144 
145  // Apply the actual filter
146  applyFilter (output);
147 
148  deinitCompute ();
149  }
150 
151  protected:
152  /** \brief The filter name. */
153  std::string filter_name_;
154 
155  /** \brief The desired user filter field name. */
156  std::string filter_field_name_;
157 
158  /** \brief The minimum allowed filter value a point will be considered from. */
160 
161  /** \brief The maximum allowed filter value a point will be considered from. */
163 
164  /** \brief Set to true if we want to return the data outside (\a filter_limit_min_;\a filter_limit_max_). Default: false. */
166 
167  /** \brief Abstract filter method.
168  *
169  * The implementation needs to set output.{points, width, height, is_dense}.
170  */
171  virtual void
172  applyFilter (PointCloud &output) = 0;
173 
174  /** \brief Get a string representation of the name of this class. */
175  inline const std::string&
176  getClassName () const { return (filter_name_); }
177  };
178 }
179 
180 #endif //#ifndef PCL_FILTER_H_
const std::string & getClassName() const
Get a string representation of the name of this class.
Definition: filter.h:176
virtual void applyFilter(PointCloud &output)=0
Abstract filter method.
void setFilterLimits(const double &limit_min, const double &limit_max)
Set the field filter limits.
Definition: filter.h:95
void filter(PointCloud &output)
Calls the filtering method and returns the filtered dataset on the device.
Definition: filter.h:136
boost::shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:428
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
double filter_limit_min_
The minimum allowed filter value a point will be considered from.
Definition: filter.h:159
bool filter_limit_negative_
Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_).
Definition: filter.h:165
double filter_limit_max_
The maximum allowed filter value a point will be considered from.
Definition: filter.h:162
PointCloud::Ptr PointCloudPtr
Definition: filter.h:68
Filter()
Empty constructor.
Definition: filter.h:72
bool getFilterLimitsNegative()
Definition: filter.h:130
boost::shared_ptr< const PointCloud< PointT > > ConstPtr
Definition: point_cloud.h:429
PCLCUDABase< CloudT >::PointCloud PointCloud
Definition: filter.h:67
Removes points with x, y, or z equal to NaN.
Definition: filter.h:59
void setFilterFieldName(const std::string &field_name)
Provide the name of the field to be used for filtering data.
Definition: filter.h:83
std::string const getFilterFieldName()
Get the name of the field used for filtering.
Definition: filter.h:87
void getFilterLimitsNegative(bool &limit_negative)
Get whether the data outside the interval (min/max) is to be returned (true) or inside (false)...
Definition: filter.h:128
std::string filter_name_
The filter name.
Definition: filter.h:153
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_field_name_
The desired user filter field name.
Definition: filter.h:156
PointCloud::ConstPtr PointCloudConstPtr
Definition: filter.h:69