28 #ifndef UTIL3D_FILTERING_H_ 29 #define UTIL3D_FILTERING_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);
61 const LaserScan & scan,
68 bool forceGroundNormalsUp),
"Use version with groundNormalsUp as float. For forceGroundNormalsUp=true, set groundNormalsUp=0.8, otherwise set groundNormalsUp=0.0.");
71 const LaserScan & scan,
76 const LaserScan & cloud,
79 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
82 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
85 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
88 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
91 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
94 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
98 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
99 const pcl::IndicesPtr & indices,
102 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
103 const pcl::IndicesPtr & indices,
106 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
107 const pcl::IndicesPtr & indices,
110 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
111 const pcl::IndicesPtr & indices,
114 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
115 const pcl::IndicesPtr & indices,
118 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
119 const pcl::IndicesPtr & indices,
122 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
125 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
128 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
131 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
134 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
137 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
141 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
147 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
153 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
161 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
164 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
167 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
170 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
173 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
176 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
181 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
182 const pcl::IndicesPtr & indices,
183 const std::string &
axis,
186 bool negative =
false);
188 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
189 const pcl::IndicesPtr & indices,
190 const std::string & axis,
193 bool negative =
false);
195 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
196 const pcl::IndicesPtr & indices,
197 const std::string & axis,
200 bool negative =
false);
202 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
203 const pcl::IndicesPtr & indices,
204 const std::string & axis,
207 bool negative =
false);
209 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
210 const pcl::IndicesPtr & indices,
211 const std::string & axis,
214 bool negative =
false);
216 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
217 const pcl::IndicesPtr & indices,
218 const std::string & axis,
221 bool negative =
false);
223 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
224 const std::string & axis,
227 bool negative =
false);
229 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
230 const std::string & axis,
233 bool negative =
false);
235 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
236 const std::string & axis,
239 bool negative =
false);
241 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
242 const std::string & axis,
245 bool negative =
false);
247 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
248 const std::string & axis,
251 bool negative =
false);
253 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
254 const std::string & axis,
257 bool negative =
false);
260 const pcl::PCLPointCloud2::Ptr & cloud,
261 const pcl::IndicesPtr & indices,
262 const Eigen::Vector4f & min,
263 const Eigen::Vector4f & max,
265 bool negative =
false);
267 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
268 const pcl::IndicesPtr & indices,
269 const Eigen::Vector4f & min,
270 const Eigen::Vector4f & max,
272 bool negative =
false);
274 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
275 const pcl::IndicesPtr & indices,
276 const Eigen::Vector4f & min,
277 const Eigen::Vector4f & max,
279 bool negative =
false);
281 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
282 const pcl::IndicesPtr & indices,
283 const Eigen::Vector4f & min,
284 const Eigen::Vector4f & max,
286 bool negative =
false);
288 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
289 const pcl::IndicesPtr & indices,
290 const Eigen::Vector4f & min,
291 const Eigen::Vector4f & max,
293 bool negative =
false);
295 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
296 const pcl::IndicesPtr & indices,
297 const Eigen::Vector4f & min,
298 const Eigen::Vector4f & max,
300 bool negative =
false);
302 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
303 const pcl::IndicesPtr & indices,
304 const Eigen::Vector4f & min,
305 const Eigen::Vector4f & max,
307 bool negative =
false);
309 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
310 const Eigen::Vector4f & min,
311 const Eigen::Vector4f & max,
313 bool negative =
false);
315 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
316 const Eigen::Vector4f & min,
317 const Eigen::Vector4f & max,
319 bool negative =
false);
321 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
322 const Eigen::Vector4f & min,
323 const Eigen::Vector4f & max,
325 bool negative =
false);
327 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
328 const Eigen::Vector4f & min,
329 const Eigen::Vector4f & max,
331 bool negative =
false);
333 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
334 const Eigen::Vector4f & min,
335 const Eigen::Vector4f & max,
337 bool negative =
false);
339 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
340 const Eigen::Vector4f & min,
341 const Eigen::Vector4f & max,
343 bool negative =
false);
347 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
348 const pcl::IndicesPtr & indices,
352 float nearClipPlaneDistance,
353 float farClipPlaneDistance,
354 bool negative =
false);
357 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
361 float nearClipPlaneDistance,
362 float farClipPlaneDistance,
363 bool negative =
false);
366 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
370 float nearClipPlaneDistance,
371 float farClipPlaneDistance,
372 bool negative =
false);
376 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud);
378 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud);
380 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud);
382 const pcl::PCLPointCloud2::Ptr & cloud);
386 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud);
388 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud);
390 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud);
397 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
399 int minNeighborsInRadius);
401 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
403 int minNeighborsInRadius);
405 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
407 int minNeighborsInRadius);
409 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
411 int minNeighborsInRadius);
413 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
415 int minNeighborsInRadius);
417 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
419 int minNeighborsInRadius);
434 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
435 const pcl::IndicesPtr & indices,
437 int minNeighborsInRadius);
439 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
440 const pcl::IndicesPtr & indices,
442 int minNeighborsInRadius);
444 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
445 const pcl::IndicesPtr & indices,
447 int minNeighborsInRadius);
449 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
450 const pcl::IndicesPtr & indices,
452 int minNeighborsInRadius);
454 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
455 const pcl::IndicesPtr & indices,
457 int minNeighborsInRadius);
459 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
460 const pcl::IndicesPtr & indices,
462 int minNeighborsInRadius);
466 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
467 const std::vector<int> & viewpointIndices,
468 const std::map<int, Transform> & viewpoints,
470 float neighborScale=2.0
f);
472 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
473 const std::vector<int> & viewpointIndices,
474 const std::map<int, Transform> & viewpoints,
476 float neighborScale=2.0
f);
478 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
479 const std::vector<int> & viewpointIndices,
480 const std::map<int, Transform> & viewpoints,
482 float neighborScale=2.0
f);
484 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
485 const std::vector<int> & viewpointIndices,
486 const std::map<int, Transform> & viewpoints,
488 float neighborScale=2.0
f);
490 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
491 const std::vector<int> & viewpointIndices,
492 const std::map<int, Transform> & viewpoints,
494 float neighborScale=2.0
f);
496 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
497 const std::vector<int> & viewpointIndices,
498 const std::map<int, Transform> & viewpoints,
500 float neighborScale=2.0
f);
515 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
516 const pcl::IndicesPtr & indices,
517 const std::vector<int> & viewpointIndices,
518 const std::map<int, Transform> & viewpoints,
520 float neighborScale=2.0
f);
522 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
523 const pcl::IndicesPtr & indices,
524 const std::vector<int> & viewpointIndices,
525 const std::map<int, Transform> & viewpoints,
527 float neighborScale=2.0
f);
529 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
530 const pcl::IndicesPtr & indices,
531 const std::vector<int> & viewpointIndices,
532 const std::map<int, Transform> & viewpoints,
534 float neighborScale=2.0
f);
536 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
537 const pcl::IndicesPtr & indices,
538 const std::vector<int> & viewpointIndices,
539 const std::map<int, Transform> & viewpoints,
541 float neighborScale=2.0
f);
543 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
544 const pcl::IndicesPtr & indices,
545 const std::vector<int> & viewpointIndices,
546 const std::map<int, Transform> & viewpoints,
548 float neighborScale=2.0
f);
550 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
551 const pcl::IndicesPtr & indices,
552 const std::vector<int> & viewpointIndices,
553 const std::map<int, Transform> & viewpoints,
555 float neighborScale=2.0
f);
561 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
562 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
564 int minNeighborsInRadius = 1);
576 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
577 const pcl::IndicesPtr & indices,
578 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
579 const pcl::IndicesPtr & substractIndices,
581 int minNeighborsInRadius = 1);
587 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
588 const pcl::PointCloud<pcl::PointNormal>::Ptr & substractCloud,
590 float maxAngle =
M_PI/4.0
f,
591 int minNeighborsInRadius = 1);
603 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
604 const pcl::IndicesPtr & indices,
605 const pcl::PointCloud<pcl::PointNormal>::Ptr & substractCloud,
606 const pcl::IndicesPtr & substractIndices,
608 float maxAngle =
M_PI/4.0
f,
609 int minNeighborsInRadius = 1);
615 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
616 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & substractCloud,
618 float maxAngle =
M_PI/4.0
f,
619 int minNeighborsInRadius = 1);
621 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
622 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
624 float maxAngle =
M_PI/4.0
f,
625 int minNeighborsInRadius = 1);
637 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
638 const pcl::IndicesPtr & indices,
639 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & substractCloud,
640 const pcl::IndicesPtr & substractIndices,
642 float maxAngle =
M_PI/4.0
f,
643 int minNeighborsInRadius = 1);
645 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
646 const pcl::IndicesPtr & indices,
647 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
648 const pcl::IndicesPtr & substractIndices,
650 float maxAngle =
M_PI/4.0
f,
651 int minNeighborsInRadius = 1);
663 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
664 const pcl::IndicesPtr & indices,
665 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
666 const pcl::IndicesPtr & substractIndices,
667 float radiusSearchRatio = 0.01,
668 int minNeighborsInRadius = 1,
669 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
681 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
682 const pcl::IndicesPtr & indices,
683 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
684 const pcl::IndicesPtr & substractIndices,
685 float radiusSearchRatio = 0.01,
686 float maxAngle =
M_PI/4.0
f,
687 int minNeighborsInRadius = 1,
688 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
696 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
698 const Eigen::Vector4f & normal,
700 const Eigen::Vector4f & viewpoint,
701 float groundNormalsUp = 0.0
f);
703 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
705 const Eigen::Vector4f & normal,
707 const Eigen::Vector4f & viewpoint,
708 float groundNormalsUp = 0.0
f);
727 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
728 const pcl::IndicesPtr & indices,
730 const Eigen::Vector4f & normal,
732 const Eigen::Vector4f & viewpoint,
733 float groundNormalsUp = 0.0
f);
735 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
736 const pcl::IndicesPtr & indices,
738 const Eigen::Vector4f & normal,
740 const Eigen::Vector4f & viewpoint,
741 float groundNormalsUp = 0.0
f);
743 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
744 const pcl::IndicesPtr & indices,
746 const Eigen::Vector4f & normal,
748 const Eigen::Vector4f & viewpoint,
749 float groundNormalsUp = 0.0
f);
751 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
752 const pcl::IndicesPtr & indices,
754 const Eigen::Vector4f & normal,
756 const Eigen::Vector4f & viewpoint,
757 float groundNormalsUp = 0.0
f);
759 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
760 const pcl::IndicesPtr & indices,
762 const Eigen::Vector4f & normal,
764 const Eigen::Vector4f & viewpoint,
765 float groundNormalsUp = 0.0
f);
767 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
768 const pcl::IndicesPtr & indices,
770 const Eigen::Vector4f & normal,
772 const Eigen::Vector4f & viewpoint,
773 float groundNormalsUp = 0.0
f);
779 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
780 float clusterTolerance,
783 int * biggestClusterIndex = 0);
785 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
786 float clusterTolerance,
789 int * biggestClusterIndex = 0);
804 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
805 const pcl::IndicesPtr & indices,
806 float clusterTolerance,
809 int * biggestClusterIndex = 0);
811 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
812 const pcl::IndicesPtr & indices,
813 float clusterTolerance,
816 int * biggestClusterIndex = 0);
818 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
819 const pcl::IndicesPtr & indices,
820 float clusterTolerance,
823 int * biggestClusterIndex = 0);
825 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
826 const pcl::IndicesPtr & indices,
827 float clusterTolerance,
830 int * biggestClusterIndex = 0);
832 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
833 const pcl::IndicesPtr & indices,
834 float clusterTolerance,
837 int * biggestClusterIndex = 0);
839 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
840 const pcl::IndicesPtr & indices,
841 float clusterTolerance,
844 int * biggestClusterIndex = 0);
847 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
848 const pcl::IndicesPtr & indices,
851 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
852 const pcl::IndicesPtr & indices,
855 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
856 const pcl::IndicesPtr & indices,
859 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
860 const pcl::IndicesPtr & indices,
863 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
864 const pcl::IndicesPtr & indices,
867 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
868 const pcl::IndicesPtr & indices,
872 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
873 const pcl::IndicesPtr & indices,
877 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
878 const pcl::IndicesPtr & indices,
888 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
889 const pcl::IndicesPtr & indices,
893 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
894 const pcl::IndicesPtr & indices,
898 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
899 const pcl::IndicesPtr & indices,
904 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
905 float distanceThreshold,
906 int maxIterations = 100,
907 pcl::ModelCoefficients * coefficientsOut = 0);
909 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
910 const pcl::IndicesPtr & indices,
911 float distanceThreshold,
912 int maxIterations = 100,
913 pcl::ModelCoefficients * coefficientsOut = 0);
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)
GLM_FUNC_DECL detail::tvec3< T, P > axis(detail::tquat< T, P > const &x)
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP removeNaNFromPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud)
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::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)
pcl::IndicesPtr RTABMAP_EXP normalFiltering(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint, float groundNormalsUp=0.0f)
LaserScan RTABMAP_EXP downsample(const LaserScan &cloud, int step)
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)
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::IndicesPtr RTABMAP_EXP 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)
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)