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::PointXYZRGB>::Ptr & cloud,
169 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
170 const pcl::IndicesPtr & indices,
171 const std::string &
axis,
174 bool negative =
false);
176 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
177 const pcl::IndicesPtr & indices,
178 const std::string & axis,
181 bool negative =
false);
183 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
184 const pcl::IndicesPtr & indices,
185 const std::string & axis,
188 bool negative =
false);
190 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
191 const pcl::IndicesPtr & indices,
192 const std::string & axis,
195 bool negative =
false);
197 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
198 const pcl::IndicesPtr & indices,
199 const std::string & axis,
202 bool negative =
false);
204 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
205 const pcl::IndicesPtr & indices,
206 const std::string & axis,
209 bool negative =
false);
211 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
212 const std::string & axis,
215 bool negative =
false);
217 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
218 const std::string & axis,
221 bool negative =
false);
223 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
224 const std::string & axis,
227 bool negative =
false);
229 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
230 const std::string & axis,
233 bool negative =
false);
235 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
236 const std::string & axis,
239 bool negative =
false);
241 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
242 const std::string & axis,
245 bool negative =
false);
248 const pcl::PCLPointCloud2::Ptr & cloud,
249 const pcl::IndicesPtr & indices,
250 const Eigen::Vector4f & min,
251 const Eigen::Vector4f & max,
253 bool negative =
false);
255 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
256 const pcl::IndicesPtr & indices,
257 const Eigen::Vector4f & min,
258 const Eigen::Vector4f & max,
260 bool negative =
false);
262 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
263 const pcl::IndicesPtr & indices,
264 const Eigen::Vector4f & min,
265 const Eigen::Vector4f & max,
267 bool negative =
false);
269 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
270 const pcl::IndicesPtr & indices,
271 const Eigen::Vector4f & min,
272 const Eigen::Vector4f & max,
274 bool negative =
false);
276 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
277 const pcl::IndicesPtr & indices,
278 const Eigen::Vector4f & min,
279 const Eigen::Vector4f & max,
281 bool negative =
false);
283 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
284 const Eigen::Vector4f & min,
285 const Eigen::Vector4f & max,
287 bool negative =
false);
289 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
290 const Eigen::Vector4f & min,
291 const Eigen::Vector4f & max,
293 bool negative =
false);
295 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
296 const Eigen::Vector4f & min,
297 const Eigen::Vector4f & max,
299 bool negative =
false);
301 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
302 const Eigen::Vector4f & min,
303 const Eigen::Vector4f & max,
305 bool negative =
false);
307 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
308 const Eigen::Vector4f & min,
309 const Eigen::Vector4f & max,
311 bool negative =
false);
315 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
316 const pcl::IndicesPtr & indices,
320 float nearClipPlaneDistance,
321 float farClipPlaneDistance,
322 bool negative =
false);
325 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
329 float nearClipPlaneDistance,
330 float farClipPlaneDistance,
331 bool negative =
false);
334 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
338 float nearClipPlaneDistance,
339 float farClipPlaneDistance,
340 bool negative =
false);
344 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud);
346 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud);
348 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud);
352 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud);
354 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud);
356 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud);
363 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
365 int minNeighborsInRadius);
367 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
369 int minNeighborsInRadius);
371 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
373 int minNeighborsInRadius);
375 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
377 int minNeighborsInRadius);
392 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
393 const pcl::IndicesPtr & indices,
395 int minNeighborsInRadius);
397 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
398 const pcl::IndicesPtr & indices,
400 int minNeighborsInRadius);
402 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
403 const pcl::IndicesPtr & indices,
405 int minNeighborsInRadius);
407 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
408 const pcl::IndicesPtr & indices,
410 int minNeighborsInRadius);
416 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
417 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & substractCloud,
419 int minNeighborsInRadius = 1);
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,
436 int minNeighborsInRadius = 1);
442 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
443 const pcl::PointCloud<pcl::PointNormal>::Ptr & substractCloud,
445 float maxAngle =
M_PI/4.0
f,
446 int minNeighborsInRadius = 1);
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,
463 float maxAngle =
M_PI/4.0
f,
464 int minNeighborsInRadius = 1);
470 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
471 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & substractCloud,
473 float maxAngle =
M_PI/4.0
f,
474 int minNeighborsInRadius = 1);
476 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
477 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & substractCloud,
479 float maxAngle =
M_PI/4.0
f,
480 int minNeighborsInRadius = 1);
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,
497 float maxAngle =
M_PI/4.0
f,
498 int minNeighborsInRadius = 1);
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,
505 float maxAngle =
M_PI/4.0
f,
506 int minNeighborsInRadius = 1);
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));
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.0
f,
542 int minNeighborsInRadius = 1,
543 const Eigen::Vector3f & viewpoint = Eigen::Vector3f(0,0,0));
551 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
553 const Eigen::Vector4f & normal,
555 const Eigen::Vector4f & viewpoint);
557 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
559 const Eigen::Vector4f & normal,
561 const Eigen::Vector4f & viewpoint);
580 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
581 const pcl::IndicesPtr & indices,
583 const Eigen::Vector4f & normal,
585 const Eigen::Vector4f & viewpoint);
587 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
588 const pcl::IndicesPtr & indices,
590 const Eigen::Vector4f & normal,
592 const Eigen::Vector4f & viewpoint);
594 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
595 const pcl::IndicesPtr & indices,
597 const Eigen::Vector4f & normal,
599 const Eigen::Vector4f & viewpoint);
601 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
602 const pcl::IndicesPtr & indices,
604 const Eigen::Vector4f & normal,
606 const Eigen::Vector4f & viewpoint);
612 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
613 float clusterTolerance,
616 int * biggestClusterIndex = 0);
618 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
619 float clusterTolerance,
622 int * biggestClusterIndex = 0);
637 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
638 const pcl::IndicesPtr & indices,
639 float clusterTolerance,
642 int * biggestClusterIndex = 0);
644 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
645 const pcl::IndicesPtr & indices,
646 float clusterTolerance,
649 int * biggestClusterIndex = 0);
651 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
652 const pcl::IndicesPtr & indices,
653 float clusterTolerance,
656 int * biggestClusterIndex = 0);
658 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
659 const pcl::IndicesPtr & indices,
660 float clusterTolerance,
663 int * biggestClusterIndex = 0);
666 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
667 const pcl::IndicesPtr & indices,
670 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
671 const pcl::IndicesPtr & indices,
674 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
675 const pcl::IndicesPtr & indices,
678 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
679 const pcl::IndicesPtr & indices,
683 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
684 const pcl::IndicesPtr & indices,
688 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
689 const pcl::IndicesPtr & indices,
699 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
700 const pcl::IndicesPtr & indices,
705 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
706 float distanceThreshold,
707 int maxIterations = 100,
708 pcl::ModelCoefficients * coefficientsOut = 0);
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);
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)
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)
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)