Point Cloud Library (PCL) 1.12.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#pragma once
37
38#include <pcl_cuda/pcl_cuda_base.h>
39#include <float.h>
40
41namespace 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;
69
70 /** \brief Empty constructor. */
72 filter_limit_min_ (-FLT_MAX), filter_limit_max_ (FLT_MAX),
74 {};
75
76 /** \brief Provide the name of the field to be used for filtering data.
77 * In conjunction with \a setFilterLimits, points having values outside
78 * this interval will be discarded.
79 * \param field_name the name of the field that contains values used for filtering
80 */
81 inline void
82 setFilterFieldName (const std::string &field_name) { filter_field_name_ = field_name; }
83
84 /** \brief Get the name of the field used for filtering. */
85 inline std::string const
87
88 /** \brief Set the field filter limits. All points having field values
89 * outside this interval will be discarded.
90 * \param limit_min the minimum allowed field value
91 * \param limit_max the maximum allowed field value
92 */
93 inline void
94 setFilterLimits (const double &limit_min, const double &limit_max)
95 {
96 filter_limit_min_ = limit_min;
97 filter_limit_max_ = limit_max;
98 }
99
100 /** \brief Get the field filter limits (min/max) set by the user.
101 * The default values are -FLT_MAX, FLT_MAX.
102 * \param limit_min the minimum limit
103 * \param limit_max the maximum limit
104 */
105 inline void
106 getFilterLimits (double &limit_min, double &limit_max)
107 {
108 limit_min = filter_limit_min_;
109 limit_max = filter_limit_max_;
110 }
111
112 /** \brief Set to true if we want to return the data outside the interval
113 * specified by setFilterLimits (min, max). Default: false.
114 * \param limit_negative return data inside the interval (false) or outside (true)
115 */
116 inline void
117 setFilterLimitsNegative (const bool limit_negative)
118 {
119 filter_limit_negative_ = limit_negative;
120 }
121
122 /** \brief Get whether the data outside the interval (min/max) is to be
123 * returned (true) or inside (false).
124 * \param limit_negative the limit_negative flag
125 */
126 PCL_DEPRECATED(1, 16, "use bool getFilterLimitsNegative() instead")
127 inline void
128 getFilterLimitsNegative (bool &limit_negative) { limit_negative = filter_limit_negative_; }
129
130 /** \brief Get whether the data outside the interval (min/max) is to be
131 * returned (true) or inside (false).
132 * \return true if data \b outside the interval [min; max] is to be returned, false otherwise
133 */
134 inline bool
136
137 /** \brief Calls the filtering method and returns the filtered dataset on the device
138 * \param output the resultant filtered point cloud dataset on the device
139 */
140 inline void
142 {
143 if (!initCompute ()) return;
144
145 // Copy header at a minimum
146 //output.header = input_->header;
147 //output.sensor_origin_ = input_->sensor_origin_;
148 //output.sensor_orientation_ = input_->sensor_orientation_;
149
150 // Apply the actual filter
151 applyFilter (output);
152
153 deinitCompute ();
154 }
155
156 protected:
157 /** \brief The filter name. */
158 std::string filter_name_;
159
160 /** \brief The desired user filter field name. */
162
163 /** \brief The minimum allowed filter value a point will be considered from. */
165
166 /** \brief The maximum allowed filter value a point will be considered from. */
168
169 /** \brief Set to true if we want to return the data outside (\a filter_limit_min_;\a filter_limit_max_). Default: false. */
171
172 /** \brief Abstract filter method.
173 *
174 * The implementation needs to set output.{points, width, height, is_dense}.
175 */
176 virtual void
177 applyFilter (PointCloud &output) = 0;
178
179 /** \brief Get a string representation of the name of this class. */
180 inline const std::string&
181 getClassName () const { return (filter_name_); }
182 };
183}
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:117
bool filter_limit_negative_
Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_).
Definition: filter.h:170
typename PointCloud::ConstPtr PointCloudConstPtr
Definition: filter.h:68
std::string const getFilterFieldName()
Get the name of the field used for filtering.
Definition: filter.h:86
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:161
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:82
double filter_limit_max_
The maximum allowed filter value a point will be considered from.
Definition: filter.h:167
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:141
double filter_limit_min_
The minimum allowed filter value a point will be considered from.
Definition: filter.h:164
void setFilterLimits(const double &limit_min, const double &limit_max)
Set the field filter limits.
Definition: filter.h:94
void getFilterLimits(double &limit_min, double &limit_max)
Get the field filter limits (min/max) set by the user.
Definition: filter.h:106
std::string filter_name_
The filter name.
Definition: filter.h:158
const std::string & getClassName() const
Get a string representation of the name of this class.
Definition: filter.h:181
bool getFilterLimitsNegative()
Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
Definition: filter.h:135
#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