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 
31 #include <rtabmap/core/rtabmap_core_export.h>
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 
51 LaserScan RTABMAP_CORE_EXPORT commonFiltering(
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);
60 // Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp=0.8, otherwise set groundNormalsUp=0.0.
61 RTABMAP_DEPRECATED LaserScan RTABMAP_CORE_EXPORT commonFiltering(
62  const LaserScan & scan,
63  int downsamplingStep,
64  float rangeMin,
65  float rangeMax,
66  float voxelSize,
67  int normalK,
68  float normalRadius,
69  bool forceGroundNormalsUp);
70 
71 LaserScan RTABMAP_CORE_EXPORT rangeFiltering(
72  const LaserScan & scan,
73  float rangeMin,
74  float rangeMax);
75 
76 LaserScan RTABMAP_CORE_EXPORT downsample(
77  const LaserScan & cloud,
78  int step);
79 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT downsample(
80  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
81  int step);
82 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT downsample(
83  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
84  int step);
85 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT downsample(
86  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
87  int step);
88 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT downsample(
89  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
90  int step);
91 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT downsample(
92  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
93  int step);
94 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT downsample(
95  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
96  int step);
97 
98 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT voxelize(
99  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
100  const pcl::IndicesPtr & indices,
101  float voxelSize);
102 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT voxelize(
103  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
104  const pcl::IndicesPtr & indices,
105  float voxelSize);
106 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT voxelize(
107  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
108  const pcl::IndicesPtr & indices,
109  float voxelSize);
110 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT voxelize(
111  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
112  const pcl::IndicesPtr & indices,
113  float voxelSize);
114 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT voxelize(
115  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
116  const pcl::IndicesPtr & indices,
117  float voxelSize);
118 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT voxelize(
119  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
120  const pcl::IndicesPtr & indices,
121  float voxelSize);
122 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT voxelize(
123  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
124  float voxelSize);
125 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT voxelize(
126  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
127  float voxelSize);
128 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT voxelize(
129  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
130  float voxelSize);
131 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT voxelize(
132  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
133  float voxelSize);
134 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT voxelize(
135  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
136  float voxelSize);
137 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT voxelize(
138  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
139  float voxelSize);
140 
141 inline pcl::PointCloud<pcl::PointXYZ>::Ptr uniformSampling(
142  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
143  float voxelSize)
144 {
145  return voxelize(cloud, voxelSize);
146 }
147 inline pcl::PointCloud<pcl::PointXYZRGB>::Ptr uniformSampling(
148  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
149  float voxelSize)
150 {
151  return voxelize(cloud, voxelSize);
152 }
153 inline pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr uniformSampling(
154  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
155  float voxelSize)
156 {
157  return voxelize(cloud, voxelSize);
158 }
159 
160 
161 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT randomSampling(
162  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
163  int samples);
164 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT randomSampling(
165  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
166  int samples);
167 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT randomSampling(
168  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
169  int samples);
170 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT randomSampling(
171  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
172  int samples);
173 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT randomSampling(
174  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
175  int samples);
176 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT randomSampling(
177  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
178  int samples);
179 
180 
181 pcl::IndicesPtr RTABMAP_CORE_EXPORT passThrough(
182  const pcl::PointCloud<pcl::PointXYZ>::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_CORE_EXPORT passThrough(
189  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
190  const pcl::IndicesPtr & indices,
191  const std::string & axis,
192  float min,
193  float max,
194  bool negative = false);
195 pcl::IndicesPtr RTABMAP_CORE_EXPORT passThrough(
196  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
197  const pcl::IndicesPtr & indices,
198  const std::string & axis,
199  float min,
200  float max,
201  bool negative = false);
202 pcl::IndicesPtr RTABMAP_CORE_EXPORT passThrough(
203  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
204  const pcl::IndicesPtr & indices,
205  const std::string & axis,
206  float min,
207  float max,
208  bool negative = false);
209 pcl::IndicesPtr RTABMAP_CORE_EXPORT passThrough(
210  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
211  const pcl::IndicesPtr & indices,
212  const std::string & axis,
213  float min,
214  float max,
215  bool negative = false);
216 pcl::IndicesPtr RTABMAP_CORE_EXPORT passThrough(
217  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
218  const pcl::IndicesPtr & indices,
219  const std::string & axis,
220  float min,
221  float max,
222  bool negative = false);
223 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT passThrough(
224  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
225  const std::string & axis,
226  float min,
227  float max,
228  bool negative = false);
229 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT passThrough(
230  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
231  const std::string & axis,
232  float min,
233  float max,
234  bool negative = false);
235 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT passThrough(
236  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
237  const std::string & axis,
238  float min,
239  float max,
240  bool negative = false);
241 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT passThrough(
242  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
243  const std::string & axis,
244  float min,
245  float max,
246  bool negative = false);
247 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT passThrough(
248  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
249  const std::string & axis,
250  float min,
251  float max,
252  bool negative = false);
253 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT passThrough(
254  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
255  const std::string & axis,
256  float min,
257  float max,
258  bool negative = false);
259 
260 pcl::IndicesPtr RTABMAP_CORE_EXPORT cropBox(
261  const pcl::PCLPointCloud2::Ptr & cloud,
262  const pcl::IndicesPtr & indices,
263  const Eigen::Vector4f & min,
264  const Eigen::Vector4f & max,
265  const Transform & transform = Transform::getIdentity(),
266  bool negative = false);
267 pcl::IndicesPtr RTABMAP_CORE_EXPORT cropBox(
268  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
269  const pcl::IndicesPtr & indices,
270  const Eigen::Vector4f & min,
271  const Eigen::Vector4f & max,
272  const Transform & transform = Transform::getIdentity(),
273  bool negative = false);
274 pcl::IndicesPtr RTABMAP_CORE_EXPORT cropBox(
275  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
276  const pcl::IndicesPtr & indices,
277  const Eigen::Vector4f & min,
278  const Eigen::Vector4f & max,
279  const Transform & transform = Transform::getIdentity(),
280  bool negative = false);
281 pcl::IndicesPtr RTABMAP_CORE_EXPORT cropBox(
282  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
283  const pcl::IndicesPtr & indices,
284  const Eigen::Vector4f & min,
285  const Eigen::Vector4f & max,
286  const Transform & transform = Transform::getIdentity(),
287  bool negative = false);
288 pcl::IndicesPtr RTABMAP_CORE_EXPORT cropBox(
289  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
290  const pcl::IndicesPtr & indices,
291  const Eigen::Vector4f & min,
292  const Eigen::Vector4f & max,
293  const Transform & transform = Transform::getIdentity(),
294  bool negative = false);
295 pcl::IndicesPtr RTABMAP_CORE_EXPORT cropBox(
296  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
297  const pcl::IndicesPtr & indices,
298  const Eigen::Vector4f & min,
299  const Eigen::Vector4f & max,
300  const Transform & transform = Transform::getIdentity(),
301  bool negative = false);
302 pcl::IndicesPtr RTABMAP_CORE_EXPORT cropBox(
303  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
304  const pcl::IndicesPtr & indices,
305  const Eigen::Vector4f & min,
306  const Eigen::Vector4f & max,
307  const Transform & transform = Transform::getIdentity(),
308  bool negative = false);
309 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT cropBox(
310  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
311  const Eigen::Vector4f & min,
312  const Eigen::Vector4f & max,
313  const Transform & transform = Transform::getIdentity(),
314  bool negative = false);
315 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT cropBox(
316  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
317  const Eigen::Vector4f & min,
318  const Eigen::Vector4f & max,
319  const Transform & transform = Transform::getIdentity(),
320  bool negative = false);
321 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT cropBox(
322  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
323  const Eigen::Vector4f & min,
324  const Eigen::Vector4f & max,
325  const Transform & transform = Transform::getIdentity(),
326  bool negative = false);
327 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT cropBox(
328  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
329  const Eigen::Vector4f & min,
330  const Eigen::Vector4f & max,
331  const Transform & transform = Transform::getIdentity(),
332  bool negative = false);
333 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT cropBox(
334  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
335  const Eigen::Vector4f & min,
336  const Eigen::Vector4f & max,
337  const Transform & transform = Transform::getIdentity(),
338  bool negative = false);
339 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT cropBox(
340  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
341  const Eigen::Vector4f & min,
342  const Eigen::Vector4f & max,
343  const Transform & transform = Transform::getIdentity(),
344  bool negative = false);
345 
346 //Note: This assumes a coordinate system where X is forward, * Y is up, and Z is right.
347 pcl::IndicesPtr RTABMAP_CORE_EXPORT frustumFiltering(
348  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
349  const pcl::IndicesPtr & indices,
350  const Transform & cameraPose,
351  float horizontalFOV, // in degrees, xfov = atan((image_width/2)/fx)*2
352  float verticalFOV, // in degrees, yfov = atan((image_height/2)/fy)*2
353  float nearClipPlaneDistance,
354  float farClipPlaneDistance,
355  bool negative = false);
356 //Note: This assumes a coordinate system where X is forward, * Y is up, and Z is right.
357 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT frustumFiltering(
358  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
359  const Transform & cameraPose,
360  float horizontalFOV, // in degrees, xfov = atan((image_width/2)/fx)*2
361  float verticalFOV, // in degrees, yfov = atan((image_height/2)/fy)*2
362  float nearClipPlaneDistance,
363  float farClipPlaneDistance,
364  bool negative = false);
365 //Note: This assumes a coordinate system where X is forward, * Y is up, and Z is right.
366 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT frustumFiltering(
367  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
368  const Transform & cameraPose,
369  float horizontalFOV, // in degrees, xfov = atan((image_width/2)/fx)*2
370  float verticalFOV, // in degrees, yfov = atan((image_height/2)/fy)*2
371  float nearClipPlaneDistance,
372  float farClipPlaneDistance,
373  bool negative = false);
374 
375 
376 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT removeNaNFromPointCloud(
377  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud);
378 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT removeNaNFromPointCloud(
379  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud);
380 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT removeNaNFromPointCloud(
381  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud);
382 pcl::PCLPointCloud2::Ptr RTABMAP_CORE_EXPORT removeNaNFromPointCloud(
383  const pcl::PCLPointCloud2::Ptr & cloud);
384 
385 
386 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT removeNaNNormalsFromPointCloud(
387  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud);
388 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT removeNaNNormalsFromPointCloud(
389  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud);
390 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT removeNaNNormalsFromPointCloud(
391  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud);
392 
397 pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(
398  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
399  float radiusSearch,
400  int minNeighborsInRadius);
401 pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(
402  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
403  float radiusSearch,
404  int minNeighborsInRadius);
405 pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(
406  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
407  float radiusSearch,
408  int minNeighborsInRadius);
409 pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(
410  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
411  float radiusSearch,
412  int minNeighborsInRadius);
413 pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(
414  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
415  float radiusSearch,
416  int minNeighborsInRadius);
417 pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(
418  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
419  float radiusSearch,
420  int minNeighborsInRadius);
421 
434 pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(
435  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
436  const pcl::IndicesPtr & indices,
437  float radiusSearch,
438  int minNeighborsInRadius);
439 pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(
440  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
441  const pcl::IndicesPtr & indices,
442  float radiusSearch,
443  int minNeighborsInRadius);
444 pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(
445  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
446  const pcl::IndicesPtr & indices,
447  float radiusSearch,
448  int minNeighborsInRadius);
449 pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(
450  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
451  const pcl::IndicesPtr & indices,
452  float radiusSearch,
453  int minNeighborsInRadius);
454 pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(
455  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
456  const pcl::IndicesPtr & indices,
457  float radiusSearch,
458  int minNeighborsInRadius);
459 pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(
460  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
461  const pcl::IndicesPtr & indices,
462  float radiusSearch,
463  int minNeighborsInRadius);
464 
465 /* for convenience */
466 pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(
467  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
468  const std::vector<int> & viewpointIndices,
469  const std::map<int, Transform> & viewpoints,
470  float factor=0.01f,
471  float neighborScale=2.0f);
472 pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(
473  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
474  const std::vector<int> & viewpointIndices,
475  const std::map<int, Transform> & viewpoints,
476  float factor=0.01f,
477  float neighborScale=2.0f);
478 pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(
479  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
480  const std::vector<int> & viewpointIndices,
481  const std::map<int, Transform> & viewpoints,
482  float factor=0.01f,
483  float neighborScale=2.0f);
484 pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(
485  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
486  const std::vector<int> & viewpointIndices,
487  const std::map<int, Transform> & viewpoints,
488  float factor=0.01f,
489  float neighborScale=2.0f);
490 pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(
491  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
492  const std::vector<int> & viewpointIndices,
493  const std::map<int, Transform> & viewpoints,
494  float factor=0.01f,
495  float neighborScale=2.0f);
496 pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(
497  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
498  const std::vector<int> & viewpointIndices,
499  const std::map<int, Transform> & viewpoints,
500  float factor=0.01f,
501  float neighborScale=2.0f);
502 
515 pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(
516  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
517  const pcl::IndicesPtr & indices,
518  const std::vector<int> & viewpointIndices,
519  const std::map<int, Transform> & viewpoints,
520  float factor=0.01f,
521  float neighborScale=2.0f);
522 pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(
523  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
524  const pcl::IndicesPtr & indices,
525  const std::vector<int> & viewpointIndices,
526  const std::map<int, Transform> & viewpoints,
527  float factor=0.01f,
528  float neighborScale=2.0f);
529 pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(
530  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
531  const pcl::IndicesPtr & indices,
532  const std::vector<int> & viewpointIndices,
533  const std::map<int, Transform> & viewpoints,
534  float factor=0.01f,
535  float neighborScale=2.0f);
536 pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(
537  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
538  const pcl::IndicesPtr & indices,
539  const std::vector<int> & viewpointIndices,
540  const std::map<int, Transform> & viewpoints,
541  float factor=0.01f,
542  float neighborScale=2.0f);
543 pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(
544  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
545  const pcl::IndicesPtr & indices,
546  const std::vector<int> & viewpointIndices,
547  const std::map<int, Transform> & viewpoints,
548  float factor=0.01f,
549  float neighborScale=2.0f);
550 pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(
551  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
552  const pcl::IndicesPtr & indices,
553  const std::vector<int> & viewpointIndices,
554  const std::map<int, Transform> & viewpoints,
555  float factor=0.01f,
556  float neighborScale=2.0f);
557 
561 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT subtractFiltering(
562  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
563  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
564  float radiusSearch,
565  int minNeighborsInRadius = 1);
566 
576 pcl::IndicesPtr RTABMAP_CORE_EXPORT subtractFiltering(
577  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
578  const pcl::IndicesPtr & indices,
579  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
580  const pcl::IndicesPtr & substractIndices,
581  float radiusSearch,
582  int minNeighborsInRadius = 1);
583 
587 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT subtractFiltering(
588  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
589  const pcl::PointCloud<pcl::PointNormal>::Ptr & substractCloud,
590  float radiusSearch,
591  float maxAngle = M_PI/4.0f,
592  int minNeighborsInRadius = 1);
593 
603 pcl::IndicesPtr RTABMAP_CORE_EXPORT subtractFiltering(
604  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
605  const pcl::IndicesPtr & indices,
606  const pcl::PointCloud<pcl::PointNormal>::Ptr & substractCloud,
607  const pcl::IndicesPtr & substractIndices,
608  float radiusSearch,
609  float maxAngle = M_PI/4.0f,
610  int minNeighborsInRadius = 1);
611 
615 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT subtractFiltering(
616  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
617  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & substractCloud,
618  float radiusSearch,
619  float maxAngle = M_PI/4.0f,
620  int minNeighborsInRadius = 1);
621 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT subtractFiltering(
622  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
623  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
624  float radiusSearch,
625  float maxAngle = M_PI/4.0f,
626  int minNeighborsInRadius = 1);
627 
637 pcl::IndicesPtr RTABMAP_CORE_EXPORT subtractFiltering(
638  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
639  const pcl::IndicesPtr & indices,
640  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & substractCloud,
641  const pcl::IndicesPtr & substractIndices,
642  float radiusSearch,
643  float maxAngle = M_PI/4.0f,
644  int minNeighborsInRadius = 1);
645 pcl::IndicesPtr RTABMAP_CORE_EXPORT subtractFiltering(
646  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
647  const pcl::IndicesPtr & indices,
648  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
649  const pcl::IndicesPtr & substractIndices,
650  float radiusSearch,
651  float maxAngle = M_PI/4.0f,
652  int minNeighborsInRadius = 1);
653 
663 pcl::IndicesPtr RTABMAP_CORE_EXPORT subtractAdaptiveFiltering(
664  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
665  const pcl::IndicesPtr & indices,
666  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
667  const pcl::IndicesPtr & substractIndices,
668  float radiusSearchRatio = 0.01,
669  int minNeighborsInRadius = 1,
670  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
671 
681 pcl::IndicesPtr RTABMAP_CORE_EXPORT subtractAdaptiveFiltering(
682  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
683  const pcl::IndicesPtr & indices,
684  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
685  const pcl::IndicesPtr & substractIndices,
686  float radiusSearchRatio = 0.01,
687  float maxAngle = M_PI/4.0f,
688  int minNeighborsInRadius = 1,
689  const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
690 
691 
696 pcl::IndicesPtr RTABMAP_CORE_EXPORT normalFiltering(
697  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
698  float angleMax,
699  const Eigen::Vector4f & normal,
700  int normalKSearch,
701  const Eigen::Vector4f & viewpoint,
702  float groundNormalsUp = 0.0f);
703 pcl::IndicesPtr RTABMAP_CORE_EXPORT normalFiltering(
704  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
705  float angleMax,
706  const Eigen::Vector4f & normal,
707  int normalKSearch,
708  const Eigen::Vector4f & viewpoint,
709  float groundNormalsUp = 0.0f);
710 
727 pcl::IndicesPtr RTABMAP_CORE_EXPORT normalFiltering(
728  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
729  const pcl::IndicesPtr & indices,
730  float angleMax,
731  const Eigen::Vector4f & normal,
732  int normalKSearch,
733  const Eigen::Vector4f & viewpoint,
734  float groundNormalsUp = 0.0f);
735 pcl::IndicesPtr RTABMAP_CORE_EXPORT normalFiltering(
736  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
737  const pcl::IndicesPtr & indices,
738  float angleMax,
739  const Eigen::Vector4f & normal,
740  int normalKSearch,
741  const Eigen::Vector4f & viewpoint,
742  float groundNormalsUp = 0.0f);
743 pcl::IndicesPtr RTABMAP_CORE_EXPORT normalFiltering(
744  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
745  const pcl::IndicesPtr & indices,
746  float angleMax,
747  const Eigen::Vector4f & normal,
748  int normalKSearch,
749  const Eigen::Vector4f & viewpoint,
750  float groundNormalsUp = 0.0f);
751 pcl::IndicesPtr RTABMAP_CORE_EXPORT normalFiltering(
752  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
753  const pcl::IndicesPtr & indices,
754  float angleMax,
755  const Eigen::Vector4f & normal,
756  int normalKSearch,
757  const Eigen::Vector4f & viewpoint,
758  float groundNormalsUp = 0.0f);
759 pcl::IndicesPtr RTABMAP_CORE_EXPORT normalFiltering(
760  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
761  const pcl::IndicesPtr & indices,
762  float angleMax,
763  const Eigen::Vector4f & normal,
764  int normalKSearch,
765  const Eigen::Vector4f & viewpoint,
766  float groundNormalsUp = 0.0f);
767 pcl::IndicesPtr RTABMAP_CORE_EXPORT normalFiltering(
768  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
769  const pcl::IndicesPtr & indices,
770  float angleMax,
771  const Eigen::Vector4f & normal,
772  int normalKSearch,
773  const Eigen::Vector4f & viewpoint,
774  float groundNormalsUp = 0.0f);
775 
779 std::vector<pcl::IndicesPtr> RTABMAP_CORE_EXPORT extractClusters(
780  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
781  float clusterTolerance,
782  int minClusterSize,
783  int maxClusterSize = std::numeric_limits<int>::max(),
784  int * biggestClusterIndex = 0);
785 std::vector<pcl::IndicesPtr> RTABMAP_CORE_EXPORT extractClusters(
786  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
787  float clusterTolerance,
788  int minClusterSize,
789  int maxClusterSize = std::numeric_limits<int>::max(),
790  int * biggestClusterIndex = 0);
791 
804 std::vector<pcl::IndicesPtr> RTABMAP_CORE_EXPORT extractClusters(
805  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
806  const pcl::IndicesPtr & indices,
807  float clusterTolerance,
808  int minClusterSize,
809  int maxClusterSize = std::numeric_limits<int>::max(),
810  int * biggestClusterIndex = 0);
811 std::vector<pcl::IndicesPtr> RTABMAP_CORE_EXPORT extractClusters(
812  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
813  const pcl::IndicesPtr & indices,
814  float clusterTolerance,
815  int minClusterSize,
816  int maxClusterSize = std::numeric_limits<int>::max(),
817  int * biggestClusterIndex = 0);
818 std::vector<pcl::IndicesPtr> RTABMAP_CORE_EXPORT extractClusters(
819  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
820  const pcl::IndicesPtr & indices,
821  float clusterTolerance,
822  int minClusterSize,
823  int maxClusterSize = std::numeric_limits<int>::max(),
824  int * biggestClusterIndex = 0);
825 std::vector<pcl::IndicesPtr> RTABMAP_CORE_EXPORT extractClusters(
826  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
827  const pcl::IndicesPtr & indices,
828  float clusterTolerance,
829  int minClusterSize,
830  int maxClusterSize = std::numeric_limits<int>::max(),
831  int * biggestClusterIndex = 0);
832 std::vector<pcl::IndicesPtr> RTABMAP_CORE_EXPORT extractClusters(
833  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
834  const pcl::IndicesPtr & indices,
835  float clusterTolerance,
836  int minClusterSize,
837  int maxClusterSize = std::numeric_limits<int>::max(),
838  int * biggestClusterIndex = 0);
839 std::vector<pcl::IndicesPtr> RTABMAP_CORE_EXPORT extractClusters(
840  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
841  const pcl::IndicesPtr & indices,
842  float clusterTolerance,
843  int minClusterSize,
844  int maxClusterSize = std::numeric_limits<int>::max(),
845  int * biggestClusterIndex = 0);
846 
847 pcl::IndicesPtr RTABMAP_CORE_EXPORT extractIndices(
848  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
849  const pcl::IndicesPtr & indices,
850  bool negative);
851 pcl::IndicesPtr RTABMAP_CORE_EXPORT extractIndices(
852  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
853  const pcl::IndicesPtr & indices,
854  bool negative);
855 pcl::IndicesPtr RTABMAP_CORE_EXPORT extractIndices(
856  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
857  const pcl::IndicesPtr & indices,
858  bool negative);
859 pcl::IndicesPtr RTABMAP_CORE_EXPORT extractIndices(
860  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
861  const pcl::IndicesPtr & indices,
862  bool negative);
863 pcl::IndicesPtr RTABMAP_CORE_EXPORT extractIndices(
864  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
865  const pcl::IndicesPtr & indices,
866  bool negative);
867 pcl::IndicesPtr RTABMAP_CORE_EXPORT extractIndices(
868  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
869  const pcl::IndicesPtr & indices,
870  bool negative);
871 
872 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT extractIndices(
873  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
874  const pcl::IndicesPtr & indices,
875  bool negative,
876  bool keepOrganized);
877 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT extractIndices(
878  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
879  const pcl::IndicesPtr & indices,
880  bool negative,
881  bool keepOrganized);
882 // PCL default lacks of pcl::PointNormal type support
883 //pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT extractIndices(
884 // const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
885 // const pcl::IndicesPtr & indices,
886 // bool negative,
887 // bool keepOrganized);
888 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT extractIndices(
889  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
890  const pcl::IndicesPtr & indices,
891  bool negative,
892  bool keepOrganized);
893 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT extractIndices(
894  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
895  const pcl::IndicesPtr & indices,
896  bool negative,
897  bool keepOrganized);
898 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT extractIndices(
899  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
900  const pcl::IndicesPtr & indices,
901  bool negative,
902  bool keepOrganized);
903 
904 pcl::IndicesPtr extractPlane(
905  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
906  float distanceThreshold,
907  int maxIterations = 100,
908  pcl::ModelCoefficients * coefficientsOut = 0);
909 pcl::IndicesPtr extractPlane(
910  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
911  const pcl::IndicesPtr & indices,
912  float distanceThreshold,
913  int maxIterations = 100,
914  pcl::ModelCoefficients * coefficientsOut = 0);
915 
916 } // namespace util3d
917 } // namespace rtabmap
918 
919 #endif /* UTIL3D_FILTERING_H_ */
glm::min
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
rtabmap::util3d::cropBox
pcl::IndicesPtr RTABMAP_CORE_EXPORT 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)
Definition: util3d_filtering.cpp:826
glm::axis
GLM_FUNC_DECL detail::tvec3< T, P > axis(detail::tquat< T, P > const &x)
rtabmap::util3d::removeNaNNormalsFromPointCloud
pcl::PointCloud< pcl::PointNormal >::Ptr RTABMAP_CORE_EXPORT removeNaNNormalsFromPointCloud(const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud)
Definition: util3d_filtering.cpp:1070
rtabmap::Transform::getIdentity
static Transform getIdentity()
Definition: Transform.cpp:411
rtabmap::util3d::passThrough
pcl::IndicesPtr RTABMAP_CORE_EXPORT passThrough(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative=false)
Definition: util3d_filtering.cpp:730
rtabmap::RTABMAP_DEPRECATED
RTABMAP_DEPRECATED(typedef SensorData Image, "rtabmap::Image class is renamed to rtabmap::SensorData, use the last one instead.")
rtabmap::util3d::voxelize
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT voxelize(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
Definition: util3d_filtering.cpp:613
Transform.h
rtabmap::util3d::normalFiltering
pcl::IndicesPtr RTABMAP_CORE_EXPORT normalFiltering(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint, float groundNormalsUp=0.0f)
Definition: util3d_filtering.cpp:1938
rtabmap::util3d::commonFiltering
LaserScan RTABMAP_CORE_EXPORT 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)
Definition: util3d_filtering.cpp:74
rtabmap::util3d::extractPlane
pcl::IndicesPtr extractPlane(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float distanceThreshold, int maxIterations=100, pcl::ModelCoefficients *coefficientsOut=0)
Definition: util3d_filtering.cpp:2358
rtabmap::util3d::uniformSampling
pcl::PointCloud< pcl::PointXYZ >::Ptr uniformSampling(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float voxelSize)
Definition: util3d_filtering.h:141
rtabmap::util3d::proportionalRadiusFiltering
pcl::IndicesPtr RTABMAP_CORE_EXPORT proportionalRadiusFiltering(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const std::vector< int > &viewpointIndices, const std::map< int, Transform > &viewpoints, float factor=0.01f, float neighborScale=2.0f)
Definition: util3d_filtering.cpp:1190
glm::max
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
rtabmap::util3d::downsample
LaserScan RTABMAP_CORE_EXPORT downsample(const LaserScan &cloud, int step)
Definition: util3d_filtering.cpp:398
rtabmap::util3d::extractIndices
pcl::IndicesPtr RTABMAP_CORE_EXPORT extractIndices(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative)
Definition: util3d_filtering.cpp:2299
rtabmap::util3d::subtractFiltering
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_CORE_EXPORT subtractFiltering(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &substractCloud, float radiusSearch, int minNeighborsInRadius=1)
Definition: util3d_filtering.cpp:1423
M_PI
#define M_PI
Definition: tango-gl/include/tango-gl/util.h:66
rtabmap::util3d::randomSampling
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT randomSampling(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, int samples)
Definition: util3d_filtering.cpp:682
rtabmap::Transform
Definition: Transform.h:41
LaserScan.h
rtabmap::util3d::removeNaNFromPointCloud
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_CORE_EXPORT removeNaNFromPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud)
Definition: util3d_filtering.cpp:1002
rtabmap::util3d::rangeFiltering
LaserScan RTABMAP_CORE_EXPORT rangeFiltering(const LaserScan &scan, float rangeMin, float rangeMax)
Definition: util3d_filtering.cpp:347
rtabmap::util3d::frustumFiltering
pcl::IndicesPtr RTABMAP_CORE_EXPORT 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)
Definition: util3d_filtering.cpp:950
rtabmap::util3d::extractClusters
std::vector< pcl::IndicesPtr > RTABMAP_CORE_EXPORT extractClusters(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float clusterTolerance, int minClusterSize, int maxClusterSize=std::numeric_limits< int >::max(), int *biggestClusterIndex=0)
Definition: util3d_filtering.cpp:2151
rtabmap
Definition: CameraARCore.cpp:35
rtabmap::util3d::radiusFiltering
pcl::IndicesPtr RTABMAP_CORE_EXPORT radiusFiltering(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float radiusSearch, int minNeighborsInRadius)
Definition: util3d_filtering.cpp:1087
rtabmap::util3d::subtractAdaptiveFiltering
pcl::IndicesPtr RTABMAP_CORE_EXPORT 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))
Definition: util3d_filtering.cpp:1713


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jul 1 2024 02:42:41