voxel_grid.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2010-2011, Willow Garage, Inc.
6  *
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the copyright holder(s) nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * $Id$
37  *
38  */
39 
40 #ifndef PCL18_BACKPORTS_VOXEL_GRID_H
41 #define PCL18_BACKPORTS_VOXEL_GRID_H
42 
43 #ifndef BACKPORT_PCL_VOXEL_GRID
44 
45 #include <pcl/filters/voxel_grid.h>
46 
47 namespace pcl
48 {
49 template <typename PointT>
51 }
52 
53 #else
54 
55 // System has old PCL; backport VoxelGrid from pcl-1.8
56 
57 #include <algorithm>
58 #include <functional>
59 #include <limits>
60 #include <string>
61 #include <utility>
62 #include <vector>
63 
64 #include <pcl/common/centroid.h>
65 #include <pcl/filters/boost.h>
66 #include <pcl/filters/filter.h>
67 
68 namespace pcl
69 {
82 template <typename PointT>
83 class VoxelGrid18 : public Filter<PointT>
84 {
85 protected:
90 
91  typedef typename Filter<PointT>::PointCloud PointCloud;
92  typedef typename PointCloud::Ptr PointCloudPtr;
93  typedef typename PointCloud::ConstPtr PointCloudConstPtr;
94 
95 public:
98 
100  VoxelGrid18()
101  : leaf_size_(Eigen::Vector4f::Zero())
102  , inverse_leaf_size_(Eigen::Array4f::Zero())
103  , leaf_layout_()
104  , min_b_(Eigen::Vector4i::Zero())
105  , max_b_(Eigen::Vector4i::Zero())
106  , div_b_(Eigen::Vector4i::Zero())
107  , divb_mul_(Eigen::Vector4i::Zero())
108  , filter_limit_min_(-FLT_MAX)
109  , filter_limit_max_(FLT_MAX)
110  , filter_limit_negative_(false)
111  , min_points_per_voxel_(0)
112  {
113  filter_name_ = "VoxelGrid";
114  }
115 
117  virtual ~VoxelGrid18()
118  {
119  }
120 
124  inline void
125  setLeafSize(const Eigen::Vector4f& leaf_size)
126  {
127  leaf_size_ = leaf_size;
128  // Avoid division errors
129  if (leaf_size_[3] == 0)
130  leaf_size_[3] = 1;
131  // Use multiplications instead of divisions
132  inverse_leaf_size_ = Eigen::Array4f::Ones() / leaf_size_.array();
133  }
134 
140  inline void
141  setLeafSize(float lx, float ly, float lz)
142  {
143  leaf_size_[0] = lx;
144  leaf_size_[1] = ly;
145  leaf_size_[2] = lz;
146  // Avoid division errors
147  if (leaf_size_[3] == 0)
148  leaf_size_[3] = 1;
149  // Use multiplications instead of divisions
150  inverse_leaf_size_ = Eigen::Array4f::Ones() / leaf_size_.array();
151  }
152 
154  inline Eigen::Vector3f
155  getLeafSize() const
156  {
157  return (leaf_size_.head<3>());
158  }
159 
163  inline void
164  setMinimumPointsNumberPerVoxel(unsigned int min_points_per_voxel)
165  {
166  min_points_per_voxel_ = min_points_per_voxel;
167  }
168 
171  inline unsigned int
172  getMinimumPointsNumberPerVoxel() const
173  {
174  return min_points_per_voxel_;
175  }
176 
180  inline Eigen::Vector3i
181  getMinBoxCoordinates() const
182  {
183  return (min_b_.head<3>());
184  }
185 
189  inline Eigen::Vector3i
190  getMaxBoxCoordinates() const
191  {
192  return (max_b_.head<3>());
193  }
194 
198  inline Eigen::Vector3i
199  getNrDivisions() const
200  {
201  return (div_b_.head<3>());
202  }
203 
207  inline Eigen::Vector3i
208  getDivisionMultiplier() const
209  {
210  return (divb_mul_.head<3>());
211  }
212 
221  inline int
222  getCentroidIndex(const PointT& p) const
223  {
224  return (leaf_layout_.at((Eigen::Vector4i(static_cast<int>(floor(p.x * inverse_leaf_size_[0])),
225  static_cast<int>(floor(p.y * inverse_leaf_size_[1])),
226  static_cast<int>(floor(p.z * inverse_leaf_size_[2])), 0) -
227  min_b_)
228  .dot(divb_mul_)));
229  }
230 
237  inline std::vector<int>
238  getNeighborCentroidIndices(const PointT& reference_point, const Eigen::MatrixXi& relative_coordinates) const
239  {
240  Eigen::Vector4i ijk(static_cast<int>(floor(reference_point.x * inverse_leaf_size_[0])),
241  static_cast<int>(floor(reference_point.y * inverse_leaf_size_[1])),
242  static_cast<int>(floor(reference_point.z * inverse_leaf_size_[2])), 0);
243  Eigen::Array4i diff2min = min_b_ - ijk;
244  Eigen::Array4i diff2max = max_b_ - ijk;
245  std::vector<int> neighbors(relative_coordinates.cols());
246  for (int ni = 0; ni < relative_coordinates.cols(); ni++)
247  {
248  Eigen::Vector4i displacement = (Eigen::Vector4i() << relative_coordinates.col(ni), 0).finished();
249  // checking if the specified cell is in the grid
250  if ((diff2min <= displacement.array()).all() && (diff2max >= displacement.array()).all())
251  neighbors[ni] = leaf_layout_[((ijk + displacement - min_b_).dot(divb_mul_))]; // .at() can be omitted
252  else
253  neighbors[ni] = -1; // cell is out of bounds, consider it empty
254  }
255  return (neighbors);
256  }
257 
261  inline std::vector<int>
262  getLeafLayout() const
263  {
264  return (leaf_layout_);
265  }
266 
272  inline Eigen::Vector3i
273  getGridCoordinates(float x, float y, float z) const
274  {
275  return (Eigen::Vector3i(static_cast<int>(floor(x * inverse_leaf_size_[0])),
276  static_cast<int>(floor(y * inverse_leaf_size_[1])),
277  static_cast<int>(floor(z * inverse_leaf_size_[2]))));
278  }
279 
283  inline int
284  getCentroidIndexAt(const Eigen::Vector3i& ijk) const
285  {
286  int idx = ((Eigen::Vector4i() << ijk, 0).finished() - min_b_).dot(divb_mul_);
287  if (idx < 0 || idx >= static_cast<int>(leaf_layout_.size()))
288  // this checks also if leaf_layout_.size () == 0 i.e. everything was computed as needed
289  {
290  return (-1);
291  }
292  return (leaf_layout_[idx]);
293  }
294 
299  inline void
300  setFilterLimits(const double& limit_min, const double& limit_max)
301  {
302  filter_limit_min_ = limit_min;
303  filter_limit_max_ = limit_max;
304  }
305 
310  inline void
311  getFilterLimits(double& limit_min, double& limit_max) const
312  {
313  limit_min = filter_limit_min_;
314  limit_max = filter_limit_max_;
315  }
316 
321  inline void
322  setFilterLimitsNegative(const bool limit_negative)
323  {
324  filter_limit_negative_ = limit_negative;
325  }
326 
330  inline void
331  getFilterLimitsNegative(bool& limit_negative) const
332  {
333  limit_negative = filter_limit_negative_;
334  }
335 
339  inline bool
340  getFilterLimitsNegative() const
341  {
342  return (filter_limit_negative_);
343  }
344 
345 protected:
347  Eigen::Vector4f leaf_size_;
348 
350  Eigen::Array4f inverse_leaf_size_;
351 
353  std::vector<int> leaf_layout_;
354 
356  Eigen::Vector4i min_b_, max_b_, div_b_, divb_mul_;
357 
359  double filter_limit_min_;
360 
362  double filter_limit_max_;
363 
367 
369  unsigned int min_points_per_voxel_;
370 
371  typedef typename pcl::traits::fieldList<PointT>::type FieldList;
372 
376  void
377  applyFilter(PointCloud& output)
378  {
379  // Has the input dataset been set already?
380  if (!input_)
381  {
382  PCL_WARN("[pcl::%s::applyFilter] No input dataset given!\n", getClassName().c_str());
383  output.width = output.height = 0;
384  output.points.clear();
385  return;
386  }
387 
388  // Copy the header (and thus the frame_id) + allocate enough space for points
389  output.height = 1; // downsampling breaks the organized structure
390  output.is_dense = true; // we filter out invalid points
391 
392  Eigen::Vector4f min_p, max_p;
393  getMinMax3D<PointT>(*input_, *indices_, min_p, max_p);
394 
395  // Check that the leaf size is not too small, given the size of the data
396  int64_t dx = static_cast<int64_t>((max_p[0] - min_p[0]) * inverse_leaf_size_[0]) + 1;
397  int64_t dy = static_cast<int64_t>((max_p[1] - min_p[1]) * inverse_leaf_size_[1]) + 1;
398  int64_t dz = static_cast<int64_t>((max_p[2] - min_p[2]) * inverse_leaf_size_[2]) + 1;
399 
400  if ((dx * dy * dz) > static_cast<int64_t>(std::numeric_limits<int32_t>::max()))
401  {
402  PCL_WARN("[pcl::%s::applyFilter] Leaf size is too small for the input dataset. Integer indices would overflow.",
403  getClassName().c_str());
404  output = *input_;
405  return;
406  }
407 
408  // Compute the minimum and maximum bounding box values
409  min_b_[0] = static_cast<int>(floor(min_p[0] * inverse_leaf_size_[0]));
410  max_b_[0] = static_cast<int>(floor(max_p[0] * inverse_leaf_size_[0]));
411  min_b_[1] = static_cast<int>(floor(min_p[1] * inverse_leaf_size_[1]));
412  max_b_[1] = static_cast<int>(floor(max_p[1] * inverse_leaf_size_[1]));
413  min_b_[2] = static_cast<int>(floor(min_p[2] * inverse_leaf_size_[2]));
414  max_b_[2] = static_cast<int>(floor(max_p[2] * inverse_leaf_size_[2]));
415 
416  // Compute the number of divisions needed along all axis
417  div_b_ = max_b_ - min_b_ + Eigen::Vector4i::Ones();
418  div_b_[3] = 0;
419 
420  // Set up the division multiplier
421  divb_mul_ = Eigen::Vector4i(1, div_b_[0], div_b_[0] * div_b_[1], 0);
422 
423  // Storage for mapping leaf and pointcloud indexes
424  std::vector<cloud_point_index_idx> index_vector;
425  index_vector.reserve(indices_->size());
426 
427  // No distance filtering, process all data
428  // First pass: go over all points and insert them into the index_vector vector
429  // with calculated idx. Points with the same idx value will contribute to the
430  // same point of resulting CloudPoint
431  for (std::vector<int>::const_iterator it = indices_->begin(); it != indices_->end(); ++it)
432  {
433  if (!input_->is_dense)
434  // Check if the point is invalid
435  if (!pcl_isfinite(input_->points[*it].x) ||
436  !pcl_isfinite(input_->points[*it].y) ||
437  !pcl_isfinite(input_->points[*it].z))
438  continue;
439 
440  int ijk0 = static_cast<int>(
441  floor(input_->points[*it].x * inverse_leaf_size_[0]) - static_cast<float>(min_b_[0]));
442  int ijk1 = static_cast<int>(
443  floor(input_->points[*it].y * inverse_leaf_size_[1]) - static_cast<float>(min_b_[1]));
444  int ijk2 = static_cast<int>(
445  floor(input_->points[*it].z * inverse_leaf_size_[2]) - static_cast<float>(min_b_[2]));
446 
447  // Compute the centroid leaf index
448  int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
449  index_vector.push_back(cloud_point_index_idx(static_cast<unsigned int>(idx), *it));
450  }
451 
452  // Second pass: sort the index_vector vector using value representing target cell as index
453  // in effect all points belonging to the same output cell will be next to each other
454  std::sort(index_vector.begin(), index_vector.end(), std::less<cloud_point_index_idx>());
455 
456  // Third pass: count output cells
457  // we need to skip all the same, adjacent idx values
458  unsigned int total = 0;
459  unsigned int index = 0;
460  // first_and_last_indices_vector[i] represents the index in index_vector of the first point in
461  // index_vector belonging to the voxel which corresponds to the i-th output point,
462  // and of the first point not belonging to.
463  std::vector<std::pair<unsigned int, unsigned int>> first_and_last_indices_vector;
464  // Worst case size
465  first_and_last_indices_vector.reserve(index_vector.size());
466  while (index < index_vector.size())
467  {
468  unsigned int i = index + 1;
469  while (i < index_vector.size() && index_vector[i].idx == index_vector[index].idx)
470  ++i;
471  if (i - index >= min_points_per_voxel_)
472  {
473  ++total;
474  first_and_last_indices_vector.push_back(std::pair<unsigned int, unsigned int>(index, i));
475  }
476  index = i;
477  }
478 
479  // Fourth pass: compute centroids, insert them into their final position
480  output.points.resize(total);
481 
482  index = 0;
483  for (unsigned int cp = 0; cp < first_and_last_indices_vector.size(); ++cp)
484  {
485  // calculate centroid - sum values from all input points, that have the same idx value in index_vector array
486  unsigned int first_index = first_and_last_indices_vector[cp].first;
487  unsigned int last_index = first_and_last_indices_vector[cp].second;
488 
489  CentroidPoint<PointT> centroid;
490 
491  // fill in the accumulator with leaf points
492  for (unsigned int li = first_index; li < last_index; ++li)
493  centroid.add(input_->points[index_vector[li].cloud_point_index]);
494 
495  centroid.get(output.points[index]);
496 
497  ++index;
498  }
499  output.width = static_cast<uint32_t>(output.points.size());
500  }
501 };
502 } // namespace pcl
503 
504 #endif // BACKPORT_PCL_VOXEL_GRID
505 
506 #endif // PCL18_BACKPORTS_VOXEL_GRID_H
TFSIMD_FORCE_INLINE const tfScalar & y() const
double filter_limit_max_
doubleAcc dot(const VectorAcc &lhs, const VectorAcc &rhs)
VoxelGrid< PointT > VoxelGrid18
Definition: voxel_grid.h:50
TFSIMD_FORCE_INLINE const tfScalar & x() const
pcl::PointCloud< pcl::PointXYZ > PointCloud
TFSIMD_FORCE_INLINE const tfScalar & z() const
PointCloud::ConstPtr PointCloudConstPtr
double filter_limit_min_
bool filter_limit_negative_
PointCloud::Ptr PointCloudPtr


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Mon Jul 8 2019 03:32:36