Point Cloud Library (PCL)  1.15.1-dev
voxel_grid.hpp
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder(s) nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  * $Id$
35  *
36  */
37 
38 #ifndef PCL_FILTERS_IMPL_VOXEL_GRID_H_
39 #define PCL_FILTERS_IMPL_VOXEL_GRID_H_
40 
41 #include <limits>
42 
43 #include <pcl/common/centroid.h>
44 #include <pcl/common/common.h>
45 #include <pcl/common/io.h>
46 #include <pcl/filters/voxel_grid.h>
47 #include <boost/sort/spreadsort/integer_sort.hpp>
48 
49 ///////////////////////////////////////////////////////////////////////////////////////////
50 template <typename T> void
51 pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx, Eigen::Matrix<T, 4, 1> &min_pt, Eigen::Matrix<T, 4, 1> &max_pt)
52 {
53  if (pcl::traits::asEnum_v<T> != cloud->fields[x_idx].datatype ||
54  pcl::traits::asEnum_v<T> != cloud->fields[y_idx].datatype ||
55  pcl::traits::asEnum_v<T> != cloud->fields[z_idx].datatype)
56  {
57  PCL_ERROR("[pcl::getMinMax3D] Type of max_pt/min_pt does not match cloud type!\n");
58  return;
59  }
60 
61  T min_x = std::numeric_limits<T>::max();
62  T min_y = std::numeric_limits<T>::max();
63  T min_z = std::numeric_limits<T>::max();
64  T max_x = std::numeric_limits<T>::lowest();
65  T max_y = std::numeric_limits<T>::lowest();
66  T max_z = std::numeric_limits<T>::lowest();
67 
68  const std::uint32_t x_off = cloud->fields[x_idx].offset;
69  const std::uint32_t y_off = cloud->fields[y_idx].offset;
70  const std::uint32_t z_off = cloud->fields[z_idx].offset;
71  const std::uint32_t pt_step = cloud->point_step;
72  const std::size_t nr_points = cloud->width * cloud->height;
73 
74  const std::uint8_t* data_ptr = cloud->data.data();
75 
76  T x, y, z;
77 
78  auto update_min_max = [&](const T& x, const T& y, const T& z) {
79  if (x < min_x)
80  min_x = x;
81  if (y < min_y)
82  min_y = y;
83  if (z < min_z)
84  min_z = z;
85  if (x > max_x)
86  max_x = x;
87  if (y > max_y)
88  max_y = y;
89  if (z > max_z)
90  max_z = z;
91  };
92 
93  // If dense, no need to check for NaNs
94  if (cloud->is_dense)
95  {
96  for (std::size_t i = 0; i < nr_points; ++i)
97  {
98  std::memcpy(&x, data_ptr + x_off, sizeof(T));
99  std::memcpy(&y, data_ptr + y_off, sizeof(T));
100  std::memcpy(&z, data_ptr + z_off, sizeof(T));
101 
102  data_ptr += pt_step;
103 
104  update_min_max(x, y, z);
105  }
106  }
107  else
108  {
109  for (std::size_t i = 0; i < nr_points; ++i)
110  {
111  std::memcpy(&x, data_ptr + x_off, sizeof(T));
112  std::memcpy(&y, data_ptr + y_off, sizeof(T));
113  std::memcpy(&z, data_ptr + z_off, sizeof(T));
114 
115  data_ptr += pt_step;
116 
117  // Check if the point is invalid
118  if (!std::isfinite(x) || !std::isfinite(y) || !std::isfinite(z))
119  continue;
120 
121  update_min_max(x, y, z);
122  }
123  }
124 
125  min_pt << min_x, min_y, min_z, 0;
126  max_pt << max_x, max_y, max_z, 0;
127 }
128 
129 ///////////////////////////////////////////////////////////////////////////////////////////
130 template <typename T> void
131 pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, const pcl::Indices &indices, int x_idx, int y_idx, int z_idx,
132  Eigen::Matrix<T, 4, 1> &min_pt, Eigen::Matrix<T, 4, 1> &max_pt)
133 {
134  if (pcl::traits::asEnum_v<T> != cloud->fields[x_idx].datatype ||
135  pcl::traits::asEnum_v<T> != cloud->fields[y_idx].datatype ||
136  pcl::traits::asEnum_v<T> != cloud->fields[z_idx].datatype)
137  {
138  PCL_ERROR("[pcl::getMinMax3D] Type of max_pt/min_pt does not match cloud type!\n");
139  return;
140  }
141 
142  T min_x = std::numeric_limits<T>::max();
143  T min_y = std::numeric_limits<T>::max();
144  T min_z = std::numeric_limits<T>::max();
145  T max_x = std::numeric_limits<T>::lowest();
146  T max_y = std::numeric_limits<T>::lowest();
147  T max_z = std::numeric_limits<T>::lowest();
148 
149  const std::uint32_t x_off = cloud->fields[x_idx].offset;
150  const std::uint32_t y_off = cloud->fields[y_idx].offset;
151  const std::uint32_t z_off = cloud->fields[z_idx].offset;
152  const std::uint32_t pt_step = cloud->point_step;
153  const std::uint8_t* data_ptr = cloud->data.data();
154 
155  T x, y, z;
156 
157  auto update_min_max = [&](const T& x, const T& y, const T& z) {
158  if (x < min_x)
159  min_x = x;
160  if (y < min_y)
161  min_y = y;
162  if (z < min_z)
163  min_z = z;
164  if (x > max_x)
165  max_x = x;
166  if (y > max_y)
167  max_y = y;
168  if (z > max_z)
169  max_z = z;
170  };
171 
172  // If dense, no need to check for NaNs
173  if (cloud->is_dense)
174  {
175  for (const auto& index : indices)
176  {
177  const std::uint8_t* pt_data = data_ptr + (index * pt_step);
178 
179  std::memcpy(&x, pt_data + x_off, sizeof(T));
180  std::memcpy(&y, pt_data + y_off, sizeof(T));
181  std::memcpy(&z, pt_data + z_off, sizeof(T));
182 
183  update_min_max(x, y, z);
184  }
185  }
186  else
187  {
188  for (const auto& index : indices)
189  {
190  const std::uint8_t* pt_data = data_ptr + (index * pt_step);
191 
192  std::memcpy(&x, pt_data + x_off, sizeof(T));
193  std::memcpy(&y, pt_data + y_off, sizeof(T));
194  std::memcpy(&z, pt_data + z_off, sizeof(T));
195 
196  // Check if the point is invalid
197  if (!std::isfinite(x) || !std::isfinite(y) || !std::isfinite(z))
198  continue;
199 
200  update_min_max(x, y, z);
201  }
202  }
203 
204  min_pt << min_x, min_y, min_z, 0;
205  max_pt << max_x, max_y, max_z, 0;
206 }
207 
208 ///////////////////////////////////////////////////////////////////////////////////////////
209 template <typename T, typename D> void
210 pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx,
211  const std::string &distance_field_name, D min_distance, D max_distance,
212  Eigen::Matrix<T, 4, 1> &min_pt, Eigen::Matrix<T, 4, 1> &max_pt, bool limit_negative)
213 {
214  if (pcl::traits::asEnum_v<T> != cloud->fields[x_idx].datatype ||
215  pcl::traits::asEnum_v<T> != cloud->fields[y_idx].datatype ||
216  pcl::traits::asEnum_v<T> != cloud->fields[z_idx].datatype)
217  {
218  PCL_ERROR("[pcl::getMinMax3D] Type of max_pt/min_pt does not match cloud type!\n");
219  return;
220  }
221 
222  int distance_idx = pcl::getFieldIndex (*cloud, distance_field_name);
223 
224  if (distance_idx < 0)
225  {
226  PCL_ERROR("[pcl::getMinMax3D] The specified distance field name is not found in the cloud!\n");
227  return;
228  }
229 
230  if (cloud->fields[distance_idx].datatype != pcl::traits::asEnum_v<D>)
231  {
232  PCL_ERROR ("[pcl::getMinMax3D] min_distance/max_distance are incorrect type!\n");
233  return;
234  }
235 
236  T min_x = std::numeric_limits<T>::max();
237  T min_y = std::numeric_limits<T>::max();
238  T min_z = std::numeric_limits<T>::max();
239  T max_x = std::numeric_limits<T>::lowest();
240  T max_y = std::numeric_limits<T>::lowest();
241  T max_z = std::numeric_limits<T>::lowest();
242 
243  const std::uint32_t x_off = cloud->fields[x_idx].offset;
244  const std::uint32_t y_off = cloud->fields[y_idx].offset;
245  const std::uint32_t z_off = cloud->fields[z_idx].offset;
246  const std::uint32_t pt_step = cloud->point_step;
247  const std::uint8_t* data_ptr = cloud->data.data();
248  const std::size_t nr_points = cloud->width * cloud->height;
249 
250  const std::uint32_t distance_off = cloud->fields[distance_idx].offset;
251 
252  T x, y, z;
253  D distance_value;
254 
255  auto update_min_max = [&](const T& x, const T& y, const T& z) {
256  if (x < min_x)
257  min_x = x;
258  if (y < min_y)
259  min_y = y;
260  if (z < min_z)
261  min_z = z;
262  if (x > max_x)
263  max_x = x;
264  if (y > max_y)
265  max_y = y;
266  if (z > max_z)
267  max_z = z;
268  };
269 
270  // If dense, no need to check for NaNs
271  if (cloud->is_dense)
272  {
273  for (std::size_t cp = 0; cp < nr_points; ++cp)
274  {
275  std::memcpy(&distance_value, data_ptr + distance_off, sizeof(D));
276 
277  if (limit_negative == (distance_value < max_distance && distance_value > min_distance))
278  {
279  data_ptr += pt_step;
280  continue;
281  }
282 
283  std::memcpy(&x, data_ptr + x_off, sizeof(T));
284  std::memcpy(&y, data_ptr + y_off, sizeof(T));
285  std::memcpy(&z, data_ptr + z_off, sizeof(T));
286 
287  data_ptr += pt_step;
288 
289  update_min_max(x, y, z);
290  }
291  }
292  else
293  {
294  for (std::size_t cp = 0; cp < nr_points; ++cp)
295  {
296  std::memcpy(&distance_value, data_ptr + distance_off, sizeof(D));
297 
298  if (limit_negative == (distance_value < max_distance && distance_value > min_distance))
299  {
300  data_ptr += pt_step;
301  continue;
302  }
303 
304  std::memcpy(&x, data_ptr + x_off, sizeof(T));
305  std::memcpy(&y, data_ptr + y_off, sizeof(T));
306  std::memcpy(&z, data_ptr + z_off, sizeof(T));
307 
308  data_ptr += pt_step;
309 
310  // Check if the point is invalid
311  if (!std::isfinite(x) || !std::isfinite(y) || !std::isfinite(z))
312  continue;
313 
314  update_min_max(x, y, z);
315  }
316  }
317 
318  min_pt << min_x, min_y, min_z, 0;
319  max_pt << max_x, max_y, max_z, 0;
320 }
321 
322 ///////////////////////////////////////////////////////////////////////////////////////////
323 template <typename T, typename D> void
324 pcl::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,
325  Eigen::Matrix<T, 4, 1> &min_pt, Eigen::Matrix<T, 4, 1> &max_pt, bool limit_negative)
326 {
327  if (pcl::traits::asEnum_v<T> != cloud->fields[x_idx].datatype ||
328  pcl::traits::asEnum_v<T> != cloud->fields[y_idx].datatype ||
329  pcl::traits::asEnum_v<T> != cloud->fields[z_idx].datatype)
330  {
331  PCL_ERROR("[pcl::getMinMax3D] Type of max_pt/min_pt does not match cloud type!\n");
332  return;
333  }
334 
335  int distance_idx = pcl::getFieldIndex (*cloud, distance_field_name);
336 
337  if (distance_idx < 0)
338  {
339  PCL_ERROR("[pcl::getMinMax3D] The specified distance field name is not found in the cloud!\n");
340  return;
341  }
342 
343  if (cloud->fields[distance_idx].datatype != pcl::traits::asEnum_v<D>)
344  {
345  PCL_ERROR ("[pcl::getMinMax3D] min_distance/max_distance are incorrect type!\n");
346  return;
347  }
348 
349  T min_x = std::numeric_limits<T>::max();
350  T min_y = std::numeric_limits<T>::max();
351  T min_z = std::numeric_limits<T>::max();
352  T max_x = std::numeric_limits<T>::lowest();
353  T max_y = std::numeric_limits<T>::lowest();
354  T max_z = std::numeric_limits<T>::lowest();
355 
356  const std::uint32_t x_off = cloud->fields[x_idx].offset;
357  const std::uint32_t y_off = cloud->fields[y_idx].offset;
358  const std::uint32_t z_off = cloud->fields[z_idx].offset;
359  const std::uint32_t pt_step = cloud->point_step;
360  const std::uint8_t* data_ptr = cloud->data.data();
361 
362  const std::uint32_t distance_off = cloud->fields[distance_idx].offset;
363 
364  T x, y, z;
365  D distance_value;
366 
367  auto update_min_max = [&](const T& x, const T& y, const T& z) {
368  if (x < min_x)
369  min_x = x;
370  if (y < min_y)
371  min_y = y;
372  if (z < min_z)
373  min_z = z;
374  if (x > max_x)
375  max_x = x;
376  if (y > max_y)
377  max_y = y;
378  if (z > max_z)
379  max_z = z;
380  };
381 
382  // If dense, no need to check for NaNs
383  if(cloud->is_dense)
384  {
385  for (const auto& index : indices)
386  {
387  const std::uint8_t* pt_data = data_ptr + (index * pt_step);
388 
389  std::memcpy(&distance_value, pt_data + distance_off, sizeof(D));
390 
391  if (limit_negative == (distance_value < max_distance && distance_value > min_distance))
392  {
393  continue;
394  }
395 
396  std::memcpy(&x, pt_data + x_off, sizeof(T));
397  std::memcpy(&y, pt_data + y_off, sizeof(T));
398  std::memcpy(&z, pt_data + z_off, sizeof(T));
399 
400  update_min_max(x, y, z);
401  }
402  }
403  else
404  {
405  for (const auto& index : indices)
406  {
407  const std::uint8_t* pt_data = data_ptr + (index * pt_step);
408 
409  std::memcpy(&distance_value, pt_data + distance_off, sizeof(D));
410 
411  if (limit_negative == (distance_value < max_distance && distance_value > min_distance))
412  {
413  continue;
414  }
415 
416  std::memcpy(&x, pt_data + x_off, sizeof(T));
417  std::memcpy(&y, pt_data + y_off, sizeof(T));
418  std::memcpy(&z, pt_data + z_off, sizeof(T));
419 
420  if (!std::isfinite(x) || !std::isfinite(y) || !std::isfinite(z))
421  continue;
422 
423  update_min_max(x, y, z);
424  }
425  }
426  min_pt << min_x, min_y, min_z, 0;
427  max_pt << max_x, max_y, max_z, 0;
428 }
429 
430 ///////////////////////////////////////////////////////////////////////////////////////////
431 template <typename PointT> void
433  const std::string &distance_field_name, float min_distance, float max_distance,
434  Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative)
435 {
436  Eigen::Array4f min_p, max_p;
437  min_p.setConstant (std::numeric_limits<float>::max());
438  max_p.setConstant (std::numeric_limits<float>::lowest());
439 
440  // Get the fields list and the distance field index
441  std::vector<pcl::PCLPointField> fields;
442  int distance_idx = pcl::getFieldIndex<PointT> (distance_field_name, fields);
443  if (distance_idx < 0 || fields.empty()) {
444  PCL_ERROR ("[pcl::getMinMax3D] Could not find field with name '%s'!\n", distance_field_name.c_str());
445  return;
446  }
447  const auto field_offset = fields[distance_idx].offset;
448 
449  float distance_value;
450  // If dense, no need to check for NaNs
451  if (cloud->is_dense)
452  {
453  for (const auto& point: *cloud)
454  {
455  // Get the distance value
456  const auto* pt_data = reinterpret_cast<const std::uint8_t*> (&point);
457  memcpy (&distance_value, pt_data + field_offset, sizeof (float));
458 
459  if (limit_negative)
460  {
461  // Use a threshold for cutting out points which inside the interval
462  if ((distance_value < max_distance) && (distance_value > min_distance))
463  continue;
464  }
465  else
466  {
467  // Use a threshold for cutting out points which are too close/far away
468  if ((distance_value > max_distance) || (distance_value < min_distance))
469  continue;
470  }
471  // Create the point structure and get the min/max
472  pcl::Array4fMapConst pt = point.getArray4fMap ();
473  min_p = min_p.min (pt);
474  max_p = max_p.max (pt);
475  }
476  }
477  else
478  {
479  for (const auto& point: *cloud)
480  {
481  // Get the distance value
482  const auto* pt_data = reinterpret_cast<const std::uint8_t*> (&point);
483  memcpy (&distance_value, pt_data + field_offset, sizeof (float));
484 
485  if (limit_negative)
486  {
487  // Use a threshold for cutting out points which inside the interval
488  if ((distance_value < max_distance) && (distance_value > min_distance))
489  continue;
490  }
491  else
492  {
493  // Use a threshold for cutting out points which are too close/far away
494  if ((distance_value > max_distance) || (distance_value < min_distance))
495  continue;
496  }
497 
498  // Check if the point is invalid
499  if (!isXYZFinite (point))
500  continue;
501  // Create the point structure and get the min/max
502  pcl::Array4fMapConst pt = point.getArray4fMap ();
503  min_p = min_p.min (pt);
504  max_p = max_p.max (pt);
505  }
506  }
507  min_pt = min_p;
508  max_pt = max_p;
509 }
510 
511 ///////////////////////////////////////////////////////////////////////////////////////////
512 template <typename PointT> void
514  const Indices &indices,
515  const std::string &distance_field_name, float min_distance, float max_distance,
516  Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative)
517 {
518  Eigen::Array4f min_p, max_p;
519  min_p.setConstant (std::numeric_limits<float>::max());
520  max_p.setConstant (std::numeric_limits<float>::lowest());
521 
522  // Get the fields list and the distance field index
523  std::vector<pcl::PCLPointField> fields;
524  int distance_idx = pcl::getFieldIndex<PointT> (distance_field_name, fields);
525  if (distance_idx < 0 || fields.empty()) {
526  PCL_ERROR ("[pcl::getMinMax3D] Could not find field with name '%s'!\n", distance_field_name.c_str());
527  return;
528  }
529  const auto field_offset = fields[distance_idx].offset;
530 
531  float distance_value;
532  // If dense, no need to check for NaNs
533  if (cloud->is_dense)
534  {
535  for (const auto &index : indices)
536  {
537  // Get the distance value
538  const auto* pt_data = reinterpret_cast<const std::uint8_t*> (&(*cloud)[index]);
539  memcpy (&distance_value, pt_data + field_offset, sizeof (float));
540 
541  if (limit_negative)
542  {
543  // Use a threshold for cutting out points which inside the interval
544  if ((distance_value < max_distance) && (distance_value > min_distance))
545  continue;
546  }
547  else
548  {
549  // Use a threshold for cutting out points which are too close/far away
550  if ((distance_value > max_distance) || (distance_value < min_distance))
551  continue;
552  }
553  // Create the point structure and get the min/max
554  pcl::Array4fMapConst pt = (*cloud)[index].getArray4fMap ();
555  min_p = min_p.min (pt);
556  max_p = max_p.max (pt);
557  }
558  }
559  else
560  {
561  for (const auto &index : indices)
562  {
563  // Get the distance value
564  const auto* pt_data = reinterpret_cast<const std::uint8_t*> (&(*cloud)[index]);
565  memcpy (&distance_value, pt_data + field_offset, sizeof (float));
566 
567  if (limit_negative)
568  {
569  // Use a threshold for cutting out points which inside the interval
570  if ((distance_value < max_distance) && (distance_value > min_distance))
571  continue;
572  }
573  else
574  {
575  // Use a threshold for cutting out points which are too close/far away
576  if ((distance_value > max_distance) || (distance_value < min_distance))
577  continue;
578  }
579 
580  // Check if the point is invalid
581  if (!std::isfinite ((*cloud)[index].x) ||
582  !std::isfinite ((*cloud)[index].y) ||
583  !std::isfinite ((*cloud)[index].z))
584  continue;
585  // Create the point structure and get the min/max
586  pcl::Array4fMapConst pt = (*cloud)[index].getArray4fMap ();
587  min_p = min_p.min (pt);
588  max_p = max_p.max (pt);
589  }
590  }
591  min_pt = min_p;
592  max_pt = max_p;
593 }
594 
595 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
596 template <typename PointT> void
598 {
599  // Has the input dataset been set already?
600  if (!input_)
601  {
602  PCL_WARN ("[pcl::%s::applyFilter] No input dataset given!\n", getClassName ().c_str ());
603  output.width = output.height = 0;
604  output.clear ();
605  return;
606  }
607 
608  // Copy the header (and thus the frame_id) + allocate enough space for points
609  output.height = 1; // downsampling breaks the organized structure
610  output.is_dense = true; // we filter out invalid points
611 
612  Eigen::Vector4f min_p, max_p;
613  // Get the minimum and maximum dimensions
614  if (!filter_field_name_.empty ()) // If we don't want to process the entire cloud...
615  getMinMax3D<PointT> (input_, *indices_, filter_field_name_, static_cast<float> (filter_limit_min_), static_cast<float> (filter_limit_max_), min_p, max_p, filter_limit_negative_);
616  else
617  getMinMax3D<PointT> (*input_, *indices_, min_p, max_p);
618 
619  // Check that the leaf size is not too small, given the size of the data
620  std::int64_t dx = static_cast<std::int64_t>((max_p[0] - min_p[0]) * inverse_leaf_size_[0])+1;
621  std::int64_t dy = static_cast<std::int64_t>((max_p[1] - min_p[1]) * inverse_leaf_size_[1])+1;
622  std::int64_t dz = static_cast<std::int64_t>((max_p[2] - min_p[2]) * inverse_leaf_size_[2])+1;
623 
624  if ((dx*dy*dz) > static_cast<std::int64_t>(std::numeric_limits<std::int32_t>::max()))
625  {
626  PCL_WARN("[pcl::%s::applyFilter] Leaf size is too small for the input dataset. Integer indices would overflow.\n", getClassName().c_str());
627  output = *input_;
628  return;
629  }
630 
631  // Compute the minimum and maximum bounding box values
632  min_b_[0] = static_cast<int> (std::floor (min_p[0] * inverse_leaf_size_[0]));
633  max_b_[0] = static_cast<int> (std::floor (max_p[0] * inverse_leaf_size_[0]));
634  min_b_[1] = static_cast<int> (std::floor (min_p[1] * inverse_leaf_size_[1]));
635  max_b_[1] = static_cast<int> (std::floor (max_p[1] * inverse_leaf_size_[1]));
636  min_b_[2] = static_cast<int> (std::floor (min_p[2] * inverse_leaf_size_[2]));
637  max_b_[2] = static_cast<int> (std::floor (max_p[2] * inverse_leaf_size_[2]));
638 
639  // Compute the number of divisions needed along all axis
640  div_b_ = max_b_ - min_b_ + Eigen::Vector4i::Ones ();
641  div_b_[3] = 0;
642 
643  // Set up the division multiplier
644  divb_mul_ = Eigen::Vector4i (1, div_b_[0], div_b_[0] * div_b_[1], 0);
645 
646  // Storage for mapping leaf and pointcloud indexes
647  std::vector<internal::cloud_point_index_idx> index_vector;
648  index_vector.reserve (indices_->size ());
649 
650  // If we don't want to process the entire cloud, but rather filter points far away from the viewpoint first...
651  if (!filter_field_name_.empty ())
652  {
653  // Get the distance field index
654  std::vector<pcl::PCLPointField> fields;
655  int distance_idx = pcl::getFieldIndex<PointT> (filter_field_name_, fields);
656  if (distance_idx == -1) {
657  PCL_ERROR ("[pcl::%s::applyFilter] Invalid filter field name (%s).\n", getClassName ().c_str (), filter_field_name_.c_str());
658  return;
659  }
660  const auto field_offset = fields[distance_idx].offset;
661 
662  // First pass: go over all points and insert them into the index_vector vector
663  // with calculated idx. Points with the same idx value will contribute to the
664  // same point of resulting CloudPoint
665  for (const auto& index : (*indices_))
666  {
667  if (!input_->is_dense)
668  // Check if the point is invalid
669  if (!isXYZFinite ((*input_)[index]))
670  continue;
671 
672  // Get the distance value
673  const auto* pt_data = reinterpret_cast<const std::uint8_t*> (&(*input_)[index]);
674  float distance_value = 0;
675  memcpy (&distance_value, pt_data + field_offset, sizeof (float));
676 
677  if (filter_limit_negative_)
678  {
679  // Use a threshold for cutting out points which inside the interval
680  if ((distance_value < filter_limit_max_) && (distance_value > filter_limit_min_))
681  continue;
682  }
683  else
684  {
685  // Use a threshold for cutting out points which are too close/far away
686  if ((distance_value > filter_limit_max_) || (distance_value < filter_limit_min_))
687  continue;
688  }
689 
690  int ijk0 = static_cast<int> (std::floor ((*input_)[index].x * inverse_leaf_size_[0]) - static_cast<float> (min_b_[0]));
691  int ijk1 = static_cast<int> (std::floor ((*input_)[index].y * inverse_leaf_size_[1]) - static_cast<float> (min_b_[1]));
692  int ijk2 = static_cast<int> (std::floor ((*input_)[index].z * inverse_leaf_size_[2]) - static_cast<float> (min_b_[2]));
693 
694  // Compute the centroid leaf index
695  int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
696  index_vector.emplace_back(static_cast<unsigned int> (idx), index);
697  }
698  }
699  // No distance filtering, process all data
700  else
701  {
702  // First pass: go over all points and insert them into the index_vector vector
703  // with calculated idx. Points with the same idx value will contribute to the
704  // same point of resulting CloudPoint
705  for (const auto& index : (*indices_))
706  {
707  if (!input_->is_dense)
708  // Check if the point is invalid
709  if (!isXYZFinite ((*input_)[index]))
710  continue;
711 
712  int ijk0 = static_cast<int> (std::floor ((*input_)[index].x * inverse_leaf_size_[0]) - static_cast<float> (min_b_[0]));
713  int ijk1 = static_cast<int> (std::floor ((*input_)[index].y * inverse_leaf_size_[1]) - static_cast<float> (min_b_[1]));
714  int ijk2 = static_cast<int> (std::floor ((*input_)[index].z * inverse_leaf_size_[2]) - static_cast<float> (min_b_[2]));
715 
716  // Compute the centroid leaf index
717  int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
718  index_vector.emplace_back(static_cast<unsigned int> (idx), index);
719  }
720  }
721 
722  // Second pass: sort the index_vector vector using value representing target cell as index
723  // in effect all points belonging to the same output cell will be next to each other
724  auto rightshift_func = [](const internal::cloud_point_index_idx &x, const unsigned offset) { return x.idx >> offset; };
725  boost::sort::spreadsort::integer_sort(index_vector.begin(), index_vector.end(), rightshift_func);
726 
727  // Third pass: count output cells
728  // we need to skip all the same, adjacent idx values
729  unsigned int total = 0;
730  unsigned int index = 0;
731  // first_and_last_indices_vector[i] represents the index in index_vector of the first point in
732  // index_vector belonging to the voxel which corresponds to the i-th output point,
733  // and of the first point not belonging to.
734  std::vector<std::pair<unsigned int, unsigned int> > first_and_last_indices_vector;
735  // Worst case size
736  first_and_last_indices_vector.reserve (index_vector.size ());
737  while (index < index_vector.size ())
738  {
739  unsigned int i = index + 1;
740  while (i < index_vector.size () && index_vector[i].idx == index_vector[index].idx)
741  ++i;
742  if (i - index >= min_points_per_voxel_)
743  {
744  ++total;
745  first_and_last_indices_vector.emplace_back(index, i);
746  }
747  index = i;
748  }
749 
750  // Fourth pass: compute centroids, insert them into their final position
751  output.resize (total);
752  if (save_leaf_layout_)
753  {
754  try
755  {
756  // Resizing won't reset old elements to -1. If leaf_layout_ has been used previously, it needs to be re-initialized to -1
757  std::uint32_t new_layout_size = div_b_[0]*div_b_[1]*div_b_[2];
758  //This is the number of elements that need to be re-initialized to -1
759  std::uint32_t reinit_size = std::min (static_cast<unsigned int> (new_layout_size), static_cast<unsigned int> (leaf_layout_.size()));
760  for (std::uint32_t i = 0; i < reinit_size; i++)
761  {
762  leaf_layout_[i] = -1;
763  }
764  leaf_layout_.resize (new_layout_size, -1);
765  }
766  catch (std::bad_alloc&)
767  {
768  throw PCLException("VoxelGrid bin size is too low; impossible to allocate memory for layout",
769  "voxel_grid.hpp", "applyFilter");
770  }
771  catch (std::length_error&)
772  {
773  throw PCLException("VoxelGrid bin size is too low; impossible to allocate memory for layout",
774  "voxel_grid.hpp", "applyFilter");
775  }
776  }
777 
778  index = 0;
779  for (const auto &cp : first_and_last_indices_vector)
780  {
781  // calculate centroid - sum values from all input points, that have the same idx value in index_vector array
782  unsigned int first_index = cp.first;
783  unsigned int last_index = cp.second;
784 
785  // index is centroid final position in resulting PointCloud
786  if (save_leaf_layout_)
787  leaf_layout_[index_vector[first_index].idx] = index;
788 
789  //Limit downsampling to coords
790  if (!downsample_all_data_)
791  {
792  Eigen::Vector4f centroid (Eigen::Vector4f::Zero ());
793 
794  for (unsigned int li = first_index; li < last_index; ++li)
795  centroid += (*input_)[index_vector[li].cloud_point_index].getVector4fMap ();
796 
797  centroid /= static_cast<float> (last_index - first_index);
798  output[index].getVector4fMap () = centroid;
799  }
800  else
801  {
802  CentroidPoint<PointT> centroid;
803 
804  // fill in the accumulator with leaf points
805  for (unsigned int li = first_index; li < last_index; ++li)
806  centroid.add ((*input_)[index_vector[li].cloud_point_index]);
807 
808  centroid.get (output[index]);
809  }
810 
811  ++index;
812  }
813  output.width = output.size ();
814 }
815 
816 #define PCL_INSTANTIATE_VoxelGrid(T) template class PCL_EXPORTS pcl::VoxelGrid<T>;
817 #define PCL_INSTANTIATE_getMinMax3D(T) template PCL_EXPORTS void pcl::getMinMax3D<T> (const pcl::PointCloud<T>::ConstPtr &, const std::string &, float, float, Eigen::Vector4f &, Eigen::Vector4f &, bool);
818 
819 #endif // PCL_FILTERS_IMPL_VOXEL_GRID_H_
820 
Define methods for centroid estimation and covariance matrix calculus.
A generic class that computes the centroid of points fed to it.
Definition: centroid.h:1077
void get(PointOutT &point) const
Retrieve the current centroid.
Definition: centroid.hpp:1173
void add(const PointT &point)
Add a new point to the centroid computation.
Definition: centroid.hpp:1164
A base class for all pcl exceptions which inherits from std::runtime_error.
Definition: exceptions.h:67
PointCloud represents the base class in PCL for storing collections of 3D points.
Definition: point_cloud.h:174
bool is_dense
True if no points are invalid (e.g., have NaN or Inf values in any of their floating point fields).
Definition: point_cloud.h:404
void resize(std::size_t count)
Resizes the container to contain count elements.
Definition: point_cloud.h:463
std::uint32_t width
The point cloud width (if organized as an image-structure).
Definition: point_cloud.h:399
std::uint32_t height
The point cloud height (if organized as an image-structure).
Definition: point_cloud.h:401
void clear()
Removes all points in a cloud and sets the width and height to 0.
Definition: point_cloud.h:886
std::size_t size() const
Definition: point_cloud.h:444
shared_ptr< const PointCloud< PointT > > ConstPtr
Definition: point_cloud.h:415
void applyFilter(PointCloud &output) override
Downsample a Point Cloud using a voxelized grid approach.
Definition: voxel_grid.hpp:597
Define standard C methods and C++ classes that are common to all methods.
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
int getFieldIndex(const pcl::PointCloud< PointT > &, const std::string &field_name, std::vector< pcl::PCLPointField > &fields)
Definition: io.hpp:52
const Eigen::Map< const Eigen::Array4f, Eigen::Aligned > Array4fMapConst
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition: types.h:133
PCLPointCloud2::ConstPtr PCLPointCloud2ConstPtr
constexpr bool isXYZFinite(const PointT &) noexcept
Definition: point_tests.h:126
Used internally in voxel grid classes.
Definition: voxel_grid.h:887