util3d_filtering.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #ifndef UTIL3D_FILTERING_H_
29 #define UTIL3D_FILTERING_H_
30 
32 #include <rtabmap/core/Transform.h>
33 #include <pcl/point_cloud.h>
34 #include <pcl/point_types.h>
35 #include <pcl/pcl_base.h>
36 #include <pcl/ModelCoefficients.h>
37 #include <rtabmap/core/LaserScan.h>
38 
39 namespace rtabmap
40 {
41 
42 namespace util3d
43 {
44 
52  const LaserScan & scan,
53  int downsamplingStep,
54  float rangeMin = 0.0f,
55  float rangeMax = 0.0f,
56  float voxelSize = 0.0f,
57  int normalK = 0,
58  float normalRadius = 0.0f,
59  bool forceGroundNormalsUp = false);
60 
61 LaserScan RTABMAP_EXP rangeFiltering(
62  const LaserScan & scan,
63  float rangeMin,
64  float rangeMax);
65 
66 LaserScan RTABMAP_EXP downsample(
67  const LaserScan & cloud,
68  int step);
69 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP downsample(
70  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
71  int step);
72 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP downsample(
73  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
74  int step);
75 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP downsample(
76  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
77  int step);
78 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP downsample(
79  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
80  int step);
81 
82 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP voxelize(
83  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
84  const pcl::IndicesPtr & indices,
85  float voxelSize);
86 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP voxelize(
87  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
88  const pcl::IndicesPtr & indices,
89  float voxelSize);
90 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP voxelize(
91  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
92  const pcl::IndicesPtr & indices,
93  float voxelSize);
94 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP voxelize(
95  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
96  const pcl::IndicesPtr & indices,
97  float voxelSize);
98 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP voxelize(
99  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
100  const pcl::IndicesPtr & indices,
101  float voxelSize);
102 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP voxelize(
103  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
104  const pcl::IndicesPtr & indices,
105  float voxelSize);
106 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP voxelize(
107  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
108  float voxelSize);
109 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP voxelize(
110  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
111  float voxelSize);
112 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP voxelize(
113  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
114  float voxelSize);
115 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP voxelize(
116  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
117  float voxelSize);
118 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP voxelize(
119  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
120  float voxelSize);
121 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP voxelize(
122  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
123  float voxelSize);
124 
125 inline pcl::PointCloud<pcl::PointXYZ>::Ptr uniformSampling(
126  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
127  float voxelSize)
128 {
129  return voxelize(cloud, voxelSize);
130 }
131 inline pcl::PointCloud<pcl::PointXYZRGB>::Ptr uniformSampling(
132  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
133  float voxelSize)
134 {
135  return voxelize(cloud, voxelSize);
136 }
137 inline pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr uniformSampling(
138  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
139  float voxelSize)
140 {
141  return voxelize(cloud, voxelSize);
142 }
143 
144 
145 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP randomSampling(
146  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
147  int samples);
148 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP randomSampling(
149  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
150  int samples);
151 
152 
153 pcl::IndicesPtr RTABMAP_EXP passThrough(
154  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
155  const pcl::IndicesPtr & indices,
156  const std::string & axis,
157  float min,
158  float max,
159  bool negative = false);
160 pcl::IndicesPtr RTABMAP_EXP passThrough(
161  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
162  const pcl::IndicesPtr & indices,
163  const std::string & axis,
164  float min,
165  float max,
166  bool negative = false);
167 pcl::IndicesPtr RTABMAP_EXP passThrough(
168  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
169  const pcl::IndicesPtr & indices,
170  const std::string & axis,
171  float min,
172  float max,
173  bool negative = false);
174 pcl::IndicesPtr RTABMAP_EXP passThrough(
175  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
176  const pcl::IndicesPtr & indices,
177  const std::string & axis,
178  float min,
179  float max,
180  bool negative = false);
181 pcl::IndicesPtr RTABMAP_EXP passThrough(
182  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
183  const pcl::IndicesPtr & indices,
184  const std::string & axis,
185  float min,
186  float max,
187  bool negative = false);
188 pcl::IndicesPtr RTABMAP_EXP passThrough(
189  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
190  const pcl::IndicesPtr & indices,
191  const std::string & axis,
192  float min,
193  float max,
194  bool negative = false);
195 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP passThrough(
196  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
197  const std::string & axis,
198  float min,
199  float max,
200  bool negative = false);
201 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP passThrough(
202  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
203  const std::string & axis,
204  float min,
205  float max,
206  bool negative = false);
207 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP passThrough(
208  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
209  const std::string & axis,
210  float min,
211  float max,
212  bool negative = false);
213 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP passThrough(
214  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
215  const std::string & axis,
216  float min,
217  float max,
218  bool negative = false);
219 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP passThrough(
220  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
221  const std::string & axis,
222  float min,
223  float max,
224  bool negative = false);
225 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP passThrough(
226  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
227  const std::string & axis,
228  float min,
229  float max,
230  bool negative = false);
231 
232 pcl::IndicesPtr RTABMAP_EXP cropBox(
233  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
234  const pcl::IndicesPtr & indices,
235  const Eigen::Vector4f & min,
236  const Eigen::Vector4f & max,
237  const Transform & transform = Transform::getIdentity(),
238  bool negative = false);
239 pcl::IndicesPtr RTABMAP_EXP cropBox(
240  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
241  const pcl::IndicesPtr & indices,
242  const Eigen::Vector4f & min,
243  const Eigen::Vector4f & max,
244  const Transform & transform = Transform::getIdentity(),
245  bool negative = false);
246 pcl::IndicesPtr RTABMAP_EXP cropBox(
247  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
248  const pcl::IndicesPtr & indices,
249  const Eigen::Vector4f & min,
250  const Eigen::Vector4f & max,
251  const Transform & transform = Transform::getIdentity(),
252  bool negative = false);
253 pcl::IndicesPtr RTABMAP_EXP cropBox(
254  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
255  const pcl::IndicesPtr & indices,
256  const Eigen::Vector4f & min,
257  const Eigen::Vector4f & max,
258  const Transform & transform = Transform::getIdentity(),
259  bool negative = false);
260 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cropBox(
261  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
262  const Eigen::Vector4f & min,
263  const Eigen::Vector4f & max,
264  const Transform & transform = Transform::getIdentity(),
265  bool negative = false);
266 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP cropBox(
267  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
268  const Eigen::Vector4f & min,
269  const Eigen::Vector4f & max,
270  const Transform & transform = Transform::getIdentity(),
271  bool negative = false);
272 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cropBox(
273  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
274  const Eigen::Vector4f & min,
275  const Eigen::Vector4f & max,
276  const Transform & transform = Transform::getIdentity(),
277  bool negative = false);
278 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP cropBox(
279  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
280  const Eigen::Vector4f & min,
281  const Eigen::Vector4f & max,
282  const Transform & transform = Transform::getIdentity(),
283  bool negative = false);
284 
285 //Note: This assumes a coordinate system where X is forward, * Y is up, and Z is right.
286 pcl::IndicesPtr RTABMAP_EXP frustumFiltering(
287  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
288  const pcl::IndicesPtr & indices,
289  const Transform & cameraPose,
290  float horizontalFOV, // in degrees, xfov = atan((image_width/2)/fx)*2
291  float verticalFOV, // in degrees, yfov = atan((image_height/2)/fy)*2
292  float nearClipPlaneDistance,
293  float farClipPlaneDistance,
294  bool negative = false);
295 //Note: This assumes a coordinate system where X is forward, * Y is up, and Z is right.
296 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP frustumFiltering(
297  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
298  const Transform & cameraPose,
299  float horizontalFOV, // in degrees, xfov = atan((image_width/2)/fx)*2
300  float verticalFOV, // in degrees, yfov = atan((image_height/2)/fy)*2
301  float nearClipPlaneDistance,
302  float farClipPlaneDistance,
303  bool negative = false);
304 //Note: This assumes a coordinate system where X is forward, * Y is up, and Z is right.
305 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP frustumFiltering(
306  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
307  const Transform & cameraPose,
308  float horizontalFOV, // in degrees, xfov = atan((image_width/2)/fx)*2
309  float verticalFOV, // in degrees, yfov = atan((image_height/2)/fy)*2
310  float nearClipPlaneDistance,
311  float farClipPlaneDistance,
312  bool negative = false);
313 
314 
315 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP removeNaNFromPointCloud(
316  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud);
317 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP removeNaNFromPointCloud(
318  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud);
319 
320 
321 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP removeNaNNormalsFromPointCloud(
322  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud);
323 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP removeNaNNormalsFromPointCloud(
324  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud);
325 
330 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
331  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
332  float radiusSearch,
333  int minNeighborsInRadius);
334 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
335  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
336  float radiusSearch,
337  int minNeighborsInRadius);
338 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
339  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
340  float radiusSearch,
341  int minNeighborsInRadius);
342 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
343  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
344  float radiusSearch,
345  int minNeighborsInRadius);
346 
359 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
360  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
361  const pcl::IndicesPtr & indices,
362  float radiusSearch,
363  int minNeighborsInRadius);
364 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
365  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
366  const pcl::IndicesPtr & indices,
367  float radiusSearch,
368  int minNeighborsInRadius);
369 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
370  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
371  const pcl::IndicesPtr & indices,
372  float radiusSearch,
373  int minNeighborsInRadius);
374 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
375  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
376  const pcl::IndicesPtr & indices,
377  float radiusSearch,
378  int minNeighborsInRadius);
379 
383 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP subtractFiltering(
384  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
385  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
386  float radiusSearch,
387  int minNeighborsInRadius = 1);
388 
398 pcl::IndicesPtr RTABMAP_EXP subtractFiltering(
399  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
400  const pcl::IndicesPtr & indices,
401  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
402  const pcl::IndicesPtr & substractIndices,
403  float radiusSearch,
404  int minNeighborsInRadius = 1);
405 
409 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP subtractFiltering(
410  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
411  const pcl::PointCloud<pcl::PointNormal>::Ptr & substractCloud,
412  float radiusSearch,
413  float maxAngle = M_PI/4.0f,
414  int minNeighborsInRadius = 1);
415 
425 pcl::IndicesPtr RTABMAP_EXP subtractFiltering(
426  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
427  const pcl::IndicesPtr & indices,
428  const pcl::PointCloud<pcl::PointNormal>::Ptr & substractCloud,
429  const pcl::IndicesPtr & substractIndices,
430  float radiusSearch,
431  float maxAngle = M_PI/4.0f,
432  int minNeighborsInRadius = 1);
433 
437 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP subtractFiltering(
438  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
439  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
440  float radiusSearch,
441  float maxAngle = M_PI/4.0f,
442  int minNeighborsInRadius = 1);
443 
453 pcl::IndicesPtr RTABMAP_EXP subtractFiltering(
454  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
455  const pcl::IndicesPtr & indices,
456  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
457  const pcl::IndicesPtr & substractIndices,
458  float radiusSearch,
459  float maxAngle = M_PI/4.0f,
460  int minNeighborsInRadius = 1);
461 
471 pcl::IndicesPtr RTABMAP_EXP subtractAdaptiveFiltering(
472  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
473  const pcl::IndicesPtr & indices,
474  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
475  const pcl::IndicesPtr & substractIndices,
476  float radiusSearchRatio = 0.01,
477  int minNeighborsInRadius = 1,
478  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
479 
489 pcl::IndicesPtr RTABMAP_EXP subtractAdaptiveFiltering(
490  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
491  const pcl::IndicesPtr & indices,
492  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
493  const pcl::IndicesPtr & substractIndices,
494  float radiusSearchRatio = 0.01,
495  float maxAngle = M_PI/4.0f,
496  int minNeighborsInRadius = 1,
497  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
498 
499 
504 pcl::IndicesPtr RTABMAP_EXP normalFiltering(
505  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
506  float angleMax,
507  const Eigen::Vector4f & normal,
508  int normalKSearch,
509  const Eigen::Vector4f & viewpoint);
510 pcl::IndicesPtr RTABMAP_EXP normalFiltering(
511  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
512  float angleMax,
513  const Eigen::Vector4f & normal,
514  int normalKSearch,
515  const Eigen::Vector4f & viewpoint);
516 
533 pcl::IndicesPtr RTABMAP_EXP normalFiltering(
534  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
535  const pcl::IndicesPtr & indices,
536  float angleMax,
537  const Eigen::Vector4f & normal,
538  int normalKSearch,
539  const Eigen::Vector4f & viewpoint);
540 pcl::IndicesPtr RTABMAP_EXP normalFiltering(
541  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
542  const pcl::IndicesPtr & indices,
543  float angleMax,
544  const Eigen::Vector4f & normal,
545  int normalKSearch,
546  const Eigen::Vector4f & viewpoint);
547 pcl::IndicesPtr RTABMAP_EXP normalFiltering(
548  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
549  const pcl::IndicesPtr & indices,
550  float angleMax,
551  const Eigen::Vector4f & normal,
552  int normalKSearch,
553  const Eigen::Vector4f & viewpoint);
554 pcl::IndicesPtr RTABMAP_EXP normalFiltering(
555  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
556  const pcl::IndicesPtr & indices,
557  float angleMax,
558  const Eigen::Vector4f & normal,
559  int normalKSearch,
560  const Eigen::Vector4f & viewpoint);
561 
565 std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
566  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
567  float clusterTolerance,
568  int minClusterSize,
569  int maxClusterSize = std::numeric_limits<int>::max(),
570  int * biggestClusterIndex = 0);
571 std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
572  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
573  float clusterTolerance,
574  int minClusterSize,
575  int maxClusterSize = std::numeric_limits<int>::max(),
576  int * biggestClusterIndex = 0);
577 
590 std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
591  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
592  const pcl::IndicesPtr & indices,
593  float clusterTolerance,
594  int minClusterSize,
595  int maxClusterSize = std::numeric_limits<int>::max(),
596  int * biggestClusterIndex = 0);
597 std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
598  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
599  const pcl::IndicesPtr & indices,
600  float clusterTolerance,
601  int minClusterSize,
602  int maxClusterSize = std::numeric_limits<int>::max(),
603  int * biggestClusterIndex = 0);
604 std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
605  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
606  const pcl::IndicesPtr & indices,
607  float clusterTolerance,
608  int minClusterSize,
609  int maxClusterSize = std::numeric_limits<int>::max(),
610  int * biggestClusterIndex = 0);
611 std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
612  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
613  const pcl::IndicesPtr & indices,
614  float clusterTolerance,
615  int minClusterSize,
616  int maxClusterSize = std::numeric_limits<int>::max(),
617  int * biggestClusterIndex = 0);
618 
619 pcl::IndicesPtr RTABMAP_EXP extractIndices(
620  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
621  const pcl::IndicesPtr & indices,
622  bool negative);
623 pcl::IndicesPtr RTABMAP_EXP extractIndices(
624  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
625  const pcl::IndicesPtr & indices,
626  bool negative);
627 pcl::IndicesPtr RTABMAP_EXP extractIndices(
628  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
629  const pcl::IndicesPtr & indices,
630  bool negative);
631 pcl::IndicesPtr RTABMAP_EXP extractIndices(
632  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
633  const pcl::IndicesPtr & indices,
634  bool negative);
635 
636 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP extractIndices(
637  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
638  const pcl::IndicesPtr & indices,
639  bool negative,
640  bool keepOrganized);
641 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP extractIndices(
642  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
643  const pcl::IndicesPtr & indices,
644  bool negative,
645  bool keepOrganized);
646 // PCL default lacks of pcl::PointNormal type support
647 //pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP extractIndices(
648 // const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
649 // const pcl::IndicesPtr & indices,
650 // bool negative,
651 // bool keepOrganized);
652 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP extractIndices(
653  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
654  const pcl::IndicesPtr & indices,
655  bool negative,
656  bool keepOrganized);
657 
658 pcl::IndicesPtr extractPlane(
659  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
660  float distanceThreshold,
661  int maxIterations = 100,
662  pcl::ModelCoefficients * coefficientsOut = 0);
663 pcl::IndicesPtr extractPlane(
664  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
665  const pcl::IndicesPtr & indices,
666  float distanceThreshold,
667  int maxIterations = 100,
668  pcl::ModelCoefficients * coefficientsOut = 0);
669 
670 } // namespace util3d
671 } // namespace rtabmap
672 
673 #endif /* UTIL3D_FILTERING_H_ */
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP subtractFiltering(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &substractCloud, float radiusSearch, int minNeighborsInRadius=1)
pcl::IndicesPtr RTABMAP_EXP cropBox(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false)
std::vector< pcl::IndicesPtr > RTABMAP_EXP extractClusters(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float clusterTolerance, int minClusterSize, int maxClusterSize=std::numeric_limits< int >::max(), int *biggestClusterIndex=0)
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
pcl::IndicesPtr RTABMAP_EXP passThrough(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative=false)
f
GLM_FUNC_DECL detail::tvec3< T, P > axis(detail::tquat< T, P > const &x)
static Transform getIdentity()
Definition: Transform.cpp:364
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP removeNaNFromPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud)
pcl::IndicesPtr RTABMAP_EXP subtractAdaptiveFiltering(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::IndicesPtr &indices, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &substractCloud, const pcl::IndicesPtr &substractIndices, float radiusSearchRatio=0.01, int minNeighborsInRadius=1, const Eigen::Vector3f &viewpoint=Eigen::Vector3f(0, 0, 0))
GLM_FUNC_DECL genType step(genType const &edge, genType const &x)
pcl::IndicesPtr RTABMAP_EXP frustumFiltering(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, const Transform &cameraPose, float horizontalFOV, float verticalFOV, float nearClipPlaneDistance, float farClipPlaneDistance, bool negative=false)
pcl::IndicesPtr RTABMAP_EXP extractIndices(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative)
LaserScan RTABMAP_EXP downsample(const LaserScan &cloud, int step)
#define RTABMAP_EXP
Definition: RtabmapExp.h:38
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP randomSampling(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, int samples)
pcl::IndicesPtr RTABMAP_EXP radiusFiltering(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius)
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
pcl::IndicesPtr extractPlane(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float distanceThreshold, int maxIterations=100, pcl::ModelCoefficients *coefficientsOut=0)
pcl::PointCloud< pcl::PointXYZ >::Ptr uniformSampling(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float voxelSize)
LaserScan RTABMAP_EXP rangeFiltering(const LaserScan &scan, float rangeMin, float rangeMax)
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_EXP removeNaNNormalsFromPointCloud(const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud)
LaserScan RTABMAP_EXP commonFiltering(const LaserScan &scan, int downsamplingStep, float rangeMin=0.0f, float rangeMax=0.0f, float voxelSize=0.0f, int normalK=0, float normalRadius=0.0f, bool forceGroundNormalsUp=false)
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP voxelize(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
pcl::IndicesPtr RTABMAP_EXP normalFiltering(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:43:41