Point Cloud Library (PCL)  1.11.0
approximate_voxel_grid.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, 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 the copyright holder(s) 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  * $Id: voxel_grid.h 1374 2011-06-19 02:29:56Z bouffa $
35  *
36  */
37 
38 #pragma once
39 
40 #include <pcl/filters/boost.h>
41 #include <pcl/filters/filter.h>
42 
43 namespace pcl
44 {
45  /** \brief Helper functor structure for copying data between an Eigen::VectorXf and a PointT. */
46  template <typename PointT>
48  {
49  using Pod = typename traits::POD<PointT>::type;
50 
51  xNdCopyEigenPointFunctor (const Eigen::VectorXf &p1, PointT &p2)
52  : p1_ (p1),
53  p2_ (reinterpret_cast<Pod&>(p2)),
54  f_idx_ (0) { }
55 
56  template<typename Key> inline void operator() ()
57  {
58  //boost::fusion::at_key<Key> (p2_) = p1_[f_idx_++];
60  std::uint8_t* data_ptr = reinterpret_cast<std::uint8_t*>(&p2_) + pcl::traits::offset<PointT, Key>::value;
61  *reinterpret_cast<T*>(data_ptr) = static_cast<T> (p1_[f_idx_++]);
62  }
63 
64  private:
65  const Eigen::VectorXf &p1_;
66  Pod &p2_;
67  int f_idx_;
68  };
69 
70  /** \brief Helper functor structure for copying data between an Eigen::VectorXf and a PointT. */
71  template <typename PointT>
73  {
74  using Pod = typename traits::POD<PointT>::type;
75 
76  xNdCopyPointEigenFunctor (const PointT &p1, Eigen::VectorXf &p2)
77  : p1_ (reinterpret_cast<const Pod&>(p1)), p2_ (p2), f_idx_ (0) { }
78 
79  template<typename Key> inline void operator() ()
80  {
81  //p2_[f_idx_++] = boost::fusion::at_key<Key> (p1_);
83  const std::uint8_t* data_ptr = reinterpret_cast<const std::uint8_t*>(&p1_) + pcl::traits::offset<PointT, Key>::value;
84  p2_[f_idx_++] = static_cast<float> (*reinterpret_cast<const T*>(data_ptr));
85  }
86 
87  private:
88  const Pod &p1_;
89  Eigen::VectorXf &p2_;
90  int f_idx_;
91  };
92 
93  /** \brief ApproximateVoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data.
94  *
95  * \author James Bowman, Radu B. Rusu
96  * \ingroup filters
97  */
98  template <typename PointT>
99  class ApproximateVoxelGrid: public Filter<PointT>
100  {
105 
106  using PointCloud = typename Filter<PointT>::PointCloud;
107  using PointCloudPtr = typename PointCloud::Ptr;
108  using PointCloudConstPtr = typename PointCloud::ConstPtr;
109 
110  private:
111  struct he
112  {
113  he () : ix (), iy (), iz (), count (0) {}
114  int ix, iy, iz;
115  int count;
116  Eigen::VectorXf centroid;
117  };
118 
119  public:
120 
121  using Ptr = shared_ptr<ApproximateVoxelGrid<PointT> >;
122  using ConstPtr = shared_ptr<const ApproximateVoxelGrid<PointT> >;
123 
124 
125  /** \brief Empty constructor. */
127  pcl::Filter<PointT> (),
128  leaf_size_ (Eigen::Vector3f::Ones ()),
129  inverse_leaf_size_ (Eigen::Array3f::Ones ()),
130  downsample_all_data_ (true), histsize_ (512),
131  history_ (new he[histsize_])
132  {
133  filter_name_ = "ApproximateVoxelGrid";
134  }
135 
136  /** \brief Copy constructor.
137  * \param[in] src the approximate voxel grid to copy into this.
138  */
140  pcl::Filter<PointT> (),
141  leaf_size_ (src.leaf_size_),
144  histsize_ (src.histsize_),
145  history_ ()
146  {
147  history_ = new he[histsize_];
148  for (std::size_t i = 0; i < histsize_; i++)
149  history_[i] = src.history_[i];
150  }
151 
152 
153  /** \brief Destructor.
154  */
156  {
157  delete [] history_;
158  }
159 
160 
161  /** \brief Copy operator.
162  * \param[in] src the approximate voxel grid to copy into this.
163  */
164  inline ApproximateVoxelGrid&
166  {
167  leaf_size_ = src.leaf_size_;
170  histsize_ = src.histsize_;
171  history_ = new he[histsize_];
172  for (std::size_t i = 0; i < histsize_; i++)
173  history_[i] = src.history_[i];
174  return (*this);
175  }
176 
177  /** \brief Set the voxel grid leaf size.
178  * \param[in] leaf_size the voxel grid leaf size
179  */
180  inline void
181  setLeafSize (const Eigen::Vector3f &leaf_size)
182  {
183  leaf_size_ = leaf_size;
184  inverse_leaf_size_ = Eigen::Array3f::Ones () / leaf_size_.array ();
185  }
186 
187  /** \brief Set the voxel grid leaf size.
188  * \param[in] lx the leaf size for X
189  * \param[in] ly the leaf size for Y
190  * \param[in] lz the leaf size for Z
191  */
192  inline void
193  setLeafSize (float lx, float ly, float lz)
194  {
195  setLeafSize (Eigen::Vector3f (lx, ly, lz));
196  }
197 
198  /** \brief Get the voxel grid leaf size. */
199  inline Eigen::Vector3f
200  getLeafSize () const { return (leaf_size_); }
201 
202  /** \brief Set to true if all fields need to be downsampled, or false if just XYZ.
203  * \param downsample the new value (true/false)
204  */
205  inline void
206  setDownsampleAllData (bool downsample) { downsample_all_data_ = downsample; }
207 
208  /** \brief Get the state of the internal downsampling parameter (true if
209  * all fields need to be downsampled, false if just XYZ).
210  */
211  inline bool
213 
214  protected:
215  /** \brief The size of a leaf. */
216  Eigen::Vector3f leaf_size_;
217 
218  /** \brief Compute 1/leaf_size_ to avoid division later */
219  Eigen::Array3f inverse_leaf_size_;
220 
221  /** \brief Set to true if all fields need to be downsampled, or false if just XYZ. */
223 
224  /** \brief history buffer size, power of 2 */
225  std::size_t histsize_;
226 
227  /** \brief history buffer */
228  struct he* history_;
229 
231 
232  /** \brief Downsample a Point Cloud using a voxelized grid approach
233  * \param output the resultant point cloud message
234  */
235  void
236  applyFilter (PointCloud &output) override;
237 
238  /** \brief Write a single point from the hash to the output cloud
239  */
240  void
241  flush (PointCloud &output, std::size_t op, he *hhe, int rgba_index, int centroid_size);
242  };
243 }
244 
245 #ifdef PCL_NO_PRECOMPILE
246 #include <pcl/filters/impl/approximate_voxel_grid.hpp>
247 #endif
pcl::xNdCopyEigenPointFunctor
Helper functor structure for copying data between an Eigen::VectorXf and a PointT.
Definition: approximate_voxel_grid.h:47
pcl::ApproximateVoxelGrid::setDownsampleAllData
void setDownsampleAllData(bool downsample)
Set to true if all fields need to be downsampled, or false if just XYZ.
Definition: approximate_voxel_grid.h:206
pcl
Definition: convolution.h:46
pcl::traits::offset
Definition: type_traits.h:168
Eigen
Definition: bfgs.h:9
pcl::PCLBase::PointCloudConstPtr
typename PointCloud::ConstPtr PointCloudConstPtr
Definition: pcl_base.h:74
pcl::PCLBase::PointCloudPtr
typename PointCloud::Ptr PointCloudPtr
Definition: pcl_base.h:73
pcl::traits::datatype
Definition: type_traits.h:180
pcl::ApproximateVoxelGrid::getLeafSize
Eigen::Vector3f getLeafSize() const
Get the voxel grid leaf size.
Definition: approximate_voxel_grid.h:200
pcl::xNdCopyPointEigenFunctor::operator()
void operator()()
Definition: approximate_voxel_grid.h:79
pcl::ApproximateVoxelGrid::FieldList
typename pcl::traits::fieldList< PointT >::type FieldList
Definition: approximate_voxel_grid.h:230
pcl::ApproximateVoxelGrid::downsample_all_data_
bool downsample_all_data_
Set to true if all fields need to be downsampled, or false if just XYZ.
Definition: approximate_voxel_grid.h:222
pcl::ApproximateVoxelGrid::history_
struct he * history_
history buffer
Definition: approximate_voxel_grid.h:228
pcl::PointCloud
PointCloud represents the base class in PCL for storing collections of 3D points.
Definition: projection_matrix.h:52
pcl::ApproximateVoxelGrid::ConstPtr
shared_ptr< const ApproximateVoxelGrid< PointT > > ConstPtr
Definition: approximate_voxel_grid.h:122
pcl::PointXYZRGB
A point structure representing Euclidean xyz coordinates, and the RGB color.
Definition: point_types.hpp:628
pcl::xNdCopyEigenPointFunctor::xNdCopyEigenPointFunctor
xNdCopyEigenPointFunctor(const Eigen::VectorXf &p1, PointT &p2)
Definition: approximate_voxel_grid.h:51
pcl::xNdCopyPointEigenFunctor::Pod
typename traits::POD< PointT >::type Pod
Definition: approximate_voxel_grid.h:74
pcl::ApproximateVoxelGrid::operator=
ApproximateVoxelGrid & operator=(const ApproximateVoxelGrid &src)
Copy operator.
Definition: approximate_voxel_grid.h:165
pcl::ApproximateVoxelGrid::ApproximateVoxelGrid
ApproximateVoxelGrid(const ApproximateVoxelGrid &src)
Copy constructor.
Definition: approximate_voxel_grid.h:139
pcl::ApproximateVoxelGrid::~ApproximateVoxelGrid
~ApproximateVoxelGrid()
Destructor.
Definition: approximate_voxel_grid.h:155
pcl::xNdCopyPointEigenFunctor::xNdCopyPointEigenFunctor
xNdCopyPointEigenFunctor(const PointT &p1, Eigen::VectorXf &p2)
Definition: approximate_voxel_grid.h:76
pcl::xNdCopyPointEigenFunctor
Helper functor structure for copying data between an Eigen::VectorXf and a PointT.
Definition: approximate_voxel_grid.h:72
pcl::ApproximateVoxelGrid::histsize_
std::size_t histsize_
history buffer size, power of 2
Definition: approximate_voxel_grid.h:225
pcl::ApproximateVoxelGrid::Ptr
shared_ptr< ApproximateVoxelGrid< PointT > > Ptr
Definition: approximate_voxel_grid.h:121
pcl::ApproximateVoxelGrid::ApproximateVoxelGrid
ApproximateVoxelGrid()
Empty constructor.
Definition: approximate_voxel_grid.h:126
pcl::xNdCopyEigenPointFunctor::operator()
void operator()()
Definition: approximate_voxel_grid.h:56
pcl::Filter
Filter represents the base filter class.
Definition: filter.h:83
pcl::ApproximateVoxelGrid::setLeafSize
void setLeafSize(float lx, float ly, float lz)
Set the voxel grid leaf size.
Definition: approximate_voxel_grid.h:193
pcl::Filter::filter_name_
std::string filter_name_
The filter name.
Definition: filter.h:161
pcl::PointCloud::Ptr
shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:428
pcl::ApproximateVoxelGrid::getDownsampleAllData
bool getDownsampleAllData() const
Get the state of the internal downsampling parameter (true if all fields need to be downsampled,...
Definition: approximate_voxel_grid.h:212
pcl::ApproximateVoxelGrid::leaf_size_
Eigen::Vector3f leaf_size_
The size of a leaf.
Definition: approximate_voxel_grid.h:216
pcl::ApproximateVoxelGrid::setLeafSize
void setLeafSize(const Eigen::Vector3f &leaf_size)
Set the voxel grid leaf size.
Definition: approximate_voxel_grid.h:181
pcl::uint8_t
std::uint8_t uint8_t
Definition: types.h:54
pcl::PointCloud::ConstPtr
shared_ptr< const PointCloud< PointT > > ConstPtr
Definition: point_cloud.h:429
pcl::xNdCopyEigenPointFunctor::Pod
typename traits::POD< PointT >::type Pod
Definition: approximate_voxel_grid.h:49
pcl::ApproximateVoxelGrid::flush
void flush(PointCloud &output, std::size_t op, he *hhe, int rgba_index, int centroid_size)
Write a single point from the hash to the output cloud.
Definition: approximate_voxel_grid.hpp:47
pcl::ApproximateVoxelGrid::inverse_leaf_size_
Eigen::Array3f inverse_leaf_size_
Compute 1/leaf_size_ to avoid division later.
Definition: approximate_voxel_grid.h:219
pcl::traits::fieldList
Definition: type_traits.h:194
pcl::ApproximateVoxelGrid::applyFilter
void applyFilter(PointCloud &output) override
Downsample a Point Cloud using a voxelized grid approach.
Definition: approximate_voxel_grid.hpp:65
pcl::ApproximateVoxelGrid
ApproximateVoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the...
Definition: approximate_voxel_grid.h:99