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