Point Cloud Library (PCL)  1.15.1-dev
voxel_grid.h
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 #pragma once
41 
42 #include <pcl/filters/filter.h>
43 #include <limits>
44 
45 namespace pcl
46 {
47  /** \brief Get the relative cell indices of the "upper half" 13 neighbors.
48  * \note Useful in combination with getNeighborCentroidIndices() from \ref VoxelGrid
49  * \ingroup filters
50  */
51  inline Eigen::MatrixXi
53  {
54  Eigen::MatrixXi relative_coordinates (3, 13);
55  int idx = 0;
56 
57  // 0 - 8
58  for (int i = -1; i < 2; i++)
59  {
60  for (int j = -1; j < 2; j++)
61  {
62  relative_coordinates (0, idx) = i;
63  relative_coordinates (1, idx) = j;
64  relative_coordinates (2, idx) = -1;
65  idx++;
66  }
67  }
68  // 9 - 11
69  for (int i = -1; i < 2; i++)
70  {
71  relative_coordinates (0, idx) = i;
72  relative_coordinates (1, idx) = -1;
73  relative_coordinates (2, idx) = 0;
74  idx++;
75  }
76  // 12
77  relative_coordinates (0, idx) = -1;
78  relative_coordinates (1, idx) = 0;
79  relative_coordinates (2, idx) = 0;
80 
81  return (relative_coordinates);
82  }
83 
84  /** \brief Get the relative cell indices of all the 26 neighbors.
85  * \note Useful in combination with getNeighborCentroidIndices() from \ref VoxelGrid
86  * \ingroup filters
87  */
88  inline Eigen::MatrixXi
90  {
91  Eigen::MatrixXi relative_coordinates = getHalfNeighborCellIndices ();
92  Eigen::MatrixXi relative_coordinates_all( 3, 26);
93  relative_coordinates_all.block<3, 13> (0, 0) = relative_coordinates;
94  relative_coordinates_all.block<3, 13> (0, 13) = -relative_coordinates;
95  return (relative_coordinates_all);
96  }
97 
98  /** \brief Obtain the maximum and minimum points in 3D from a given point cloud.
99  * \tparam T the coordinate type
100  * \param[in] cloud the pointer to a pcl::PCLPointCloud2 dataset
101  * \param[in] x_idx the index of the X channel
102  * \param[in] y_idx the index of the Y channel
103  * \param[in] z_idx the index of the Z channel
104  * \param[out] min_pt the minimum data point
105  * \param[out] max_pt the maximum data point
106  * \ingroup filters
107  */
108  template <typename T> void
109  getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx,
110  Eigen::Matrix<T, 4, 1> &min_pt, Eigen::Matrix<T, 4, 1> &max_pt);
111 
112  /** \brief Obtain the maximum and minimum points in 3D from a given point cloud.
113  * \tparam T the coordinate type
114  * \param[in] cloud the pointer to a pcl::PCLPointCloud2 dataset
115  * \param[in] indices the point cloud indices that need to be considered
116  * \param[in] x_idx the index of the X channel
117  * \param[in] y_idx the index of the Y channel
118  * \param[in] z_idx the index of the Z channel
119  * \param[out] min_pt the minimum data point
120  * \param[out] max_pt the maximum data point
121  * \ingroup filters
122  */
123  template <typename T> void
124  getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, const pcl::Indices &indices, int x_idx, int y_idx, int z_idx,
125  Eigen::Matrix<T, 4, 1> &min_pt, Eigen::Matrix<T, 4, 1> &max_pt);
126 
127 
128  /** \brief Obtain the maximum and minimum points in 3D from a given point cloud.
129  * \note Performs internal data filtering as well.
130  * \tparam T the coordinate type
131  * \tparam D the distance type
132  * \param[in] cloud the pointer to a pcl::PCLPointCloud2 dataset
133  * \param[in] x_idx the index of the X channel
134  * \param[in] y_idx the index of the Y channel
135  * \param[in] z_idx the index of the Z channel
136  * \param[in] distance_field_name the name of the dimension to filter data along to
137  * \param[in] min_distance the minimum acceptable value in \a distance_field_name data
138  * \param[in] max_distance the maximum acceptable value in \a distance_field_name data
139  * \param[out] min_pt the minimum data point
140  * \param[out] max_pt the maximum data point
141  * \param[in] limit_negative \b false if data \b inside of the [min_distance; max_distance] interval should be
142  * considered, \b true otherwise.
143  * \ingroup filters
144  */
145  template <typename T, typename D> void
146  getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx,
147  const std::string &distance_field_name, D min_distance, D max_distance,
148  Eigen::Matrix<T, 4, 1> &min_pt, Eigen::Matrix<T, 4, 1> &max_pt, bool limit_negative = false);
149 
150 
151  /** \brief Obtain the maximum and minimum points in 3D from a given point cloud.
152  * \note Performs internal data filtering as well.
153  * \tparam T the coordinate type
154  * \tparam D the distance type
155  * \param[in] cloud the pointer to a pcl::PCLPointCloud2 dataset
156  * \param[in] indices the point cloud indices that need to be considered
157  * \param[in] x_idx the index of the X channel
158  * \param[in] y_idx the index of the Y channel
159  * \param[in] z_idx the index of the Z channel
160  * \param[in] distance_field_name the name of the dimension to filter data along to
161  * \param[in] min_distance the minimum acceptable value in \a distance_field_name data
162  * \param[in] max_distance the maximum acceptable value in \a distance_field_name data
163  * \param[out] min_pt the minimum data point
164  * \param[out] max_pt the maximum data point
165  * \param[in] limit_negative \b false if data \b inside of the [min_distance; max_distance] interval should be
166  * considered, \b true otherwise.
167  * \ingroup filters
168  */
169  template <typename T, typename D> void
170  getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, const pcl::Indices &indices, int x_idx, int y_idx, int z_idx, const std::string &distance_field_name, D min_distance, D max_distance,
171  Eigen::Matrix<T, 4, 1> &min_pt, Eigen::Matrix<T, 4, 1> &max_pt, bool limit_negative = false);
172 
173 
174  /** \brief Get the minimum and maximum values on each of the 3 (x-y-z) dimensions
175  * in a given pointcloud, without considering points outside of a distance threshold from the laser origin
176  * \param[in] cloud the point cloud data message
177  * \param[in] distance_field_name the field name that contains the distance values
178  * \param[in] min_distance the minimum distance a point will be considered from
179  * \param[in] max_distance the maximum distance a point will be considered to
180  * \param[out] min_pt the resultant minimum bounds
181  * \param[out] max_pt the resultant maximum bounds
182  * \param[in] limit_negative if set to true, then all points outside of the interval (min_distance;max_distace) are considered
183  * \ingroup filters
184  */
185  template <typename PointT> void
186  getMinMax3D (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
187  const std::string &distance_field_name, float min_distance, float max_distance,
188  Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative = false);
189 
190  /** \brief Get the minimum and maximum values on each of the 3 (x-y-z) dimensions
191  * in a given pointcloud, without considering points outside of a distance threshold from the laser origin
192  * \param[in] cloud the point cloud data message
193  * \param[in] indices the vector of indices to use
194  * \param[in] distance_field_name the field name that contains the distance values
195  * \param[in] min_distance the minimum distance a point will be considered from
196  * \param[in] max_distance the maximum distance a point will be considered to
197  * \param[out] min_pt the resultant minimum bounds
198  * \param[out] max_pt the resultant maximum bounds
199  * \param[in] limit_negative if set to true, then all points outside of the interval (min_distance;max_distace) are considered
200  * \ingroup filters
201  */
202  template <typename PointT> void
203  getMinMax3D (const typename pcl::PointCloud<PointT>::ConstPtr &cloud,
204  const Indices &indices,
205  const std::string &distance_field_name, float min_distance, float max_distance,
206  Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative = false);
207 
208  /** \brief VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data.
209  *
210  * The VoxelGrid class creates a *3D voxel grid* (think about a voxel
211  * grid as a set of tiny 3D boxes in space) over the input point cloud data.
212  * Then, in each *voxel* (i.e., 3D box), all the points present will be
213  * approximated (i.e., *downsampled*) with their centroid. This approach is
214  * a bit slower than approximating them with the center of the voxel, but it
215  * represents the underlying surface more accurately.
216  *
217  * \author Radu B. Rusu, Bastian Steder
218  * \ingroup filters
219  */
220  template <typename PointT>
221  class VoxelGrid: public Filter<PointT>
222  {
223  protected:
228 
230  using PointCloudPtr = typename PointCloud::Ptr;
232 
233  public:
234 
235  using Ptr = shared_ptr<VoxelGrid<PointT> >;
236  using ConstPtr = shared_ptr<const VoxelGrid<PointT> >;
237 
239 
240  /** \brief Empty constructor. */
242  leaf_size_ (Eigen::Vector4f::Zero ()),
243  inverse_leaf_size_ (Eigen::Array4f::Zero ()),
244  min_b_ (Eigen::Vector4i::Zero ()),
245  max_b_ (Eigen::Vector4i::Zero ()),
246  div_b_ (Eigen::Vector4i::Zero ()),
247  divb_mul_ (Eigen::Vector4i::Zero ())
248  {
249  filter_name_ = "VoxelGrid";
250  }
251 
252  /** \brief Destructor. */
253  ~VoxelGrid () override = default;
254 
255  /** \brief Set the voxel grid leaf size.
256  * \param[in] leaf_size the voxel grid leaf size
257  */
258  inline void
259  setLeafSize (const Eigen::Vector4f &leaf_size)
260  {
261  leaf_size_ = leaf_size;
262  // Avoid division errors
263  if (leaf_size_[3] == 0)
264  leaf_size_[3] = 1;
265  // Use multiplications instead of divisions
266  inverse_leaf_size_ = Eigen::Array4f::Ones () / leaf_size_.array ();
267  }
268 
269  /** \brief Set the voxel grid leaf size.
270  * \param[in] lx the leaf size for X
271  * \param[in] ly the leaf size for Y
272  * \param[in] lz the leaf size for Z
273  */
274  inline void
275  setLeafSize (float lx, float ly, float lz)
276  {
277  leaf_size_[0] = lx; leaf_size_[1] = ly; leaf_size_[2] = lz;
278  // Avoid division errors
279  if (leaf_size_[3] == 0)
280  leaf_size_[3] = 1;
281  // Use multiplications instead of divisions
282  inverse_leaf_size_ = Eigen::Array4f::Ones () / leaf_size_.array ();
283  }
284 
285  /** \brief Get the voxel grid leaf size. */
286  inline Eigen::Vector3f
287  getLeafSize () const { return (leaf_size_.head<3> ()); }
288 
289  /** \brief Set to true if all fields need to be downsampled, or false if just XYZ.
290  * \param[in] downsample the new value (true/false)
291  */
292  inline void
293  setDownsampleAllData (bool downsample) { downsample_all_data_ = downsample; }
294 
295  /** \brief Get the state of the internal downsampling parameter (true if
296  * all fields need to be downsampled, false if just XYZ).
297  */
298  inline bool
300 
301  /** \brief Set the minimum number of points required for a voxel to be used.
302  * \param[in] min_points_per_voxel the minimum number of points for required for a voxel to be used
303  */
304  inline void
305  setMinimumPointsNumberPerVoxel (unsigned int min_points_per_voxel) { min_points_per_voxel_ = min_points_per_voxel; }
306 
307  /** \brief Return the minimum number of points required for a voxel to be used.
308  */
309  inline unsigned int
311 
312  /** \brief Set to true if leaf layout information needs to be saved for later access.
313  * \param[in] save_leaf_layout the new value (true/false)
314  */
315  inline void
316  setSaveLeafLayout (bool save_leaf_layout) { save_leaf_layout_ = save_leaf_layout; }
317 
318  /** \brief Returns true if leaf layout information will to be saved for later access. */
319  inline bool
320  getSaveLeafLayout () const { return (save_leaf_layout_); }
321 
322  /** \brief Get the minimum coordinates of the bounding box (after
323  * filtering is performed).
324  */
325  inline Eigen::Vector3i
326  getMinBoxCoordinates () const { return (min_b_.head<3> ()); }
327 
328  /** \brief Get the minimum coordinates of the bounding box (after
329  * filtering is performed).
330  */
331  inline Eigen::Vector3i
332  getMaxBoxCoordinates () const { return (max_b_.head<3> ()); }
333 
334  /** \brief Get the number of divisions along all 3 axes (after filtering
335  * is performed).
336  */
337  inline Eigen::Vector3i
338  getNrDivisions () const { return (div_b_.head<3> ()); }
339 
340  /** \brief Get the multipliers to be applied to the grid coordinates in
341  * order to find the centroid index (after filtering is performed).
342  */
343  inline Eigen::Vector3i
344  getDivisionMultiplier () const { return (divb_mul_.head<3> ()); }
345 
346  /** \brief Returns the index in the resulting downsampled cloud of the specified point.
347  *
348  * \note for efficiency, user must make sure that the saving of the leaf layout is enabled and filtering
349  * performed, and that the point is inside the grid, to avoid invalid access (or use
350  * getGridCoordinates+getCentroidIndexAt)
351  *
352  * \param[in] p the point to get the index at
353  */
354  inline int
355  getCentroidIndex (const PointT &p) const
356  {
357  return (leaf_layout_.at ((Eigen::Vector4i (static_cast<int> (std::floor (p.x * inverse_leaf_size_[0])),
358  static_cast<int> (std::floor (p.y * inverse_leaf_size_[1])),
359  static_cast<int> (std::floor (p.z * inverse_leaf_size_[2])), 0) - min_b_).dot (divb_mul_)));
360  }
361 
362  /** \brief Returns the indices in the resulting downsampled cloud of the points at the specified grid coordinates,
363  * relative to the grid coordinates of the specified point (or -1 if the cell was empty/out of bounds).
364  * \param[in] reference_point the coordinates of the reference point (corresponding cell is allowed to be empty/out of bounds)
365  * \param[in] relative_coordinates matrix with the columns being the coordinates of the requested cells, relative to the reference point's cell
366  * \note for efficiency, user must make sure that the saving of the leaf layout is enabled and filtering performed
367  */
368  inline std::vector<int>
369  getNeighborCentroidIndices (const PointT &reference_point, const Eigen::MatrixXi &relative_coordinates) const
370  {
371  Eigen::Vector4i ijk (static_cast<int> (std::floor (reference_point.x * inverse_leaf_size_[0])),
372  static_cast<int> (std::floor (reference_point.y * inverse_leaf_size_[1])),
373  static_cast<int> (std::floor (reference_point.z * inverse_leaf_size_[2])), 0);
374  Eigen::Array4i diff2min = min_b_ - ijk;
375  Eigen::Array4i diff2max = max_b_ - ijk;
376  std::vector<int> neighbors (relative_coordinates.cols());
377  for (Eigen::Index ni = 0; ni < relative_coordinates.cols (); ni++)
378  {
379  Eigen::Vector4i displacement = (Eigen::Vector4i() << relative_coordinates.col(ni), 0).finished();
380  // checking if the specified cell is in the grid
381  if ((diff2min <= displacement.array()).all() && (diff2max >= displacement.array()).all())
382  neighbors[ni] = leaf_layout_[((ijk + displacement - min_b_).dot (divb_mul_))]; // .at() can be omitted
383  else
384  neighbors[ni] = -1; // cell is out of bounds, consider it empty
385  }
386  return (neighbors);
387  }
388 
389  /** \brief Returns the layout of the leafs for fast access to cells relative to current position.
390  * \note position at (i-min_x) + (j-min_y)*div_x + (k-min_z)*div_x*div_y holds the index of the element at coordinates (i,j,k) in the grid (-1 if empty)
391  */
392  inline std::vector<int>
393  getLeafLayout () const { return (leaf_layout_); }
394 
395  /** \brief Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z).
396  * \param[in] x the X point coordinate to get the (i, j, k) index at
397  * \param[in] y the Y point coordinate to get the (i, j, k) index at
398  * \param[in] z the Z point coordinate to get the (i, j, k) index at
399  */
400  inline Eigen::Vector3i
401  getGridCoordinates (float x, float y, float z) const
402  {
403  return {static_cast<int> (std::floor (x * inverse_leaf_size_[0])),
404  static_cast<int> (std::floor (y * inverse_leaf_size_[1])),
405  static_cast<int> (std::floor (z * inverse_leaf_size_[2]))};
406  }
407 
408  /** \brief Returns the index in the downsampled cloud corresponding to a given set of coordinates.
409  * \param[in] ijk the coordinates (i,j,k) in the grid (-1 if empty)
410  */
411  inline int
412  getCentroidIndexAt (const Eigen::Vector3i &ijk) const
413  {
414  int idx = ((Eigen::Vector4i() << ijk, 0).finished() - min_b_).dot (divb_mul_);
415  if (idx < 0 || idx >= static_cast<int> (leaf_layout_.size ())) // this checks also if leaf_layout_.size () == 0 i.e. everything was computed as needed
416  {
417  //if (verbose)
418  // PCL_ERROR ("[pcl::%s::getCentroidIndexAt] Specified coordinate is outside grid bounds, or leaf layout is not saved, make sure to call setSaveLeafLayout(true) and filter(output) first!\n", getClassName ().c_str ());
419  return (-1);
420  }
421  return (leaf_layout_[idx]);
422  }
423 
424  /** \brief Provide the name of the field to be used for filtering data. In conjunction with \a setFilterLimits,
425  * points having values outside this interval will be discarded.
426  * \param[in] field_name the name of the field that contains values used for filtering
427  */
428  inline void
429  setFilterFieldName (const std::string &field_name)
430  {
431  filter_field_name_ = field_name;
432  }
433 
434  /** \brief Get the name of the field used for filtering. */
435  inline std::string const
437  {
438  return (filter_field_name_);
439  }
440 
441  /** \brief Set the field filter limits. All points having field values outside this interval will be discarded.
442  * \param[in] limit_min the minimum allowed field value
443  * \param[in] limit_max the maximum allowed field value
444  */
445  inline void
446  setFilterLimits (const double &limit_min, const double &limit_max)
447  {
448  filter_limit_min_ = limit_min;
449  filter_limit_max_ = limit_max;
450  }
451 
452  /** \brief Get the field filter limits (min/max) set by the user.
453  The default values are std::numeric_limits<float>::lowest(), std::numeric_limits<float>::max().
454  * \param[out] limit_min the minimum allowed field value
455  * \param[out] limit_max the maximum allowed field value
456  */
457  inline void
458  getFilterLimits (double &limit_min, double &limit_max) const
459  {
460  limit_min = filter_limit_min_;
461  limit_max = filter_limit_max_;
462  }
463 
464  /** \brief Set to true if we want to return the data outside the interval specified by setFilterLimits (min, max).
465  * Default: false.
466  * \param[in] limit_negative return data inside the interval (false) or outside (true)
467  */
468  inline void
469  setFilterLimitsNegative (const bool limit_negative)
470  {
471  filter_limit_negative_ = limit_negative;
472  }
473 
474  /** \brief Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
475  * \param[out] limit_negative true if data \b outside the interval [min; max] is to be returned, false otherwise
476  */
477  PCL_DEPRECATED(1, 16, "use bool getFilterLimitsNegative() instead")
478  inline void
479  getFilterLimitsNegative (bool &limit_negative) const
480  {
481  limit_negative = filter_limit_negative_;
482  }
483 
484  /** \brief Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
485  * \return true if data \b outside the interval [min; max] is to be returned, false otherwise
486  */
487  inline bool
489  {
490  return (filter_limit_negative_);
491  }
492 
493  protected:
494  /** \brief The size of a leaf. */
495  Eigen::Vector4f leaf_size_;
496 
497  /** \brief Internal leaf sizes stored as 1/leaf_size_ for efficiency reasons. */
498  Eigen::Array4f inverse_leaf_size_;
499 
500  /** \brief Set to true if all fields need to be downsampled, or false if just XYZ. */
502 
503  /** \brief Set to true if leaf layout information needs to be saved in \a leaf_layout_. */
504  bool save_leaf_layout_{false};
505 
506  /** \brief The leaf layout information for fast access to cells relative to current position **/
507  std::vector<int> leaf_layout_;
508 
509  /** \brief The minimum and maximum bin coordinates, the number of divisions, and the division multiplier. */
510  Eigen::Vector4i min_b_, max_b_, div_b_, divb_mul_;
511 
512  /** \brief The desired user filter field name. */
513  std::string filter_field_name_;
514 
515  /** \brief The minimum allowed filter value a point will be considered from. */
516  double filter_limit_min_{std::numeric_limits<float>::lowest()};
517 
518  /** \brief The maximum allowed filter value a point will be considered from. */
519  double filter_limit_max_{std::numeric_limits<float>::max()};
520 
521  /** \brief Set to true if we want to return the data outside (\a filter_limit_min_;\a filter_limit_max_). Default: false. */
523 
524  /** \brief Minimum number of points per voxel for the centroid to be computed */
525  unsigned int min_points_per_voxel_{0};
526 
527  using FieldList = typename pcl::traits::fieldList<PointT>::type;
528 
529  /** \brief Downsample a Point Cloud using a voxelized grid approach
530  * \param[out] output the resultant point cloud message
531  */
532  void
533  applyFilter (PointCloud &output) override;
534  };
535 
536  /** \brief VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data.
537  *
538  * The VoxelGrid class creates a *3D voxel grid* (think about a voxel
539  * grid as a set of tiny 3D boxes in space) over the input point cloud data.
540  * Then, in each *voxel* (i.e., 3D box), all the points present will be
541  * approximated (i.e., *downsampled*) with their centroid. This approach is
542  * a bit slower than approximating them with the center of the voxel, but it
543  * represents the underlying surface more accurately.
544  *
545  * \author Radu B. Rusu, Bastian Steder, Radoslaw Cybulski
546  * \ingroup filters
547  */
548  template <>
549  class PCL_EXPORTS VoxelGrid<pcl::PCLPointCloud2> : public Filter<pcl::PCLPointCloud2>
550  {
553 
557 
558  public:
559  /** \brief Empty constructor. */
561  leaf_size_ (Eigen::Vector4f::Zero ()),
562  inverse_leaf_size_ (Eigen::Array4f::Zero ()),
563 
564  min_b_ (Eigen::Vector4i::Zero ()),
565  max_b_ (Eigen::Vector4i::Zero ()),
566  div_b_ (Eigen::Vector4i::Zero ()),
567  divb_mul_ (Eigen::Vector4i::Zero ())
568  {
569  filter_name_ = "VoxelGrid";
570  }
571 
572  /** \brief Destructor. */
573  ~VoxelGrid () override = default;
574 
575  /** \brief Set the voxel grid leaf size.
576  * \param[in] leaf_size the voxel grid leaf size
577  */
578  inline void
579  setLeafSize (const Eigen::Vector4f &leaf_size)
580  {
581  leaf_size_ = leaf_size;
582  // Avoid division errors
583  if (leaf_size_[3] == 0)
584  leaf_size_[3] = 1;
585  // Use multiplications instead of divisions
586  inverse_leaf_size_ = Eigen::Array4f::Ones () / leaf_size_.array ();
587  }
588 
589  /** \brief Set the voxel grid leaf size.
590  * \param[in] lx the leaf size for X
591  * \param[in] ly the leaf size for Y
592  * \param[in] lz the leaf size for Z
593  */
594  inline void
595  setLeafSize (float lx, float ly, float lz)
596  {
597  leaf_size_[0] = lx; leaf_size_[1] = ly; leaf_size_[2] = lz;
598  // Avoid division errors
599  if (leaf_size_[3] == 0)
600  leaf_size_[3] = 1;
601  // Use multiplications instead of divisions
602  inverse_leaf_size_ = Eigen::Array4f::Ones () / leaf_size_.array ();
603  }
604 
605  /** \brief Get the voxel grid leaf size. */
606  inline Eigen::Vector3f
607  getLeafSize () const { return (leaf_size_.head<3> ()); }
608 
609  /** \brief Set to true if all fields need to be downsampled, or false if just XYZ.
610  * \param[in] downsample the new value (true/false)
611  */
612  inline void
613  setDownsampleAllData (bool downsample) { downsample_all_data_ = downsample; }
614 
615  /** \brief Get the state of the internal downsampling parameter (true if
616  * all fields need to be downsampled, false if just XYZ).
617  */
618  inline bool
619  getDownsampleAllData () const { return (downsample_all_data_); }
620 
621  /** \brief Set the minimum number of points required for a voxel to be used.
622  * \param[in] min_points_per_voxel the minimum number of points for required for a voxel to be used
623  */
624  inline void
625  setMinimumPointsNumberPerVoxel (unsigned int min_points_per_voxel) { min_points_per_voxel_ = min_points_per_voxel; }
626 
627  /** \brief Return the minimum number of points required for a voxel to be used.
628  */
629  inline unsigned int
630  getMinimumPointsNumberPerVoxel () const { return min_points_per_voxel_; }
631 
632  /** \brief Set to true if leaf layout information needs to be saved for later access.
633  * \param[in] save_leaf_layout the new value (true/false)
634  */
635  inline void
636  setSaveLeafLayout (bool save_leaf_layout) { save_leaf_layout_ = save_leaf_layout; }
637 
638  /** \brief Returns true if leaf layout information will to be saved for later access. */
639  inline bool
640  getSaveLeafLayout () const { return (save_leaf_layout_); }
641 
642  /** \brief Get the minimum coordinates of the bounding box (after
643  * filtering is performed).
644  */
645  inline Eigen::Vector3i
646  getMinBoxCoordinates () const { return (min_b_.head<3> ()); }
647 
648  /** \brief Get the minimum coordinates of the bounding box (after
649  * filtering is performed).
650  */
651  inline Eigen::Vector3i
652  getMaxBoxCoordinates () const { return (max_b_.head<3> ()); }
653 
654  /** \brief Get the number of divisions along all 3 axes (after filtering
655  * is performed).
656  */
657  inline Eigen::Vector3i
658  getNrDivisions () const { return (div_b_.head<3> ()); }
659 
660  /** \brief Get the multipliers to be applied to the grid coordinates in
661  * order to find the centroid index (after filtering is performed).
662  */
663  inline Eigen::Vector3i
664  getDivisionMultiplier () const { return (divb_mul_.head<3> ()); }
665 
666  /** \brief Returns the index in the resulting downsampled cloud of the specified point.
667  * \note for efficiency, user must make sure that the saving of the leaf layout is enabled and filtering performed,
668  * and that the point is inside the grid, to avoid invalid access (or use getGridCoordinates+getCentroidIndexAt)
669  * \param[in] x the X point coordinate to get the index at
670  * \param[in] y the Y point coordinate to get the index at
671  * \param[in] z the Z point coordinate to get the index at
672  */
673  inline int
674  getCentroidIndex (float x, float y, float z) const
675  {
676  return (leaf_layout_.at ((Eigen::Vector4i (static_cast<int> (std::floor (x * inverse_leaf_size_[0])),
677  static_cast<int> (std::floor (y * inverse_leaf_size_[1])),
678  static_cast<int> (std::floor (z * inverse_leaf_size_[2])),
679  0)
680  - min_b_).dot (divb_mul_)));
681  }
682 
683  /** \brief Returns the indices in the resulting downsampled cloud of the points at the specified grid coordinates,
684  * relative to the grid coordinates of the specified point (or -1 if the cell was empty/out of bounds).
685  * \param[in] x the X coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds)
686  * \param[in] y the Y coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds)
687  * \param[in] z the Z coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds)
688  * \param[out] relative_coordinates matrix with the columns being the coordinates of the requested cells, relative to the reference point's cell
689  * \note for efficiency, user must make sure that the saving of the leaf layout is enabled and filtering performed
690  */
691  inline std::vector<int>
692  getNeighborCentroidIndices (float x, float y, float z, const Eigen::MatrixXi &relative_coordinates) const
693  {
694  Eigen::Vector4i ijk (static_cast<int> (std::floor (x * inverse_leaf_size_[0])),
695  static_cast<int> (std::floor (y * inverse_leaf_size_[1])),
696  static_cast<int> (std::floor (z * inverse_leaf_size_[2])), 0);
697  Eigen::Array4i diff2min = min_b_ - ijk;
698  Eigen::Array4i diff2max = max_b_ - ijk;
699  std::vector<int> neighbors (relative_coordinates.cols());
700  for (Eigen::Index ni = 0; ni < relative_coordinates.cols (); ni++)
701  {
702  Eigen::Vector4i displacement = (Eigen::Vector4i() << relative_coordinates.col(ni), 0).finished();
703  // checking if the specified cell is in the grid
704  if ((diff2min <= displacement.array()).all() && (diff2max >= displacement.array()).all())
705  neighbors[ni] = leaf_layout_[((ijk + displacement - min_b_).dot (divb_mul_))]; // .at() can be omitted
706  else
707  neighbors[ni] = -1; // cell is out of bounds, consider it empty
708  }
709  return (neighbors);
710  }
711 
712  /** \brief Returns the indices in the resulting downsampled cloud of the points at the specified grid coordinates,
713  * relative to the grid coordinates of the specified point (or -1 if the cell was empty/out of bounds).
714  * \param[in] x the X coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds)
715  * \param[in] y the Y coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds)
716  * \param[in] z the Z coordinate of the reference point (corresponding cell is allowed to be empty/out of bounds)
717  * \param[out] relative_coordinates vector with the elements being the coordinates of the requested cells, relative to the reference point's cell
718  * \note for efficiency, user must make sure that the saving of the leaf layout is enabled and filtering performed
719  */
720  inline std::vector<int>
721  getNeighborCentroidIndices (float x, float y, float z, const std::vector<Eigen::Vector3i, Eigen::aligned_allocator<Eigen::Vector3i> > &relative_coordinates) const
722  {
723  Eigen::Vector4i ijk (static_cast<int> (std::floor (x * inverse_leaf_size_[0])), static_cast<int> (std::floor (y * inverse_leaf_size_[1])), static_cast<int> (std::floor (z * inverse_leaf_size_[2])), 0);
724  std::vector<int> neighbors;
725  neighbors.reserve (relative_coordinates.size ());
726  for (const auto &relative_coordinate : relative_coordinates)
727  neighbors.push_back (leaf_layout_[(ijk + (Eigen::Vector4i() << relative_coordinate, 0).finished() - min_b_).dot (divb_mul_)]);
728  return (neighbors);
729  }
730 
731  /** \brief Returns the layout of the leafs for fast access to cells relative to current position.
732  * \note position at (i-min_x) + (j-min_y)*div_x + (k-min_z)*div_x*div_y holds the index of the element at coordinates (i,j,k) in the grid (-1 if empty)
733  */
734  inline std::vector<int>
735  getLeafLayout () const { return (leaf_layout_); }
736 
737  /** \brief Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z).
738  * \param[in] x the X point coordinate to get the (i, j, k) index at
739  * \param[in] y the Y point coordinate to get the (i, j, k) index at
740  * \param[in] z the Z point coordinate to get the (i, j, k) index at
741  */
742  inline Eigen::Vector3i
743  getGridCoordinates (float x, float y, float z) const
744  {
745  return {static_cast<int> (std::floor (x * inverse_leaf_size_[0])),
746  static_cast<int> (std::floor (y * inverse_leaf_size_[1])),
747  static_cast<int> (std::floor (z * inverse_leaf_size_[2]))};
748  }
749 
750  /** \brief Returns the index in the downsampled cloud corresponding to a given set of coordinates.
751  * \param[in] ijk the coordinates (i,j,k) in the grid (-1 if empty)
752  */
753  inline int
754  getCentroidIndexAt (const Eigen::Vector3i &ijk) const
755  {
756  int idx = ((Eigen::Vector4i() << ijk, 0).finished() - min_b_).dot (divb_mul_);
757  if (idx < 0 || idx >= static_cast<int> (leaf_layout_.size ())) // this checks also if leaf_layout_.size () == 0 i.e. everything was computed as needed
758  {
759  //if (verbose)
760  // PCL_ERROR ("[pcl::%s::getCentroidIndexAt] Specified coordinate is outside grid bounds, or leaf layout is not saved, make sure to call setSaveLeafLayout(true) and filter(output) first!\n", getClassName ().c_str ());
761  return (-1);
762  }
763  return (leaf_layout_[idx]);
764  }
765 
766  /** \brief Provide the name of the field to be used for filtering data. In conjunction with \a setFilterLimits,
767  * points having values outside this interval will be discarded.
768  * \param[in] field_name the name of the field that contains values used for filtering
769  */
770  inline void
771  setFilterFieldName (const std::string &field_name)
772  {
773  filter_field_name_ = field_name;
774  }
775 
776  /** \brief Get the name of the field used for filtering. */
777  inline std::string const
779  {
780  return (filter_field_name_);
781  }
782 
783  /** \brief Set the field filter limits. All points having field values outside this interval will be discarded.
784  * \param[in] limit_min the minimum allowed field value
785  * \param[in] limit_max the maximum allowed field value
786  */
787  inline void
788  setFilterLimits (const double &limit_min, const double &limit_max)
789  {
790  filter_limit_min_ = limit_min;
791  filter_limit_max_ = limit_max;
792  }
793 
794  /** \brief Get the field filter limits (min/max) set by the user.
795  * The default values are std::numeric_limits<float>::lowest(), std::numeric_limits<float>::max().
796  * \param[out] limit_min the minimum allowed field value
797  * \param[out] limit_max the maximum allowed field value
798  */
799  inline void
800  getFilterLimits (double &limit_min, double &limit_max) const
801  {
802  limit_min = filter_limit_min_;
803  limit_max = filter_limit_max_;
804  }
805 
806  /** \brief Set to true if we want to return the data outside the interval specified by setFilterLimits (min, max).
807  * Default: false.
808  * \param[in] limit_negative return data inside the interval (false) or outside (true)
809  */
810  inline void
811  setFilterLimitsNegative (const bool limit_negative)
812  {
813  filter_limit_negative_ = limit_negative;
814  }
815 
816  /** \brief Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
817  * \param[out] limit_negative true if data \b outside the interval [min; max] is to be returned, false otherwise
818  */
819  PCL_DEPRECATED(1, 16, "use bool getFilterLimitsNegative() instead")
820  inline void
821  getFilterLimitsNegative (bool &limit_negative) const
822  {
823  limit_negative = filter_limit_negative_;
824  }
825 
826  /** \brief Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
827  * \return true if data \b outside the interval [min; max] is to be returned, false otherwise
828  */
829  inline bool
831  {
832  return (filter_limit_negative_);
833  }
834 
835  protected:
836  /** \brief The size of a leaf. */
837  Eigen::Vector4f leaf_size_;
838 
839  /** \brief Internal leaf sizes stored as 1/leaf_size_ for efficiency reasons. */
840  Eigen::Array4f inverse_leaf_size_;
841 
842  /** \brief Set to true if all fields need to be downsampled, or false if just XYZ. */
843  bool downsample_all_data_{true};
844 
845  /** \brief Set to true if leaf layout information needs to be saved in \a
846  * leaf_layout.
847  */
848  bool save_leaf_layout_{false};
849 
850  /** \brief The leaf layout information for fast access to cells relative
851  * to current position
852  */
853  std::vector<int> leaf_layout_;
854 
855  /** \brief The minimum and maximum bin coordinates, the number of
856  * divisions, and the division multiplier.
857  */
858  Eigen::Vector4i min_b_, max_b_, div_b_, divb_mul_;
859 
860  /** \brief The desired user filter field name. */
861  std::string filter_field_name_;
862 
863  /** \brief The minimum allowed filter value a point will be considered from. */
864  double filter_limit_min_{std::numeric_limits<float>::lowest()};
865 
866  /** \brief The maximum allowed filter value a point will be considered from. */
867  double filter_limit_max_{std::numeric_limits<float>::max()};
868 
869  /** \brief Set to true if we want to return the data outside (\a filter_limit_min_;\a filter_limit_max_). Default: false. */
870  bool filter_limit_negative_{false};
871 
872  /** \brief Minimum number of points per voxel for the centroid to be computed */
873  unsigned int min_points_per_voxel_{0};
874 
875  /** \brief Downsample a Point Cloud using a voxelized grid approach
876  * \param[out] output the resultant point cloud
877  */
878  void
879  applyFilter (PCLPointCloud2 &output) override;
880  };
881 
882  namespace internal
883  {
884  /** \brief Used internally in voxel grid classes.
885  */
887  {
888  unsigned int idx;
889  unsigned int cloud_point_index;
890 
892  cloud_point_index_idx (unsigned int idx_, unsigned int cloud_point_index_) : idx (idx_), cloud_point_index (cloud_point_index_) {}
893  bool operator < (const cloud_point_index_idx &p) const { return (idx < p.idx); }
894  };
895  }
896 }
897 
898 #ifdef PCL_NO_PRECOMPILE
899 #include <pcl/filters/impl/voxel_grid.hpp>
900 #endif
Filter represents the base filter class.
Definition: filter.h:81
shared_ptr< Filter< PointT > > Ptr
Definition: filter.h:83
shared_ptr< const Filter< PointT > > ConstPtr
Definition: filter.h:84
std::string filter_name_
The filter name.
Definition: filter.h:158
PCLPointCloud2::Ptr PCLPointCloud2Ptr
Definition: pcl_base.h:185
PCLPointCloud2::ConstPtr PCLPointCloud2ConstPtr
Definition: pcl_base.h:186
typename PointCloud::Ptr PointCloudPtr
Definition: pcl_base.h:73
typename PointCloud::ConstPtr PointCloudConstPtr
Definition: pcl_base.h:74
PointCloud represents the base class in PCL for storing collections of 3D points.
Definition: point_cloud.h:174
shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:414
shared_ptr< const PointCloud< PointT > > ConstPtr
Definition: point_cloud.h:415
int getCentroidIndexAt(const Eigen::Vector3i &ijk) const
Returns the index in the downsampled cloud corresponding to a given set of coordinates.
Definition: voxel_grid.h:754
Eigen::Vector3i getDivisionMultiplier() const
Get the multipliers to be applied to the grid coordinates in order to find the centroid index (after ...
Definition: voxel_grid.h:664
bool getFilterLimitsNegative() const
Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
Definition: voxel_grid.h:830
std::vector< int > getNeighborCentroidIndices(float x, float y, float z, const Eigen::MatrixXi &relative_coordinates) const
Returns the indices in the resulting downsampled cloud of the points at the specified grid coordinate...
Definition: voxel_grid.h:692
std::string filter_field_name_
The desired user filter field name.
Definition: voxel_grid.h:861
std::vector< int > leaf_layout_
The leaf layout information for fast access to cells relative to current position.
Definition: voxel_grid.h:853
void setDownsampleAllData(bool downsample)
Set to true if all fields need to be downsampled, or false if just XYZ.
Definition: voxel_grid.h:613
void setFilterLimits(const double &limit_min, const double &limit_max)
Set the field filter limits.
Definition: voxel_grid.h:788
Eigen::Vector3f getLeafSize() const
Get the voxel grid leaf size.
Definition: voxel_grid.h:607
Eigen::Vector3i getNrDivisions() const
Get the number of divisions along all 3 axes (after filtering is performed).
Definition: voxel_grid.h:658
Eigen::Vector3i getMinBoxCoordinates() const
Get the minimum coordinates of the bounding box (after filtering is performed).
Definition: voxel_grid.h:646
void applyFilter(PCLPointCloud2 &output) override
Downsample a Point Cloud using a voxelized grid approach.
unsigned int getMinimumPointsNumberPerVoxel() const
Return the minimum number of points required for a voxel to be used.
Definition: voxel_grid.h:630
void setLeafSize(const Eigen::Vector4f &leaf_size)
Set the voxel grid leaf size.
Definition: voxel_grid.h:579
void getFilterLimits(double &limit_min, double &limit_max) const
Get the field filter limits (min/max) set by the user.
Definition: voxel_grid.h:800
std::vector< int > getNeighborCentroidIndices(float x, float y, float z, const std::vector< Eigen::Vector3i, Eigen::aligned_allocator< Eigen::Vector3i > > &relative_coordinates) const
Returns the indices in the resulting downsampled cloud of the points at the specified grid coordinate...
Definition: voxel_grid.h:721
Eigen::Vector3i getGridCoordinates(float x, float y, float z) const
Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z).
Definition: voxel_grid.h:743
bool getDownsampleAllData() const
Get the state of the internal downsampling parameter (true if all fields need to be downsampled,...
Definition: voxel_grid.h:619
bool getSaveLeafLayout() const
Returns true if leaf layout information will to be saved for later access.
Definition: voxel_grid.h:640
std::vector< int > getLeafLayout() const
Returns the layout of the leafs for fast access to cells relative to current position.
Definition: voxel_grid.h:735
std::string const getFilterFieldName() const
Get the name of the field used for filtering.
Definition: voxel_grid.h:778
Eigen::Vector3i getMaxBoxCoordinates() const
Get the minimum coordinates of the bounding box (after filtering is performed).
Definition: voxel_grid.h:652
void setFilterFieldName(const std::string &field_name)
Provide the name of the field to be used for filtering data.
Definition: voxel_grid.h:771
void setSaveLeafLayout(bool save_leaf_layout)
Set to true if leaf layout information needs to be saved for later access.
Definition: voxel_grid.h:636
void setFilterLimitsNegative(const bool limit_negative)
Set to true if we want to return the data outside the interval specified by setFilterLimits (min,...
Definition: voxel_grid.h:811
void setLeafSize(float lx, float ly, float lz)
Set the voxel grid leaf size.
Definition: voxel_grid.h:595
Eigen::Array4f inverse_leaf_size_
Internal leaf sizes stored as 1/leaf_size_ for efficiency reasons.
Definition: voxel_grid.h:840
~VoxelGrid() override=default
Destructor.
void setMinimumPointsNumberPerVoxel(unsigned int min_points_per_voxel)
Set the minimum number of points required for a voxel to be used.
Definition: voxel_grid.h:625
int getCentroidIndex(float x, float y, float z) const
Returns the index in the resulting downsampled cloud of the specified point.
Definition: voxel_grid.h:674
Eigen::Vector4f leaf_size_
The size of a leaf.
Definition: voxel_grid.h:837
VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data.
Definition: voxel_grid.h:222
Eigen::Vector3i getGridCoordinates(float x, float y, float z) const
Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z).
Definition: voxel_grid.h:401
void setFilterFieldName(const std::string &field_name)
Provide the name of the field to be used for filtering data.
Definition: voxel_grid.h:429
void setDownsampleAllData(bool downsample)
Set to true if all fields need to be downsampled, or false if just XYZ.
Definition: voxel_grid.h:293
bool downsample_all_data_
Set to true if all fields need to be downsampled, or false if just XYZ.
Definition: voxel_grid.h:501
Eigen::Vector3i getDivisionMultiplier() const
Get the multipliers to be applied to the grid coordinates in order to find the centroid index (after ...
Definition: voxel_grid.h:344
bool getFilterLimitsNegative() const
Get whether the data outside the interval (min/max) is to be returned (true) or inside (false).
Definition: voxel_grid.h:488
void setFilterLimitsNegative(const bool limit_negative)
Set to true if we want to return the data outside the interval specified by setFilterLimits (min,...
Definition: voxel_grid.h:469
Eigen::Vector3i getMaxBoxCoordinates() const
Get the minimum coordinates of the bounding box (after filtering is performed).
Definition: voxel_grid.h:332
Eigen::Vector4i max_b_
Definition: voxel_grid.h:510
unsigned int min_points_per_voxel_
Minimum number of points per voxel for the centroid to be computed.
Definition: voxel_grid.h:525
void applyFilter(PointCloud &output) override
Downsample a Point Cloud using a voxelized grid approach.
Definition: voxel_grid.hpp:597
unsigned int getMinimumPointsNumberPerVoxel() const
Return the minimum number of points required for a voxel to be used.
Definition: voxel_grid.h:310
bool getDownsampleAllData() const
Get the state of the internal downsampling parameter (true if all fields need to be downsampled,...
Definition: voxel_grid.h:299
std::vector< int > leaf_layout_
The leaf layout information for fast access to cells relative to current position.
Definition: voxel_grid.h:507
void getFilterLimits(double &limit_min, double &limit_max) const
Get the field filter limits (min/max) set by the user.
Definition: voxel_grid.h:458
Eigen::Vector4i divb_mul_
Definition: voxel_grid.h:510
typename pcl::traits::fieldList< PointT >::type FieldList
Definition: voxel_grid.h:527
int getCentroidIndex(const PointT &p) const
Returns the index in the resulting downsampled cloud of the specified point.
Definition: voxel_grid.h:355
Eigen::Vector3i getNrDivisions() const
Get the number of divisions along all 3 axes (after filtering is performed).
Definition: voxel_grid.h:338
bool save_leaf_layout_
Set to true if leaf layout information needs to be saved in leaf_layout_.
Definition: voxel_grid.h:504
bool filter_limit_negative_
Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_).
Definition: voxel_grid.h:522
std::vector< int > getLeafLayout() const
Returns the layout of the leafs for fast access to cells relative to current position.
Definition: voxel_grid.h:393
int getCentroidIndexAt(const Eigen::Vector3i &ijk) const
Returns the index in the downsampled cloud corresponding to a given set of coordinates.
Definition: voxel_grid.h:412
void setLeafSize(const Eigen::Vector4f &leaf_size)
Set the voxel grid leaf size.
Definition: voxel_grid.h:259
Eigen::Vector4i min_b_
The minimum and maximum bin coordinates, the number of divisions, and the division multiplier.
Definition: voxel_grid.h:510
void setSaveLeafLayout(bool save_leaf_layout)
Set to true if leaf layout information needs to be saved for later access.
Definition: voxel_grid.h:316
double filter_limit_max_
The maximum allowed filter value a point will be considered from.
Definition: voxel_grid.h:519
void setMinimumPointsNumberPerVoxel(unsigned int min_points_per_voxel)
Set the minimum number of points required for a voxel to be used.
Definition: voxel_grid.h:305
std::vector< int > getNeighborCentroidIndices(const PointT &reference_point, const Eigen::MatrixXi &relative_coordinates) const
Returns the indices in the resulting downsampled cloud of the points at the specified grid coordinate...
Definition: voxel_grid.h:369
PCL_MAKE_ALIGNED_OPERATOR_NEW VoxelGrid()
Empty constructor.
Definition: voxel_grid.h:241
std::string filter_field_name_
The desired user filter field name.
Definition: voxel_grid.h:513
Eigen::Vector4f leaf_size_
The size of a leaf.
Definition: voxel_grid.h:495
double filter_limit_min_
The minimum allowed filter value a point will be considered from.
Definition: voxel_grid.h:516
Eigen::Vector3f getLeafSize() const
Get the voxel grid leaf size.
Definition: voxel_grid.h:287
void setLeafSize(float lx, float ly, float lz)
Set the voxel grid leaf size.
Definition: voxel_grid.h:275
std::string const getFilterFieldName() const
Get the name of the field used for filtering.
Definition: voxel_grid.h:436
Eigen::Vector3i getMinBoxCoordinates() const
Get the minimum coordinates of the bounding box (after filtering is performed).
Definition: voxel_grid.h:326
Eigen::Array4f inverse_leaf_size_
Internal leaf sizes stored as 1/leaf_size_ for efficiency reasons.
Definition: voxel_grid.h:498
~VoxelGrid() override=default
Destructor.
bool getSaveLeafLayout() const
Returns true if leaf layout information will to be saved for later access.
Definition: voxel_grid.h:320
Eigen::Vector4i div_b_
Definition: voxel_grid.h:510
void setFilterLimits(const double &limit_min, const double &limit_max)
Set the field filter limits.
Definition: voxel_grid.h:446
void getMinMax3D(const pcl::PointCloud< PointT > &cloud, PointT &min_pt, PointT &max_pt)
Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud.
Definition: common.hpp:295
#define PCL_MAKE_ALIGNED_OPERATOR_NEW
Macro to signal a class requires a custom allocator.
Definition: memory.h:86
Eigen::MatrixXi getAllNeighborCellIndices()
Get the relative cell indices of all the 26 neighbors.
Definition: voxel_grid.h:89
Eigen::MatrixXi getHalfNeighborCellIndices()
Get the relative cell indices of the "upper half" 13 neighbors.
Definition: voxel_grid.h:52
Definition: bfgs.h:10
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition: types.h:133
PCLPointCloud2::ConstPtr PCLPointCloud2ConstPtr
#define PCL_EXPORTS
Definition: pcl_macros.h:322
#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
shared_ptr< ::pcl::PCLPointCloud2 > Ptr
shared_ptr< const ::pcl::PCLPointCloud2 > ConstPtr
A point structure representing Euclidean xyz coordinates, and the RGB color.
Used internally in voxel grid classes.
Definition: voxel_grid.h:887
bool operator<(const cloud_point_index_idx &p) const
Definition: voxel_grid.h:893
cloud_point_index_idx(unsigned int idx_, unsigned int cloud_point_index_)
Definition: voxel_grid.h:892