Point Cloud Library (PCL)  1.8.1-dev
grid_minimum.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2009-2012, Willow Garage, Inc.
6  * Copyright (c) 2012-, Open Perception, Inc.
7  * Copyright (c) 2014, RadiantBlue Technologies, Inc.
8  *
9  * All rights reserved.
10  *
11  * Redistribution and use in source and binary forms, with or without
12  * modification, are permitted provided that the following conditions
13  * are met:
14  *
15  * * Redistributions of source code must retain the above copyright
16  * notice, this list of conditions and the following disclaimer.
17  * * Redistributions in binary form must reproduce the above
18  * copyright notice, this list of conditions and the following
19  * disclaimer in the documentation and/or other materials provided
20  * with the distribution.
21  * * Neither the name of the copyright holder(s) nor the names of its
22  * contributors may be used to endorse or promote products derived
23  * from this software without specific prior written permission.
24  *
25  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
26  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
27  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
28  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
29  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
30  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
31  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
32  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
33  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
34  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
35  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
36  * POSSIBILITY OF SUCH DAMAGE.
37  *
38  * $Id$
39  *
40  */
41 
42 #ifndef PCL_FILTERS_VOXEL_GRID_MINIMUM_H_
43 #define PCL_FILTERS_VOXEL_GRID_MINIMUM_H_
44 
45 #include <pcl/filters/boost.h>
46 #include <pcl/filters/filter.h>
47 #include <pcl/filters/filter_indices.h>
48 
49 namespace pcl
50 {
51  /** \brief GridMinimum assembles a local 2D grid over a given PointCloud, and downsamples the data.
52  *
53  * The GridMinimum class creates a *2D grid* over the input point cloud
54  * data. Then, in each *cell* (i.e., 2D grid element), all the points
55  * present will be *downsampled* with the minimum z value. This grid minimum
56  * can be useful in a number of topographic processing tasks such as crudely
57  * estimating ground returns, especially under foliage.
58  *
59  * \author Bradley J Chambers
60  * \ingroup filters
61  */
62  template <typename PointT>
63  class GridMinimum: public FilterIndices<PointT>
64  {
65  protected:
70 
72 
73  public:
74  /** \brief Empty constructor. */
75  GridMinimum (const float resolution)
76  {
77  setResolution (resolution);
78  filter_name_ = "GridMinimum";
79  }
80 
81  /** \brief Destructor. */
82  virtual ~GridMinimum ()
83  {
84  }
85 
86  /** \brief Set the grid resolution.
87  * \param[in] resolution the grid resolution
88  */
89  inline void
90  setResolution (const float resolution)
91  {
92  resolution_ = resolution;
93  // Use multiplications instead of divisions
95  }
96 
97  /** \brief Get the grid resolution. */
98  inline float
99  getResolution () { return (resolution_); }
100 
101  protected:
102  /** \brief The resolution. */
103  float resolution_;
104 
105  /** \brief Internal resolution stored as 1/resolution_ for efficiency reasons. */
107 
108  /** \brief Downsample a Point Cloud using a 2D grid approach
109  * \param[out] output the resultant point cloud message
110  */
111  void
112  applyFilter (PointCloud &output);
113 
114  /** \brief Filtered results are indexed by an indices array.
115  * \param[out] indices The resultant indices.
116  */
117  void
118  applyFilter (std::vector<int> &indices)
119  {
120  applyFilterIndices (indices);
121  }
122 
123  /** \brief Filtered results are indexed by an indices array.
124  * \param[out] indices The resultant indices.
125  */
126  void
127  applyFilterIndices (std::vector<int> &indices);
128 
129  };
130 }
131 
132 #ifdef PCL_NO_PRECOMPILE
133 #include <pcl/filters/impl/grid_minimum.hpp>
134 #endif
135 
136 #endif //#ifndef PCL_FILTERS_VOXEL_GRID_MINIMUM_H_
137 
float inverse_resolution_
Internal resolution stored as 1/resolution_ for efficiency reasons.
Definition: grid_minimum.h:106
void setResolution(const float resolution)
Set the grid resolution.
Definition: grid_minimum.h:90
float resolution_
The resolution.
Definition: grid_minimum.h:103
float getResolution()
Get the grid resolution.
Definition: grid_minimum.h:99
GridMinimum assembles a local 2D grid over a given PointCloud, and downsamples the data...
Definition: grid_minimum.h:63
void applyFilterIndices(std::vector< int > &indices)
Filtered results are indexed by an indices array.
FilterIndices represents the base class for filters that are about binary point removal.
void applyFilter(std::vector< int > &indices)
Filtered results are indexed by an indices array.
Definition: grid_minimum.h:118
Filter represents the base filter class.
Definition: filter.h:84
virtual ~GridMinimum()
Destructor.
Definition: grid_minimum.h:82
FilterIndices< PointT >::PointCloud PointCloud
Definition: grid_minimum.h:71
std::string filter_name_
The filter name.
Definition: filter.h:166
GridMinimum(const float resolution)
Empty constructor.
Definition: grid_minimum.h:75
void applyFilter(PointCloud &output)
Downsample a Point Cloud using a 2D grid approach.