28 #ifndef UTIL3D_FILTERING_H_
29 #define UTIL3D_FILTERING_H_
31 #include <rtabmap/core/rtabmap_core_export.h>
33 #include <pcl/point_cloud.h>
34 #include <pcl/point_types.h>
35 #include <pcl/pcl_base.h>
36 #include <pcl/ModelCoefficients.h>
52 const LaserScan & scan,
54 float rangeMin = 0.0f,
55 float rangeMax = 0.0f,
56 float voxelSize = 0.0f,
58 float normalRadius = 0.0f,
59 float groundNormalsUp = 0.0f);
62 const LaserScan & scan,
69 bool forceGroundNormalsUp);
72 const LaserScan & scan,
77 const LaserScan & cloud,
79 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT
downsample(
80 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
82 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT
downsample(
83 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
85 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT
downsample(
86 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
88 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT
downsample(
89 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
91 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT
downsample(
92 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
94 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT
downsample(
95 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
98 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT
voxelize(
99 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
100 const pcl::IndicesPtr & indices,
102 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT
voxelize(
103 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
104 const pcl::IndicesPtr & indices,
106 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT
voxelize(
107 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
108 const pcl::IndicesPtr & indices,
110 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT
voxelize(
111 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
112 const pcl::IndicesPtr & indices,
114 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT
voxelize(
115 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
116 const pcl::IndicesPtr & indices,
118 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT
voxelize(
119 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
120 const pcl::IndicesPtr & indices,
122 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT
voxelize(
123 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
125 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT
voxelize(
126 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
128 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT
voxelize(
129 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
131 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT
voxelize(
132 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
134 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT
voxelize(
135 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
137 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT
voxelize(
138 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
142 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
148 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
154 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
161 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT
randomSampling(
162 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
164 pcl::PointCloud<pcl::PointNormal>::Ptr RTABMAP_CORE_EXPORT
randomSampling(
165 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
167 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT
randomSampling(
168 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
170 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT
randomSampling(
171 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
173 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT
randomSampling(
174 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
176 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT
randomSampling(
177 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
182 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
183 const pcl::IndicesPtr & indices,
184 const std::string &
axis,
187 bool negative =
false);
189 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
190 const pcl::IndicesPtr & indices,
191 const std::string &
axis,
194 bool negative =
false);
196 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
197 const pcl::IndicesPtr & indices,
198 const std::string &
axis,
201 bool negative =
false);
203 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
204 const pcl::IndicesPtr & indices,
205 const std::string &
axis,
208 bool negative =
false);
210 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
211 const pcl::IndicesPtr & indices,
212 const std::string &
axis,
215 bool negative =
false);
217 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
218 const pcl::IndicesPtr & indices,
219 const std::string &
axis,
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,
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,
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,
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,
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,
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,
258 bool negative =
false);
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,
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,
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,
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,
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,
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,
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,
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,
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,
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,
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,
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,
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,
344 bool negative =
false);
348 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
349 const pcl::IndicesPtr & indices,
353 float nearClipPlaneDistance,
354 float farClipPlaneDistance,
355 bool negative =
false);
358 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
362 float nearClipPlaneDistance,
363 float farClipPlaneDistance,
364 bool negative =
false);
366 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT
frustumFiltering(
367 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
371 float nearClipPlaneDistance,
372 float farClipPlaneDistance,
373 bool negative =
false);
377 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud);
379 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud);
381 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud);
383 const pcl::PCLPointCloud2::Ptr & cloud);
387 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud);
389 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud);
391 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud);
398 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
400 int minNeighborsInRadius);
402 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
404 int minNeighborsInRadius);
406 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
408 int minNeighborsInRadius);
410 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
412 int minNeighborsInRadius);
414 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
416 int minNeighborsInRadius);
418 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
420 int minNeighborsInRadius);
435 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
436 const pcl::IndicesPtr & indices,
438 int minNeighborsInRadius);
440 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
441 const pcl::IndicesPtr & indices,
443 int minNeighborsInRadius);
445 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
446 const pcl::IndicesPtr & indices,
448 int minNeighborsInRadius);
450 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
451 const pcl::IndicesPtr & indices,
453 int minNeighborsInRadius);
455 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
456 const pcl::IndicesPtr & indices,
458 int minNeighborsInRadius);
460 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
461 const pcl::IndicesPtr & indices,
463 int minNeighborsInRadius);
467 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
468 const std::vector<int> & viewpointIndices,
469 const std::map<int, Transform> & viewpoints,
471 float neighborScale=2.0f);
473 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
474 const std::vector<int> & viewpointIndices,
475 const std::map<int, Transform> & viewpoints,
477 float neighborScale=2.0f);
479 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
480 const std::vector<int> & viewpointIndices,
481 const std::map<int, Transform> & viewpoints,
483 float neighborScale=2.0f);
485 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
486 const std::vector<int> & viewpointIndices,
487 const std::map<int, Transform> & viewpoints,
489 float neighborScale=2.0f);
491 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
492 const std::vector<int> & viewpointIndices,
493 const std::map<int, Transform> & viewpoints,
495 float neighborScale=2.0f);
497 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
498 const std::vector<int> & viewpointIndices,
499 const std::map<int, Transform> & viewpoints,
501 float neighborScale=2.0f);
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,
521 float neighborScale=2.0f);
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,
528 float neighborScale=2.0f);
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,
535 float neighborScale=2.0f);
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,
542 float neighborScale=2.0f);
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,
549 float neighborScale=2.0f);
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,
556 float neighborScale=2.0f);
562 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
563 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
565 int minNeighborsInRadius = 1);
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,
582 int minNeighborsInRadius = 1);
588 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
589 const pcl::PointCloud<pcl::PointNormal>::Ptr & substractCloud,
591 float maxAngle =
M_PI/4.0f,
592 int minNeighborsInRadius = 1);
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,
609 float maxAngle =
M_PI/4.0f,
610 int minNeighborsInRadius = 1);
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,
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,
625 float maxAngle =
M_PI/4.0f,
626 int minNeighborsInRadius = 1);
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,
643 float maxAngle =
M_PI/4.0f,
644 int minNeighborsInRadius = 1);
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,
651 float maxAngle =
M_PI/4.0f,
652 int minNeighborsInRadius = 1);
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));
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));
697 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
699 const Eigen::Vector4f & normal,
701 const Eigen::Vector4f & viewpoint,
702 float groundNormalsUp = 0.0f);
704 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
706 const Eigen::Vector4f & normal,
708 const Eigen::Vector4f & viewpoint,
709 float groundNormalsUp = 0.0f);
728 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
729 const pcl::IndicesPtr & indices,
731 const Eigen::Vector4f & normal,
733 const Eigen::Vector4f & viewpoint,
734 float groundNormalsUp = 0.0f);
736 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
737 const pcl::IndicesPtr & indices,
739 const Eigen::Vector4f & normal,
741 const Eigen::Vector4f & viewpoint,
742 float groundNormalsUp = 0.0f);
744 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
745 const pcl::IndicesPtr & indices,
747 const Eigen::Vector4f & normal,
749 const Eigen::Vector4f & viewpoint,
750 float groundNormalsUp = 0.0f);
752 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
753 const pcl::IndicesPtr & indices,
755 const Eigen::Vector4f & normal,
757 const Eigen::Vector4f & viewpoint,
758 float groundNormalsUp = 0.0f);
760 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
761 const pcl::IndicesPtr & indices,
763 const Eigen::Vector4f & normal,
765 const Eigen::Vector4f & viewpoint,
766 float groundNormalsUp = 0.0f);
768 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
769 const pcl::IndicesPtr & indices,
771 const Eigen::Vector4f & normal,
773 const Eigen::Vector4f & viewpoint,
774 float groundNormalsUp = 0.0f);
780 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
781 float clusterTolerance,
784 int * biggestClusterIndex = 0);
786 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
787 float clusterTolerance,
790 int * biggestClusterIndex = 0);
805 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
806 const pcl::IndicesPtr & indices,
807 float clusterTolerance,
810 int * biggestClusterIndex = 0);
812 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
813 const pcl::IndicesPtr & indices,
814 float clusterTolerance,
817 int * biggestClusterIndex = 0);
819 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
820 const pcl::IndicesPtr & indices,
821 float clusterTolerance,
824 int * biggestClusterIndex = 0);
826 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
827 const pcl::IndicesPtr & indices,
828 float clusterTolerance,
831 int * biggestClusterIndex = 0);
833 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
834 const pcl::IndicesPtr & indices,
835 float clusterTolerance,
838 int * biggestClusterIndex = 0);
840 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
841 const pcl::IndicesPtr & indices,
842 float clusterTolerance,
845 int * biggestClusterIndex = 0);
848 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
849 const pcl::IndicesPtr & indices,
852 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
853 const pcl::IndicesPtr & indices,
856 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
857 const pcl::IndicesPtr & indices,
860 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
861 const pcl::IndicesPtr & indices,
864 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
865 const pcl::IndicesPtr & indices,
868 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
869 const pcl::IndicesPtr & indices,
872 pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMAP_CORE_EXPORT
extractIndices(
873 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
874 const pcl::IndicesPtr & indices,
877 pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMAP_CORE_EXPORT
extractIndices(
878 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
879 const pcl::IndicesPtr & indices,
888 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr RTABMAP_CORE_EXPORT
extractIndices(
889 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
890 const pcl::IndicesPtr & indices,
893 pcl::PointCloud<pcl::PointXYZI>::Ptr RTABMAP_CORE_EXPORT
extractIndices(
894 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
895 const pcl::IndicesPtr & indices,
898 pcl::PointCloud<pcl::PointXYZINormal>::Ptr RTABMAP_CORE_EXPORT
extractIndices(
899 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
900 const pcl::IndicesPtr & indices,
905 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
906 float distanceThreshold,
907 int maxIterations = 100,
908 pcl::ModelCoefficients * coefficientsOut = 0);
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);