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  float groundNormalsUp = 0.0f);
61  const LaserScan & scan,
62  int downsamplingStep,
63  float rangeMin,
64  float rangeMax,
65  float voxelSize,
66  int normalK,
67  float normalRadius,
68  bool forceGroundNormalsUp), "Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp=0.8, otherwise set groundNormalsUp=0.0.");
69 
70 LaserScan RTABMAP_EXP rangeFiltering(
71  const LaserScan & scan,
72  float rangeMin,
73  float rangeMax);
74 
75 LaserScan RTABMAP_EXP downsample(
76  const LaserScan & cloud,
77  int step);
78 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP downsample(
79  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
80  int step);
81 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP downsample(
82  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
83  int step);
84 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP downsample(
85  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
86  int step);
87 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP downsample(
88  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
89  int step);
90 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP downsample(
91  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
92  int step);
93 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP downsample(
94  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
95  int step);
96 
97 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP voxelize(
98  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
99  const pcl::IndicesPtr & indices,
100  float voxelSize);
101 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP voxelize(
102  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
103  const pcl::IndicesPtr & indices,
104  float voxelSize);
105 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP voxelize(
106  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
107  const pcl::IndicesPtr & indices,
108  float voxelSize);
109 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP voxelize(
110  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
111  const pcl::IndicesPtr & indices,
112  float voxelSize);
113 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP voxelize(
114  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
115  const pcl::IndicesPtr & indices,
116  float voxelSize);
117 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP voxelize(
118  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
119  const pcl::IndicesPtr & indices,
120  float voxelSize);
121 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP voxelize(
122  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
123  float voxelSize);
124 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP voxelize(
125  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
126  float voxelSize);
127 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP voxelize(
128  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
129  float voxelSize);
130 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP voxelize(
131  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
132  float voxelSize);
133 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP voxelize(
134  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
135  float voxelSize);
136 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP voxelize(
137  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
138  float voxelSize);
139 
140 inline pcl::PointCloud<pcl::PointXYZ>::Ptr uniformSampling(
141  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
142  float voxelSize)
143 {
144  return voxelize(cloud, voxelSize);
145 }
146 inline pcl::PointCloud<pcl::PointXYZRGB>::Ptr uniformSampling(
147  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
148  float voxelSize)
149 {
150  return voxelize(cloud, voxelSize);
151 }
152 inline pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr uniformSampling(
153  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
154  float voxelSize)
155 {
156  return voxelize(cloud, voxelSize);
157 }
158 
159 
160 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP randomSampling(
161  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
162  int samples);
163 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP randomSampling(
164  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
165  int samples);
166 
167 
168 pcl::IndicesPtr RTABMAP_EXP passThrough(
169  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
170  const pcl::IndicesPtr & indices,
171  const std::string & axis,
172  float min,
173  float max,
174  bool negative = false);
175 pcl::IndicesPtr RTABMAP_EXP passThrough(
176  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
177  const pcl::IndicesPtr & indices,
178  const std::string & axis,
179  float min,
180  float max,
181  bool negative = false);
182 pcl::IndicesPtr RTABMAP_EXP passThrough(
183  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
184  const pcl::IndicesPtr & indices,
185  const std::string & axis,
186  float min,
187  float max,
188  bool negative = false);
189 pcl::IndicesPtr RTABMAP_EXP passThrough(
190  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
191  const pcl::IndicesPtr & indices,
192  const std::string & axis,
193  float min,
194  float max,
195  bool negative = false);
196 pcl::IndicesPtr RTABMAP_EXP passThrough(
197  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
198  const pcl::IndicesPtr & indices,
199  const std::string & axis,
200  float min,
201  float max,
202  bool negative = false);
203 pcl::IndicesPtr RTABMAP_EXP passThrough(
204  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
205  const pcl::IndicesPtr & indices,
206  const std::string & axis,
207  float min,
208  float max,
209  bool negative = false);
210 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP passThrough(
211  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
212  const std::string & axis,
213  float min,
214  float max,
215  bool negative = false);
216 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP passThrough(
217  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
218  const std::string & axis,
219  float min,
220  float max,
221  bool negative = false);
222 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP passThrough(
223  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
224  const std::string & axis,
225  float min,
226  float max,
227  bool negative = false);
228 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP passThrough(
229  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
230  const std::string & axis,
231  float min,
232  float max,
233  bool negative = false);
234 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP passThrough(
235  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
236  const std::string & axis,
237  float min,
238  float max,
239  bool negative = false);
240 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP passThrough(
241  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
242  const std::string & axis,
243  float min,
244  float max,
245  bool negative = false);
246 
247 pcl::IndicesPtr RTABMAP_EXP cropBox(
248  const pcl::PCLPointCloud2::Ptr & cloud,
249  const pcl::IndicesPtr & indices,
250  const Eigen::Vector4f & min,
251  const Eigen::Vector4f & max,
252  const Transform & transform = Transform::getIdentity(),
253  bool negative = false);
254 pcl::IndicesPtr RTABMAP_EXP cropBox(
255  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
256  const pcl::IndicesPtr & indices,
257  const Eigen::Vector4f & min,
258  const Eigen::Vector4f & max,
259  const Transform & transform = Transform::getIdentity(),
260  bool negative = false);
261 pcl::IndicesPtr RTABMAP_EXP cropBox(
262  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
263  const pcl::IndicesPtr & indices,
264  const Eigen::Vector4f & min,
265  const Eigen::Vector4f & max,
266  const Transform & transform = Transform::getIdentity(),
267  bool negative = false);
268 pcl::IndicesPtr RTABMAP_EXP cropBox(
269  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
270  const pcl::IndicesPtr & indices,
271  const Eigen::Vector4f & min,
272  const Eigen::Vector4f & max,
273  const Transform & transform = Transform::getIdentity(),
274  bool negative = false);
275 pcl::IndicesPtr RTABMAP_EXP cropBox(
276  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
277  const pcl::IndicesPtr & indices,
278  const Eigen::Vector4f & min,
279  const Eigen::Vector4f & max,
280  const Transform & transform = Transform::getIdentity(),
281  bool negative = false);
282 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP cropBox(
283  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
284  const Eigen::Vector4f & min,
285  const Eigen::Vector4f & max,
286  const Transform & transform = Transform::getIdentity(),
287  bool negative = false);
288 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP cropBox(
289  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
290  const Eigen::Vector4f & min,
291  const Eigen::Vector4f & max,
292  const Transform & transform = Transform::getIdentity(),
293  bool negative = false);
294 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP cropBox(
295  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
296  const Eigen::Vector4f & min,
297  const Eigen::Vector4f & max,
298  const Transform & transform = Transform::getIdentity(),
299  bool negative = false);
300 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP cropBox(
301  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
302  const Eigen::Vector4f & min,
303  const Eigen::Vector4f & max,
304  const Transform & transform = Transform::getIdentity(),
305  bool negative = false);
306 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP cropBox(
307  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
308  const Eigen::Vector4f & min,
309  const Eigen::Vector4f & max,
310  const Transform & transform = Transform::getIdentity(),
311  bool negative = false);
312 
313 //Note: This assumes a coordinate system where X is forward, * Y is up, and Z is right.
314 pcl::IndicesPtr RTABMAP_EXP frustumFiltering(
315  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
316  const pcl::IndicesPtr & indices,
317  const Transform & cameraPose,
318  float horizontalFOV, // in degrees, xfov = atan((image_width/2)/fx)*2
319  float verticalFOV, // in degrees, yfov = atan((image_height/2)/fy)*2
320  float nearClipPlaneDistance,
321  float farClipPlaneDistance,
322  bool negative = false);
323 //Note: This assumes a coordinate system where X is forward, * Y is up, and Z is right.
324 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP frustumFiltering(
325  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
326  const Transform & cameraPose,
327  float horizontalFOV, // in degrees, xfov = atan((image_width/2)/fx)*2
328  float verticalFOV, // in degrees, yfov = atan((image_height/2)/fy)*2
329  float nearClipPlaneDistance,
330  float farClipPlaneDistance,
331  bool negative = false);
332 //Note: This assumes a coordinate system where X is forward, * Y is up, and Z is right.
333 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP frustumFiltering(
334  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
335  const Transform & cameraPose,
336  float horizontalFOV, // in degrees, xfov = atan((image_width/2)/fx)*2
337  float verticalFOV, // in degrees, yfov = atan((image_height/2)/fy)*2
338  float nearClipPlaneDistance,
339  float farClipPlaneDistance,
340  bool negative = false);
341 
342 
343 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP removeNaNFromPointCloud(
344  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud);
345 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP removeNaNFromPointCloud(
346  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud);
347 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_EXP removeNaNFromPointCloud(
348  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud);
349 
350 
351 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP removeNaNNormalsFromPointCloud(
352  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud);
353 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP removeNaNNormalsFromPointCloud(
354  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud);
355 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP removeNaNNormalsFromPointCloud(
356  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud);
357 
362 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
363  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
364  float radiusSearch,
365  int minNeighborsInRadius);
366 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
367  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
368  float radiusSearch,
369  int minNeighborsInRadius);
370 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
371  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
372  float radiusSearch,
373  int minNeighborsInRadius);
374 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
375  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
376  float radiusSearch,
377  int minNeighborsInRadius);
378 
391 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
392  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
393  const pcl::IndicesPtr & indices,
394  float radiusSearch,
395  int minNeighborsInRadius);
396 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
397  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
398  const pcl::IndicesPtr & indices,
399  float radiusSearch,
400  int minNeighborsInRadius);
401 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
402  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
403  const pcl::IndicesPtr & indices,
404  float radiusSearch,
405  int minNeighborsInRadius);
406 pcl::IndicesPtr RTABMAP_EXP radiusFiltering(
407  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
408  const pcl::IndicesPtr & indices,
409  float radiusSearch,
410  int minNeighborsInRadius);
411 
415 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP subtractFiltering(
416  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
417  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
418  float radiusSearch,
419  int minNeighborsInRadius = 1);
420 
430 pcl::IndicesPtr RTABMAP_EXP subtractFiltering(
431  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
432  const pcl::IndicesPtr & indices,
433  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
434  const pcl::IndicesPtr & substractIndices,
435  float radiusSearch,
436  int minNeighborsInRadius = 1);
437 
441 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP subtractFiltering(
442  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
443  const pcl::PointCloud<pcl::PointNormal>::Ptr & substractCloud,
444  float radiusSearch,
445  float maxAngle = M_PI/4.0f,
446  int minNeighborsInRadius = 1);
447 
457 pcl::IndicesPtr RTABMAP_EXP subtractFiltering(
458  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
459  const pcl::IndicesPtr & indices,
460  const pcl::PointCloud<pcl::PointNormal>::Ptr & substractCloud,
461  const pcl::IndicesPtr & substractIndices,
462  float radiusSearch,
463  float maxAngle = M_PI/4.0f,
464  int minNeighborsInRadius = 1);
465 
469 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_EXP subtractFiltering(
470  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
471  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & substractCloud,
472  float radiusSearch,
473  float maxAngle = M_PI/4.0f,
474  int minNeighborsInRadius = 1);
475 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP subtractFiltering(
476  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
477  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
478  float radiusSearch,
479  float maxAngle = M_PI/4.0f,
480  int minNeighborsInRadius = 1);
481 
491 pcl::IndicesPtr RTABMAP_EXP subtractFiltering(
492  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
493  const pcl::IndicesPtr & indices,
494  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & substractCloud,
495  const pcl::IndicesPtr & substractIndices,
496  float radiusSearch,
497  float maxAngle = M_PI/4.0f,
498  int minNeighborsInRadius = 1);
499 pcl::IndicesPtr RTABMAP_EXP subtractFiltering(
500  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
501  const pcl::IndicesPtr & indices,
502  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
503  const pcl::IndicesPtr & substractIndices,
504  float radiusSearch,
505  float maxAngle = M_PI/4.0f,
506  int minNeighborsInRadius = 1);
507 
517 pcl::IndicesPtr RTABMAP_EXP subtractAdaptiveFiltering(
518  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
519  const pcl::IndicesPtr & indices,
520  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
521  const pcl::IndicesPtr & substractIndices,
522  float radiusSearchRatio = 0.01,
523  int minNeighborsInRadius = 1,
524  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
525 
535 pcl::IndicesPtr RTABMAP_EXP subtractAdaptiveFiltering(
536  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
537  const pcl::IndicesPtr & indices,
538  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
539  const pcl::IndicesPtr & substractIndices,
540  float radiusSearchRatio = 0.01,
541  float maxAngle = M_PI/4.0f,
542  int minNeighborsInRadius = 1,
543  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
544 
545 
550 pcl::IndicesPtr RTABMAP_EXP normalFiltering(
551  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
552  float angleMax,
553  const Eigen::Vector4f & normal,
554  int normalKSearch,
555  const Eigen::Vector4f & viewpoint);
556 pcl::IndicesPtr RTABMAP_EXP normalFiltering(
557  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
558  float angleMax,
559  const Eigen::Vector4f & normal,
560  int normalKSearch,
561  const Eigen::Vector4f & viewpoint);
562 
579 pcl::IndicesPtr RTABMAP_EXP normalFiltering(
580  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
581  const pcl::IndicesPtr & indices,
582  float angleMax,
583  const Eigen::Vector4f & normal,
584  int normalKSearch,
585  const Eigen::Vector4f & viewpoint);
586 pcl::IndicesPtr RTABMAP_EXP normalFiltering(
587  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
588  const pcl::IndicesPtr & indices,
589  float angleMax,
590  const Eigen::Vector4f & normal,
591  int normalKSearch,
592  const Eigen::Vector4f & viewpoint);
593 pcl::IndicesPtr RTABMAP_EXP normalFiltering(
594  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
595  const pcl::IndicesPtr & indices,
596  float angleMax,
597  const Eigen::Vector4f & normal,
598  int normalKSearch,
599  const Eigen::Vector4f & viewpoint);
600 pcl::IndicesPtr RTABMAP_EXP normalFiltering(
601  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
602  const pcl::IndicesPtr & indices,
603  float angleMax,
604  const Eigen::Vector4f & normal,
605  int normalKSearch,
606  const Eigen::Vector4f & viewpoint);
607 
611 std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
612  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
613  float clusterTolerance,
614  int minClusterSize,
615  int maxClusterSize = std::numeric_limits<int>::max(),
616  int * biggestClusterIndex = 0);
617 std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
618  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
619  float clusterTolerance,
620  int minClusterSize,
621  int maxClusterSize = std::numeric_limits<int>::max(),
622  int * biggestClusterIndex = 0);
623 
636 std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
637  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
638  const pcl::IndicesPtr & indices,
639  float clusterTolerance,
640  int minClusterSize,
641  int maxClusterSize = std::numeric_limits<int>::max(),
642  int * biggestClusterIndex = 0);
643 std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
644  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
645  const pcl::IndicesPtr & indices,
646  float clusterTolerance,
647  int minClusterSize,
648  int maxClusterSize = std::numeric_limits<int>::max(),
649  int * biggestClusterIndex = 0);
650 std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
651  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
652  const pcl::IndicesPtr & indices,
653  float clusterTolerance,
654  int minClusterSize,
655  int maxClusterSize = std::numeric_limits<int>::max(),
656  int * biggestClusterIndex = 0);
657 std::vector<pcl::IndicesPtr> RTABMAP_EXP extractClusters(
658  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
659  const pcl::IndicesPtr & indices,
660  float clusterTolerance,
661  int minClusterSize,
662  int maxClusterSize = std::numeric_limits<int>::max(),
663  int * biggestClusterIndex = 0);
664 
665 pcl::IndicesPtr RTABMAP_EXP extractIndices(
666  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
667  const pcl::IndicesPtr & indices,
668  bool negative);
669 pcl::IndicesPtr RTABMAP_EXP extractIndices(
670  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
671  const pcl::IndicesPtr & indices,
672  bool negative);
673 pcl::IndicesPtr RTABMAP_EXP extractIndices(
674  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
675  const pcl::IndicesPtr & indices,
676  bool negative);
677 pcl::IndicesPtr RTABMAP_EXP extractIndices(
678  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
679  const pcl::IndicesPtr & indices,
680  bool negative);
681 
682 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_EXP extractIndices(
683  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
684  const pcl::IndicesPtr & indices,
685  bool negative,
686  bool keepOrganized);
687 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_EXP extractIndices(
688  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
689  const pcl::IndicesPtr & indices,
690  bool negative,
691  bool keepOrganized);
692 // PCL default lacks of pcl::PointNormal type support
693 //pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_EXP extractIndices(
694 // const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
695 // const pcl::IndicesPtr & indices,
696 // bool negative,
697 // bool keepOrganized);
698 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_EXP extractIndices(
699  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
700  const pcl::IndicesPtr & indices,
701  bool negative,
702  bool keepOrganized);
703 
704 pcl::IndicesPtr extractPlane(
705  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
706  float distanceThreshold,
707  int maxIterations = 100,
708  pcl::ModelCoefficients * coefficientsOut = 0);
709 pcl::IndicesPtr extractPlane(
710  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
711  const pcl::IndicesPtr & indices,
712  float distanceThreshold,
713  int maxIterations = 100,
714  pcl::ModelCoefficients * coefficientsOut = 0);
715 
716 } // namespace util3d
717 } // namespace rtabmap
718 
719 #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)
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:380
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
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, float groundNormalsUp=0.0f)
RTABMAP_DEPRECATED(pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP cloudFromDepth(const cv::Mat &imageDepth, float cx, float cy, float fx, float fy, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0),"Use cloudFromDepth with CameraModel interface.")
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)
pcl::IndicesPtr RTABMAP_EXP cropBox(const pcl::PCLPointCloud2::Ptr &cloud, const pcl::IndicesPtr &indices, const Eigen::Vector4f &min, const Eigen::Vector4f &max, const Transform &transform=Transform::getIdentity(), bool negative=false)
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)
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 Mon Dec 14 2020 03:37:06