vision
Loading...
Searching...
No Matches
YarpCloudUtils-pcl-impl.hpp
1// -*- mode:C++; tab-width:4; c-basic-offset:4; indent-tabs-mode:nil -*-
2
3#ifndef __YARP_CLOUD_UTILS_PCL_IMPL_HPP__
4#define __YARP_CLOUD_UTILS_PCL_IMPL_HPP__
5
6#define _USE_MATH_DEFINES
7#include <cmath> // M_PI
8#include <ctime> // std::time
9
10#include <limits> // std::numeric_limits
11#include <memory> // std::const_pointer_cast
12#include <stdexcept> // std::invalid_argument, std::runtime_error
13#include <string>
14
15#include <pcl/pcl_config.h>
16#include <pcl/point_cloud.h>
17#include <pcl/point_types.h>
18#include <pcl/PolygonMesh.h>
19#include <pcl/common/transforms.h>
20#include <pcl/features/normal_3d.h>
21#include <pcl/features/normal_3d_omp.h>
22#include <pcl/filters/approximate_voxel_grid.h>
23#include <pcl/filters/bilateral.h>
24#include <pcl/filters/crop_box.h>
25#include <pcl/filters/fast_bilateral.h>
26#include <pcl/filters/fast_bilateral_omp.h>
27#include <pcl/filters/grid_minimum.h>
28#include <pcl/filters/local_maximum.h>
29#include <pcl/filters/median_filter.h>
30#include <pcl/filters/passthrough.h>
31#include <pcl/filters/radius_outlier_removal.h>
32#include <pcl/filters/random_sample.h>
33#include <pcl/filters/sampling_surface_normal.h>
34#include <pcl/filters/shadowpoints.h>
35#include <pcl/filters/statistical_outlier_removal.h>
36#include <pcl/filters/uniform_sampling.h>
37#include <pcl/filters/voxel_grid.h>
38#include <pcl/search/kdtree.h>
39#include <pcl/surface/bilateral_upsampling.h>
40#include <pcl/surface/concave_hull.h>
41#include <pcl/surface/convex_hull.h>
42#include <pcl/surface/gp3.h>
43#include <pcl/surface/grid_projection.h>
44#include <pcl/surface/marching_cubes_hoppe.h>
45#include <pcl/surface/marching_cubes_rbf.h>
46#include <pcl/surface/mls.h>
47#include <pcl/surface/organized_fast_mesh.h>
48#include <pcl/surface/poisson.h>
49#include <pcl/surface/simplification_remove_unused_vertices.h>
50#include <pcl/surface/vtk_smoothing/vtk_mesh_quadric_decimation.h>
51#include <pcl/surface/vtk_smoothing/vtk_mesh_smoothing_laplacian.h>
52#include <pcl/surface/vtk_smoothing/vtk_mesh_smoothing_windowed_sinc.h>
53#include <pcl/surface/vtk_smoothing/vtk_mesh_subdivision.h>
54
55namespace
56{
57
58auto getTransformation(const yarp::os::Searchable & options)
59{
60 auto transformation = Eigen::Transform<double, 3, Eigen::Affine>::Identity();
61
62 if (const auto & translation = options.find("translation"); !translation.isNull())
63 {
64 if (!translation.isList() || translation.asList()->size() != 3)
65 {
66 throw std::runtime_error("translation is not a list or size not equal to 3");
67 }
68
69 const auto * b = translation.asList();
70 Eigen::Vector3d vector(b->get(0).asFloat64(), b->get(1).asFloat64(), b->get(2).asFloat64());
71 transformation.translate(vector);
72 }
73
74 if (const auto & rotation = options.find("rotation"); !rotation.isNull())
75 {
76 if (!rotation.isList() || rotation.asList()->size() != 3)
77 {
78 throw std::runtime_error("rotation is not a list or size not equal to 3");
79 }
80
81 const auto * b = rotation.asList();
82 Eigen::Vector3d axis(b->get(0).asFloat64(), b->get(1).asFloat64(), b->get(2).asFloat64());
83 Eigen::AngleAxisd rot(axis.norm(), axis.normalized());
84 transformation.rotate(rot);
85 }
86
87 return transformation;
88}
89
90template <typename T>
91void checkOutput(const typename pcl::PointCloud<T>::ConstPtr & cloud, const std::string & caller)
92{
93 if (cloud->empty())
94 {
95 throw std::runtime_error(caller + " returned an empty cloud");
96 }
97}
98
99inline void checkOutput(const pcl::PolygonMesh::ConstPtr & mesh, const std::string & caller)
100{
101 if (mesh->cloud.data.empty() || mesh->polygons.empty())
102 {
103 throw std::runtime_error(caller + " returned an empty or incomplete mesh");
104 }
105}
106
107template <typename T>
108void doTransformPointCloud(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
109{
110 auto transformation = getTransformation(options);
111 pcl::transformPointCloud(*in, *out, transformation);
112 checkOutput<T>(out, "transformPointCloud");
113}
114
115template <typename T>
116void doTransformPointCloudWithNormals(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
117{
118 auto transformation = getTransformation(options);
119 pcl::transformPointCloudWithNormals(*in, *out, transformation);
120 checkOutput<T>(out, "transformPointCloudWithNormals");
121}
122
123template <typename T>
124void doApproximateVoxelGrid(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
125{
126 auto downsampleAllData = options.check("downsampleAllData", yarp::os::Value(true)).asBool();
127 auto leafSize = options.check("leafSize", yarp::os::Value(0.0f)).asFloat32();
128 auto leafSizeX = options.check("leafSizeX", yarp::os::Value(leafSize)).asFloat32();
129 auto leafSizeY = options.check("leafSizeY", yarp::os::Value(leafSize)).asFloat32();
130 auto leafSizeZ = options.check("leafSizeZ", yarp::os::Value(leafSize)).asFloat32();
131
132 pcl::ApproximateVoxelGrid<T> grid;
133 grid.setDownsampleAllData(downsampleAllData);
134 grid.setInputCloud(in);
135 grid.setLeafSize(leafSizeX, leafSizeY, leafSizeZ);
136 grid.filter(*out);
137
138 checkOutput<T>(out, "ApproximateVoxelGrid");
139}
140
141template <typename T>
142void doBilateralFilter(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
143{
144 auto halfSize = options.check("halfSize", yarp::os::Value(0.0)).asFloat64();
145 auto stdDev = options.check("stdDev", yarp::os::Value(std::numeric_limits<double>::max())).asFloat64();
146
147 auto tree = pcl::make_shared<pcl::search::KdTree<T>>();
148 tree->setInputCloud(in);
149
150 pcl::BilateralFilter<T> filter;
151 filter.setHalfSize(halfSize);
152 filter.setInputCloud(in);
153 filter.setSearchMethod(tree);
154 filter.setStdDev(stdDev);
155 filter.filter(*out);
156
157 checkOutput<T>(out, "BilateralFilter");
158}
159
160template <typename T>
161void doBilateralUpsampling(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
162{
163 auto sigmaColor = options.check("sigmaColor", yarp::os::Value(15.0f)).asFloat32();
164 auto sigmaDepth = options.check("sigmaDepth", yarp::os::Value(0.5f)).asFloat32();
165 auto windowSize = options.check("windowSize", yarp::os::Value(5)).asInt32();
166
167 pcl::BilateralUpsampling<T, T> upsampler;
168 upsampler.setInputCloud(in);
169 upsampler.setSigmaColor(sigmaColor);
170 upsampler.setSigmaDepth(sigmaDepth);
171 upsampler.setWindowSize(windowSize);
172 upsampler.process(*out);
173
174 checkOutput<T>(out, "BilateralUpsampling");
175}
176
177template <typename T>
178void doConcaveHull(const typename pcl::PointCloud<T>::ConstPtr & in, const pcl::PolygonMesh::Ptr & out, const yarp::os::Searchable & options)
179{
180 auto alpha = options.check("alpha", yarp::os::Value(0.0)).asFloat64();
181
182 pcl::ConcaveHull<T> concave;
183 concave.setAlpha(alpha);
184 concave.setDimension(3);
185 concave.setInputCloud(in);
186 concave.setKeepInformation(true);
187 concave.reconstruct(*out);
188
189 checkOutput(out, "ConcaveHull");
190}
191
192template <typename T>
193void doConvexHull(const typename pcl::PointCloud<T>::ConstPtr & in, const pcl::PolygonMesh::Ptr & out, const yarp::os::Searchable & options)
194{
195 pcl::ConvexHull<T> convex;
196 convex.setDimension(3);
197 convex.setInputCloud(in);
198 convex.reconstruct(*out);
199
200 checkOutput(out, "ConvexHull");
201}
202
203template <typename T>
204void doCropBox(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
205{
206 auto keepOrganized = options.check("keepOrganized", yarp::os::Value(false)).asBool();
207 auto maxX = options.check("maxX", yarp::os::Value(1.0f)).asFloat32();
208 auto maxY = options.check("maxY", yarp::os::Value(1.0f)).asFloat32();
209 auto maxZ = options.check("maxZ", yarp::os::Value(1.0f)).asFloat32();
210 auto minX = options.check("minX", yarp::os::Value(-1.0f)).asFloat32();
211 auto minY = options.check("minY", yarp::os::Value(-1.0f)).asFloat32();
212 auto minZ = options.check("minZ", yarp::os::Value(-1.0f)).asFloat32();
213 auto negative = options.check("negative", yarp::os::Value(false)).asBool();
214 auto rotationX = options.check("rotationX", yarp::os::Value(0.0f)).asFloat32();
215 auto rotationY = options.check("rotationY", yarp::os::Value(0.0f)).asFloat32();
216 auto rotationZ = options.check("rotationZ", yarp::os::Value(0.0f)).asFloat32();
217 auto translationX = options.check("translationX", yarp::os::Value(0.0f)).asFloat32();
218 auto translationY = options.check("translationY", yarp::os::Value(0.0f)).asFloat32();
219 auto translationZ = options.check("translationZ", yarp::os::Value(0.0f)).asFloat32();
220
221 pcl::CropBox<T> cropper;
222 cropper.setInputCloud(in);
223 cropper.setKeepOrganized(keepOrganized);
224 cropper.setMax({maxX, maxY, maxZ, 1.0f});
225 cropper.setMin({minX, minY, minZ, 1.0f});
226 cropper.setNegative(negative);
227 cropper.setRotation({rotationX, rotationY, rotationZ});
228 cropper.setTranslation({translationX, translationY, translationZ});
229 cropper.filter(*out);
230
231 checkOutput<T>(out, "CropBox");
232}
233
234template <typename T>
235void doFastBilateralFilter(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
236{
237 auto sigmaR = options.check("sigmaR", yarp::os::Value(0.05f)).asFloat32();
238 auto sigmaS = options.check("sigmaS", yarp::os::Value(15.0f)).asFloat32();
239
240 pcl::FastBilateralFilter<T> fast;
241 fast.setInputCloud(in);
242 fast.setSigmaR(sigmaR);
243 fast.setSigmaS(sigmaS);
244 fast.filter(*out);
245
246 checkOutput<T>(out, "FastBilateralFilter");
247}
248
249template <typename T>
250void doFastBilateralFilterOMP(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
251{
252 auto numberOfThreads = options.check("numberOfThreads", yarp::os::Value(0)).asInt32();
253 auto sigmaR = options.check("sigmaR", yarp::os::Value(0.05f)).asFloat32();
254 auto sigmaS = options.check("sigmaS", yarp::os::Value(15.0f)).asFloat32();
255
256 pcl::FastBilateralFilterOMP<T> fast;
257 fast.setInputCloud(in);
258 fast.setNumberOfThreads(numberOfThreads);
259 fast.setSigmaR(sigmaR);
260 fast.setSigmaS(sigmaS);
261 fast.filter(*out);
262
263 checkOutput<T>(out, "FastBilateralFilterOMP");
264}
265
266template <typename T>
267void doGreedyProjectionTriangulation(const typename pcl::PointCloud<T>::ConstPtr & in, const pcl::PolygonMesh::Ptr & out, const yarp::os::Searchable & options)
268{
269 auto consistentVertexOrdering = options.check("consistentVertexOrdering", yarp::os::Value(false)).asBool();
270 auto maximumAngle = options.check("maximumAngle", yarp::os::Value(2 * M_PI / 3)).asFloat64();
271 auto maximumNearestNeighbors = options.check("maximumNearestNeighbors", yarp::os::Value(100)).asInt32();
272 auto maximumSurfaceAngle = options.check("maximumSurfaceAngle", yarp::os::Value(M_PI / 4)).asFloat64();
273 auto minimumAngle = options.check("minimumAngle", yarp::os::Value(M_PI / 18)).asFloat64();
274 auto mu = options.check("mu", yarp::os::Value(0.0)).asFloat64();
275 auto normalConsistency = options.check("normalConsistency", yarp::os::Value(false)).asBool();
276 auto searchRadius = options.check("searchRadius", yarp::os::Value(0.0)).asFloat64();
277
278 auto tree = pcl::make_shared<pcl::search::KdTree<T>>();
279 tree->setInputCloud(in);
280
281 pcl::GreedyProjectionTriangulation<T> gp3;
282 gp3.setConsistentVertexOrdering(consistentVertexOrdering);
283 gp3.setInputCloud(in);
284 gp3.setMaximumAngle(maximumAngle);
285 gp3.setMaximumSurfaceAngle(maximumSurfaceAngle);
286 gp3.setMaximumNearestNeighbors(maximumNearestNeighbors);
287 gp3.setMinimumAngle(minimumAngle);
288 gp3.setMu(mu);
289 gp3.setNormalConsistency(normalConsistency);
290 gp3.setSearchMethod(tree);
291 gp3.setSearchRadius(searchRadius);
292 gp3.reconstruct(*out);
293
294 checkOutput(out, "GreedyProjectionTriangulation");
295}
296
297template <typename T>
298void doGridMinimum(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
299{
300 auto keepOrganized = options.check("keepOrganized", yarp::os::Value(false)).asBool();
301 auto negative = options.check("negative", yarp::os::Value(false)).asBool();
302 auto resolution = options.check("resolution", yarp::os::Value(0.0f)).asFloat32();
303
304 pcl::GridMinimum<T> grid(resolution);
305
306 grid.setInputCloud(in);
307 grid.setKeepOrganized(keepOrganized);
308 grid.setNegative(negative);
309 grid.filter(*out);
310
311 checkOutput<T>(out, "GridMinimum");
312}
313
314template <typename T>
315void doGridProjection(const typename pcl::PointCloud<T>::ConstPtr & in, const pcl::PolygonMesh::Ptr & out, const yarp::os::Searchable & options)
316{
317 auto maxBinarySearchLevel = options.check("maxBinarySearchLevel", yarp::os::Value(10)).asInt32();
318 auto nearestNeighborNum = options.check("nearestNeighborNum", yarp::os::Value(50)).asInt32();
319 auto paddingSize = options.check("paddingSize", yarp::os::Value(3)).asInt32();
320 auto resolution = options.check("resolution", yarp::os::Value(0.001)).asFloat64();
321
322 auto tree = pcl::make_shared<pcl::search::KdTree<T>>();
323 tree->setInputCloud(in);
324
325 pcl::GridProjection<T> gp;
326 gp.setInputCloud(in);
327 gp.setMaxBinarySearchLevel(maxBinarySearchLevel);
328 gp.setNearestNeighborNum(nearestNeighborNum);
329 gp.setPaddingSize(paddingSize);
330 gp.setResolution(resolution);
331 gp.setSearchMethod(tree);
332 gp.reconstruct(*out);
333
334 checkOutput(out, "GridProjection");
335}
336
337template <typename T>
338void doLocalMaximum(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
339{
340 auto keepOrganized = options.check("keepOrganized", yarp::os::Value(false)).asBool();
341 auto negative = options.check("negative", yarp::os::Value(false)).asBool();
342 auto radius = options.check("radius", yarp::os::Value(1.0f)).asFloat32();
343
344 pcl::LocalMaximum<T> local;
345 local.setInputCloud(in);
346 local.setKeepOrganized(keepOrganized);
347 local.setNegative(negative);
348 local.setRadius(radius);
349 local.filter(*out);
350
351 checkOutput<T>(out, "LocalMaximum");
352}
353
354template <typename T>
355void doMarchingCubesHoppe(const typename pcl::PointCloud<T>::ConstPtr & in, const pcl::PolygonMesh::Ptr & out, const yarp::os::Searchable & options)
356{
357 auto distanceIgnore = options.check("distanceIgnore", yarp::os::Value(-1.0f)).asFloat32();
358 auto gridResolution = options.check("gridResolution", yarp::os::Value(32)).asInt32();
359 auto gridResolutionX = options.check("gridResolutionX", yarp::os::Value(gridResolution)).asInt32();
360 auto gridResolutionY = options.check("gridResolutionY", yarp::os::Value(gridResolution)).asInt32();
361 auto gridResolutionZ = options.check("gridResolutionZ", yarp::os::Value(gridResolution)).asInt32();
362 auto isoLevel = options.check("isoLevel", yarp::os::Value(0.0f)).asFloat32();
363 auto percentageExtendGrid = options.check("percentageExtendGrid", yarp::os::Value(0.0f)).asFloat32();
364
365 auto tree = pcl::make_shared<pcl::search::KdTree<T>>();
366 tree->setInputCloud(in);
367
368 pcl::MarchingCubesHoppe<T> hoppe;
369 hoppe.setDistanceIgnore(distanceIgnore);
370 hoppe.setGridResolution(gridResolutionX, gridResolutionY, gridResolutionZ);
371 hoppe.setInputCloud(in);
372 hoppe.setIsoLevel(isoLevel);
373 hoppe.setPercentageExtendGrid(percentageExtendGrid);
374 hoppe.setSearchMethod(tree);
375 hoppe.reconstruct(*out);
376
377 checkOutput(out, "MarchingCubesHoppe");
378}
379
380template <typename T>
381void doMarchingCubesRBF(const typename pcl::PointCloud<T>::ConstPtr & in, const pcl::PolygonMesh::Ptr & out, const yarp::os::Searchable & options)
382{
383 auto gridResolution = options.check("gridResolution", yarp::os::Value(32)).asInt32();
384 auto gridResolutionX = options.check("gridResolutionX", yarp::os::Value(gridResolution)).asInt32();
385 auto gridResolutionY = options.check("gridResolutionY", yarp::os::Value(gridResolution)).asInt32();
386 auto gridResolutionZ = options.check("gridResolutionZ", yarp::os::Value(gridResolution)).asInt32();
387 auto isoLevel = options.check("isoLevel", yarp::os::Value(0.0f)).asFloat32();
388 auto offSurfaceDisplacement = options.check("offSurfaceDisplacement", yarp::os::Value(0.1f)).asFloat32();
389 auto percentageExtendGrid = options.check("percentageExtendGrid", yarp::os::Value(0.0f)).asFloat32();
390
391 auto tree = pcl::make_shared<pcl::search::KdTree<T>>();
392 tree->setInputCloud(in);
393
394 pcl::MarchingCubesRBF<T> rbf;
395 rbf.setGridResolution(gridResolutionX, gridResolutionY, gridResolutionZ);
396 rbf.setInputCloud(in);
397 rbf.setIsoLevel(isoLevel);
398 rbf.setOffSurfaceDisplacement(offSurfaceDisplacement);
399 rbf.setPercentageExtendGrid(percentageExtendGrid);
400 rbf.setSearchMethod(tree);
401 rbf.reconstruct(*out);
402
403 checkOutput(out, "MarchingCubesRBF");
404}
405
406template <typename T>
407void doMedianFilter(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
408{
409 auto maxAllowedMovement = options.check("maxAllowedMovement", yarp::os::Value(std::numeric_limits<float>::max())).asFloat32();
410 auto windowSize = options.check("windowSize", yarp::os::Value(5)).asInt32();
411
412 pcl::MedianFilter<T> median;
413 median.setInputCloud(in);
414 median.setMaxAllowedMovement(maxAllowedMovement);
415 median.setWindowSize(windowSize);
416 median.filter(*out);
417
418 checkOutput<T>(out, "MedianFilter");
419}
420
421void doMeshQuadricDecimationVTK(const pcl::PolygonMesh::ConstPtr & in, const pcl::PolygonMesh::Ptr & out, const yarp::os::Searchable & options)
422{
423 auto targetReductionFactor = options.check("targetReductionFactor", yarp::os::Value(0.5f)).asFloat32();
424
425 pcl::MeshQuadricDecimationVTK quadric;
426 quadric.setInputMesh(in);
427 quadric.setTargetReductionFactor(targetReductionFactor);
428 quadric.process(*out);
429
430 checkOutput(out, "MeshQuadricDecimationVTK");
431}
432
433void doMeshSmoothingLaplacianVTK(const pcl::PolygonMesh::ConstPtr & in, const pcl::PolygonMesh::Ptr & out, const yarp::os::Searchable & options)
434{
435 auto boundarySmoothing = options.check("boundarySmoothing", yarp::os::Value(true)).asBool();
436 auto convergence = options.check("convergence", yarp::os::Value(0.0f)).asFloat32();
437 auto edgeAngle = options.check("edgeAngle", yarp::os::Value(15.0f)).asFloat32();
438 auto featureAngle = options.check("featureAngle", yarp::os::Value(45.0f)).asFloat32();
439 auto featureEdgeSmoothing = options.check("featureEdgeSmoothing", yarp::os::Value(false)).asBool();
440 auto numIter = options.check("numIter", yarp::os::Value(20)).asInt32();
441 auto relaxationFactor = options.check("relaxationFactor", yarp::os::Value(0.01f)).asFloat32();
442
443 pcl::MeshSmoothingLaplacianVTK laplacian;
444 laplacian.setBoundarySmoothing(boundarySmoothing);
445 laplacian.setConvergence(convergence);
446 laplacian.setEdgeAngle(edgeAngle);
447 laplacian.setFeatureAngle(featureAngle);
448 laplacian.setFeatureEdgeSmoothing(featureEdgeSmoothing);
449 laplacian.setInputMesh(in);
450 laplacian.setNumIter(numIter);
451 laplacian.setRelaxationFactor(relaxationFactor);
452 laplacian.process(*out);
453
454 checkOutput(out, "MeshSmoothingLaplacianVTK");
455}
456
457void doMeshSmoothingWindowedSincVTK(const pcl::PolygonMesh::ConstPtr & in, const pcl::PolygonMesh::Ptr & out, const yarp::os::Searchable & options)
458{
459 auto boundarySmoothing = options.check("boundarySmoothing", yarp::os::Value(true)).asBool();
460 auto edgeAngle = options.check("edgeAngle", yarp::os::Value(15.0f)).asFloat32();
461 auto featureAngle = options.check("featureAngle", yarp::os::Value(45.0f)).asFloat32();
462 auto featureEdgeSmoothing = options.check("featureEdgeSmoothing", yarp::os::Value(false)).asBool();
463 auto normalizeCoordinates = options.check("normalizeCoordinates", yarp::os::Value(false)).asBool();
464 auto numIter = options.check("numIter", yarp::os::Value(20)).asInt32();
465 auto passBand = options.check("passBand", yarp::os::Value(0.1f)).asFloat32();
466
467 pcl::MeshSmoothingWindowedSincVTK windowed;
468 windowed.setBoundarySmoothing(boundarySmoothing);
469 windowed.setEdgeAngle(edgeAngle);
470 windowed.setFeatureAngle(featureAngle);
471 windowed.setFeatureEdgeSmoothing(featureEdgeSmoothing);
472 windowed.setInputMesh(in);
473 windowed.setNormalizeCoordinates(normalizeCoordinates);
474 windowed.setNumIter(numIter);
475 windowed.setPassBand(passBand);
476 windowed.process(*out);
477
478 checkOutput(out, "MeshSmoothingWindowedSincVTK");
479}
480
481void doMeshSubdivisionVTK(const pcl::PolygonMesh::ConstPtr & in, const pcl::PolygonMesh::Ptr & out, const yarp::os::Searchable & options)
482{
483 auto filterTypeStr = options.check("filterType", yarp::os::Value("linear")).asString();
484
485 pcl::MeshSubdivisionVTK::MeshSubdivisionVTKFilterType filterType;
486
487 if (filterTypeStr == "butterfly")
488 {
489 filterType = pcl::MeshSubdivisionVTK::MeshSubdivisionVTKFilterType::BUTTERFLY;
490 }
491 else if (filterTypeStr == "linear")
492 {
493 filterType = pcl::MeshSubdivisionVTK::MeshSubdivisionVTKFilterType::LINEAR;
494 }
495 else if (filterTypeStr == "loop")
496 {
497 filterType = pcl::MeshSubdivisionVTK::MeshSubdivisionVTKFilterType::LOOP;
498 }
499 else
500 {
501 throw std::invalid_argument("unknown filter type: " + filterTypeStr);
502 }
503
504 pcl::MeshSubdivisionVTK subdivision;
505 subdivision.setFilterType(filterType);
506 subdivision.setInputMesh(in);
507 subdivision.process(*out);
508
509 checkOutput(out, "MeshSubdivisionVTK");
510}
511
512template <typename T1, typename T2 = T1>
513void doMovingLeastSquares(const typename pcl::PointCloud<T1>::ConstPtr & in, const typename pcl::PointCloud<T2>::Ptr & out, const yarp::os::Searchable & options)
514{
515 auto cacheMlsResults = options.check("cacheMlsResults", yarp::os::Value(true)).asBool();
516 auto computeNormals = options.check("computeNormals", yarp::os::Value(false)).asBool();
517 auto dilationIterations = options.check("dilationIterations", yarp::os::Value(0)).asInt32();
518 auto dilationVoxelSize = options.check("dilationVoxelSize", yarp::os::Value(1.0f)).asFloat32();
519 auto numberOfThreads = options.check("numberOfThreads", yarp::os::Value(1)).asInt32();
520 auto pointDensity = options.check("pointDensity", yarp::os::Value(0)).asInt32();
521 auto polynomialOrder = options.check("polynomialOrder", yarp::os::Value(2)).asInt32();
522 auto projectionMethodStr = options.check("projectionMethod", yarp::os::Value("simple")).asString();
523 auto searchRadius = options.check("searchRadius", yarp::os::Value(0.0)).asFloat64();
524 auto sqrGaussParam = options.check("sqrGaussParam", yarp::os::Value(0.0)).asFloat64();
525 auto upsamplingMethodStr = options.check("upsamplingMethod", yarp::os::Value("none")).asString();
526 auto upsamplingRadius = options.check("upsamplingRadius", yarp::os::Value(0.0)).asFloat64();
527 auto upsamplingStepSize = options.check("upsamplingStepSize", yarp::os::Value(0.0)).asFloat64();
528
529 pcl::MLSResult::ProjectionMethod projectionMethod;
530
531 if (projectionMethodStr == "none")
532 {
533 projectionMethod = pcl::MLSResult::ProjectionMethod::NONE;
534 }
535 else if (projectionMethodStr == "orthogonal")
536 {
537 projectionMethod = pcl::MLSResult::ProjectionMethod::ORTHOGONAL;
538 }
539 else if (projectionMethodStr == "simple")
540 {
541 projectionMethod = pcl::MLSResult::ProjectionMethod::SIMPLE;
542 }
543 else
544 {
545 throw std::invalid_argument("unknown projection method: " + projectionMethodStr);
546 }
547
548 typename pcl::MovingLeastSquares<T1, T2>::UpsamplingMethod upsamplingMethod;
549
550 if (upsamplingMethodStr == "distinctCloud")
551 {
552 upsamplingMethod = decltype(upsamplingMethod)::DISTINCT_CLOUD;
553 }
554 else if (upsamplingMethodStr == "none")
555 {
556 upsamplingMethod = decltype(upsamplingMethod)::NONE;
557 }
558 else if (upsamplingMethodStr == "randomUniformDensity")
559 {
560 upsamplingMethod = decltype(upsamplingMethod)::RANDOM_UNIFORM_DENSITY;
561 }
562 else if (upsamplingMethodStr == "sampleLocalPlane")
563 {
564 upsamplingMethod = decltype(upsamplingMethod)::SAMPLE_LOCAL_PLANE;
565 }
566 else if (upsamplingMethodStr == "voxelGridDilation")
567 {
568 upsamplingMethod = decltype(upsamplingMethod)::VOXEL_GRID_DILATION;
569 }
570 else
571 {
572 throw std::invalid_argument("unknown upsampling method: " + upsamplingMethodStr);
573 }
574
575 auto tree = pcl::make_shared<pcl::search::KdTree<T1>>();
576 tree->setInputCloud(in);
577
578 pcl::MovingLeastSquares<T1, T2> mls;
579 mls.setCacheMLSResults(cacheMlsResults);
580 mls.setComputeNormals(computeNormals);
581 mls.setDilationIterations(dilationIterations);
582 mls.setDilationVoxelSize(dilationVoxelSize);
583 mls.setInputCloud(in);
584 mls.setNumberOfThreads(numberOfThreads);
585 mls.setPointDensity(pointDensity);
586 mls.setPolynomialOrder(polynomialOrder);
587 mls.setProjectionMethod(projectionMethod);
588 mls.setSearchMethod(tree);
589 mls.setSearchRadius(searchRadius);
590 mls.setSqrGaussParam(sqrGaussParam);
591 mls.setUpsamplingMethod(upsamplingMethod);
592 mls.setUpsamplingRadius(upsamplingRadius);
593 mls.setUpsamplingStepSize(upsamplingStepSize);
594 mls.process(*out);
595
596 checkOutput<T2>(out, "MovingLeastSquares");
597}
598
599template <typename T1, typename T2>
600void doNormalEstimation(const typename pcl::PointCloud<T1>::ConstPtr & in, const typename pcl::PointCloud<T2>::Ptr & out, const yarp::os::Searchable & options)
601{
602 auto kSearch = options.check("kSearch", yarp::os::Value(0)).asInt32();
603 auto radiusSearch = options.check("radiusSearch", yarp::os::Value(0.0)).asFloat64();
604
605 auto tree = pcl::make_shared<pcl::search::KdTree<T1>>();
606 tree->setInputCloud(in);
607
608 pcl::NormalEstimation<T1, T2> estimator;
609 estimator.setInputCloud(in);
610 estimator.setKSearch(kSearch);
611 estimator.setRadiusSearch(radiusSearch);
612 estimator.setSearchMethod(tree);
613 estimator.compute(*out);
614
615 checkOutput<T2>(out, "NormalEstimation");
616}
617
618template <typename T1, typename T2>
619void doNormalEstimationOMP(const typename pcl::PointCloud<T1>::ConstPtr & in, const typename pcl::PointCloud<T2>::Ptr & out, const yarp::os::Searchable & options)
620{
621 auto kSearch = options.check("kSearch", yarp::os::Value(0)).asInt32();
622 auto numberOfThreads = options.check("numberOfThreads", yarp::os::Value(0)).asInt32();
623 auto radiusSearch = options.check("radiusSearch", yarp::os::Value(0.0)).asFloat64();
624
625 auto tree = pcl::make_shared<pcl::search::KdTree<T1>>();
626 tree->setInputCloud(in);
627
628 pcl::NormalEstimationOMP<T1, T2> estimator;
629 estimator.setInputCloud(in);
630 estimator.setKSearch(kSearch);
631 estimator.setNumberOfThreads(numberOfThreads);
632 estimator.setRadiusSearch(radiusSearch);
633 estimator.setSearchMethod(tree);
634 estimator.compute(*out);
635
636 checkOutput<T2>(out, "NormalEstimationOMP");
637}
638
639template <typename T>
640void doOrganizedFastMesh(const typename pcl::PointCloud<T>::ConstPtr & in, const pcl::PolygonMesh::Ptr & out, const yarp::os::Searchable & options)
641{
642 if (!in->isOrganized())
643 {
644 // the implementation lacks a proper check
645 throw std::invalid_argument("input cloud must be organized (height > 1) for OrganizedFastMesh");
646 }
647
648 auto angleTolerance = options.check("angleTolerance", yarp::os::Value(12.5 * M_PI / 180)).asFloat32();
649 auto depthDependent = options.check("depthDependent", yarp::os::Value(false)).asBool();
650 auto distanceTolerance = options.check("distanceTolerance", yarp::os::Value(-1.0f)).asFloat32();
651 auto maxEdgeLengthA = options.check("maxEdgeLengthA", yarp::os::Value(0.0f)).asFloat32();
652 auto maxEdgeLengthB = options.check("maxEdgeLengthB", yarp::os::Value(0.0f)).asFloat32();
653 auto maxEdgeLengthC = options.check("maxEdgeLengthC", yarp::os::Value(0.0f)).asFloat32();
654 auto storeShadowedFaces = options.check("storeShadowedFaces", yarp::os::Value(false)).asBool();
655 auto trianglePixelSize = options.check("trianglePixelSize", yarp::os::Value(1)).asInt32();
656 auto trianglePixelSizeColumns = options.check("trianglePixelSizeColumns", yarp::os::Value(trianglePixelSize)).asInt32();
657 auto trianglePixelSizeRows = options.check("trianglePixelSizeRows", yarp::os::Value(trianglePixelSize)).asInt32();
658 auto triangulationTypeStr = options.check("triangulationType", yarp::os::Value("quadMesh")).asString();
659 auto useDepthAsDistance = options.check("useDepthAsDistance", yarp::os::Value(false)).asBool();
660
661 typename pcl::OrganizedFastMesh<T>::TriangulationType triangulationType;
662
663 if (triangulationTypeStr == "quadMesh")
664 {
665 triangulationType = decltype(triangulationType)::QUAD_MESH;
666 }
667 else if (triangulationTypeStr == "triangleAdaptiveCut")
668 {
669 triangulationType = decltype(triangulationType)::TRIANGLE_ADAPTIVE_CUT;
670 }
671 else if (triangulationTypeStr == "triangleLeftCut")
672 {
673 triangulationType = decltype(triangulationType)::TRIANGLE_LEFT_CUT;
674 }
675 else if (triangulationTypeStr == "triangleRightCut")
676 {
677 triangulationType = decltype(triangulationType)::TRIANGLE_RIGHT_CUT;
678 }
679 else
680 {
681 throw std::invalid_argument("unknown triangulation type: " + triangulationTypeStr);
682 }
683
684 pcl::OrganizedFastMesh<T> organized;
685 organized.setAngleTolerance(angleTolerance);
686 organized.setDistanceTolerance(distanceTolerance, depthDependent);
687 organized.setInputCloud(in);
688 organized.setMaxEdgeLength(maxEdgeLengthA, maxEdgeLengthB, maxEdgeLengthC);
689 organized.setTrianglePixelSize(trianglePixelSize);
690 organized.setTrianglePixelSizeColumns(trianglePixelSizeColumns);
691 organized.setTrianglePixelSizeRows(trianglePixelSizeRows);
692 organized.setTriangulationType(triangulationType);
693 organized.storeShadowedFaces(storeShadowedFaces);
694 organized.useDepthAsDistance(useDepthAsDistance);
695 organized.reconstruct(*out);
696
697 checkOutput(out, "OrganizedFastMesh");
698}
699
700template <typename T>
701void doPassThrough(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
702{
703 auto filterFieldName = options.check("filterFieldName", yarp::os::Value("")).asString();
704 auto filterLimitMax = options.check("filterLimitMax", yarp::os::Value(std::numeric_limits<float>::max())).asFloat32();
705 auto filterLimitMin = options.check("filterLimitMin", yarp::os::Value(std::numeric_limits<float>::min())).asFloat32();
706 auto keepOrganized = options.check("keepOrganized", yarp::os::Value(false)).asBool();
707 auto negative = options.check("negative", yarp::os::Value(false)).asBool();
708
709 pcl::PassThrough<T> pass;
710 pass.setFilterFieldName(filterFieldName);
711 pass.setFilterLimits(filterLimitMin, filterLimitMax);
712 pass.setInputCloud(in);
713 pass.setKeepOrganized(keepOrganized);
714 pass.setNegative(negative);
715 pass.filter(*out);
716
717 checkOutput<T>(out, "PassThrough");
718}
719
720template <typename T>
721void doPoisson(const typename pcl::PointCloud<T>::ConstPtr & in, const pcl::PolygonMesh::Ptr & out, const yarp::os::Searchable & options)
722{
723 auto confidence = options.check("confidence", yarp::os::Value(false)).asBool();
724 auto degree = options.check("degree", yarp::os::Value(2)).asInt32();
725 auto depth = options.check("depth", yarp::os::Value(8)).asInt32();
726 auto isoDivide = options.check("isoDivide", yarp::os::Value(8)).asInt32();
727 auto manifold = options.check("manifold", yarp::os::Value(true)).asBool();
728 auto minDepth = options.check("minDepth", yarp::os::Value(5)).asInt32();
729 auto outputPolygons = options.check("outputPolygons", yarp::os::Value(false)).asBool();
730 auto pointWeight = options.check("pointWeight", yarp::os::Value(4.0f)).asFloat32();
731 auto samplesPerNode = options.check("samplesPerNode", yarp::os::Value(1.0f)).asFloat32();
732 auto scale = options.check("scale", yarp::os::Value(1.1f)).asFloat32();
733 auto solverDivide = options.check("solverDivide", yarp::os::Value(8)).asInt32();
734#if PCL_VERSION_COMPARE(>=, 1, 12, 0)
735 auto threads = options.check("threads", yarp::os::Value(1)).asInt32();
736#endif
737
738 auto tree = pcl::make_shared<pcl::search::KdTree<T>>();
739 tree->setInputCloud(in);
740
741 pcl::Poisson<T> poisson;
742 poisson.setConfidence(confidence);
743 poisson.setDegree(degree);
744 poisson.setDepth(depth);
745 poisson.setInputCloud(in);
746 poisson.setIsoDivide(isoDivide);
747 poisson.setManifold(manifold);
748 poisson.setMinDepth(minDepth);
749 poisson.setOutputPolygons(outputPolygons);
750 poisson.setPointWeight(pointWeight);
751 poisson.setSamplesPerNode(samplesPerNode);
752 poisson.setScale(scale);
753 poisson.setSearchMethod(tree);
754 poisson.setSolverDivide(solverDivide);
755#if PCL_VERSION_COMPARE(>=, 1, 12, 0)
756 poisson.setThreads(threads);
757#endif
758 poisson.reconstruct(*out);
759
760 checkOutput(out, "Poisson");
761}
762
763template <typename T>
764void doRadiusOutlierRemoval(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
765{
766 auto keepOrganized = options.check("keepOrganized", yarp::os::Value(false)).asBool();
767 auto minNeighborsInRadius = options.check("minNeighborsInRadius", yarp::os::Value(1)).asInt32();
768 auto negative = options.check("negative", yarp::os::Value(false)).asBool();
769 auto radiusSearch = options.check("radiusSearch", yarp::os::Value(0.0)).asFloat64();
770
771 pcl::RadiusOutlierRemoval<T> remover;
772 remover.setInputCloud(in);
773 remover.setKeepOrganized(keepOrganized);
774 remover.setMinNeighborsInRadius(minNeighborsInRadius);
775 remover.setNegative(negative);
776 remover.setRadiusSearch(radiusSearch);
777 remover.filter(*out);
778
779 checkOutput<T>(out, "RadiusOutlierRemoval");
780}
781
782template <typename T>
783void doRandomSample(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
784{
785 auto keepOrganized = options.check("keepOrganized", yarp::os::Value(false)).asBool();
786 auto negative = options.check("negative", yarp::os::Value(false)).asBool();
787 auto sample = options.check("sample", yarp::os::Value(std::numeric_limits<int>::max())).asInt64(); // note the shortening conversion
788 auto seed = options.check("seed", yarp::os::Value(static_cast<int>(std::time(nullptr)))).asInt64(); // note the shortening conversion
789
790 pcl::RandomSample<T> random;
791 random.setInputCloud(in);
792 random.setKeepOrganized(keepOrganized);
793 random.setNegative(negative);
794 random.setSample(sample);
795 random.setSeed(seed);
796 random.filter(*out);
797
798 checkOutput<T>(out, "RandomSample");
799}
800
801template <typename T>
802void doSamplingSurfaceNormal(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
803{
804 auto ratio = options.check("ratio", yarp::os::Value(0.0f)).asFloat32();
805 auto sample = options.check("sample", yarp::os::Value(10)).asInt32();
806 auto seed = options.check("seed", yarp::os::Value(static_cast<int>(std::time(nullptr)))).asInt64(); // note the shortening conversion
807
808 pcl::SamplingSurfaceNormal<T> sampler;
809 sampler.setInputCloud(in);
810 sampler.setRatio(ratio);
811 sampler.setSample(sample);
812 sampler.setSeed(seed);
813 sampler.filter(*out);
814
815 checkOutput<T>(out, "SamplingSurfaceNormal");
816}
817
818template <typename T>
819void doShadowPoints(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
820{
821 auto keepOrganized = options.check("keepOrganized", yarp::os::Value(false)).asBool();
822 auto negative = options.check("negative", yarp::os::Value(false)).asBool();
823 auto threshold = options.check("threshold", yarp::os::Value(0.1f)).asFloat32();
824
825#if PCL_VERSION_COMPARE(>=, 1, 11, 0)
826 auto temp = std::const_pointer_cast<pcl::PointCloud<T>>(in); // cast away constness
827#else
828 auto temp = boost::const_pointer_cast<pcl::PointCloud<T>>(in); // cast away constness
829#endif
830
831 pcl::ShadowPoints<T, T> shadow;
832 shadow.setInputCloud(in);
833 shadow.setKeepOrganized(keepOrganized);
834 shadow.setNegative(negative);
835 shadow.setNormals(temp); // assumes normals are contained in the input cloud
836 shadow.setThreshold(threshold);
837 shadow.filter(*out);
838
839 checkOutput<T>(out, "ShadowPoints");
840}
841
842void doSimplificationRemoveUnusedVertices(const pcl::PolygonMesh::ConstPtr & in, const pcl::PolygonMesh::Ptr & out, const yarp::os::Searchable & options)
843{
844 pcl::surface::SimplificationRemoveUnusedVertices cleaner;
845 cleaner.simplify(*in, *out);
846 checkOutput(out, "doSimplificationRemoveUnusedVertices");
847}
848
849template <typename T>
850void doStatisticalOutlierRemoval(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
851{
852 auto keepOrganized = options.check("keepOrganized", yarp::os::Value(false)).asBool();
853 auto meanK = options.check("meanK", yarp::os::Value(1)).asInt32();
854 auto negative = options.check("negative", yarp::os::Value(false)).asBool();
855 auto stddevMulThresh = options.check("stddevMulThresh", yarp::os::Value(0.0)).asFloat64();
856
857 pcl::StatisticalOutlierRemoval<T> remover;
858 remover.setInputCloud(in);
859 remover.setKeepOrganized(keepOrganized);
860 remover.setMeanK(meanK);
861 remover.setNegative(negative);
862 remover.setStddevMulThresh(stddevMulThresh);
863 remover.filter(*out);
864
865 checkOutput<T>(out, "StatisticalOutlierRemoval");
866}
867
868template <typename T>
869void doUniformSampling(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
870{
871#if PCL_VERSION_COMPARE(>=, 1, 15, 0)
872 auto keepOrganized = options.check("keepOrganized", yarp::os::Value(false)).asBool();
873 auto negative = options.check("negative", yarp::os::Value(false)).asBool();
874#endif
875 auto radiusSearch = options.check("radiusSearch", yarp::os::Value(0.0)).asFloat64();
876
877 pcl::UniformSampling<T> uniform;
878 uniform.setInputCloud(in);
879#if PCL_VERSION_COMPARE(>=, 1, 15, 0)
880 uniform.setKeepOrganized(keepOrganized);
881 uniform.setNegative(negative);
882#endif
883 uniform.setRadiusSearch(radiusSearch);
884 uniform.filter(*out);
885
886 checkOutput<T>(out, "UniformSampling");
887}
888
889template <typename T>
890void doVoxelGrid(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
891{
892 auto downsampleAllData = options.check("downsampleAllData", yarp::os::Value(true)).asBool();
893 auto leafSize = options.check("leafSize", yarp::os::Value(0.0f)).asFloat32();
894 auto leafSizeX = options.check("leafSizeX", yarp::os::Value(leafSize)).asFloat32();
895 auto leafSizeY = options.check("leafSizeY", yarp::os::Value(leafSize)).asFloat32();
896 auto leafSizeZ = options.check("leafSizeZ", yarp::os::Value(leafSize)).asFloat32();
897 auto limitMax = options.check("limitMax", yarp::os::Value(std::numeric_limits<float>::max())).asFloat64();
898 auto limitMin = options.check("limitMin", yarp::os::Value(-std::numeric_limits<float>::max())).asFloat64();
899 auto limitsNegative = options.check("limitsNegative", yarp::os::Value(false)).asBool();
900 auto minimumPointsNumberPerVoxel = options.check("minimumPointsNumberPerVoxel", yarp::os::Value(0)).asInt32();
901
902 pcl::VoxelGrid<T> grid;
903 grid.setDownsampleAllData(downsampleAllData);
904 grid.setFilterLimits(limitMin, limitMax);
905 grid.setFilterLimitsNegative(limitsNegative);
906 grid.setInputCloud(in);
907 grid.setLeafSize(leafSizeX, leafSizeY, leafSizeZ);
908 grid.setMinimumPointsNumberPerVoxel(minimumPointsNumberPerVoxel);
909 grid.setSaveLeafLayout(false);
910 grid.filter(*out);
911
912 checkOutput<T>(out, "VoxelGrid");
913}
914
915} // namespace
916
917#endif // __YARP_CLOUD_UTILS_PCL_IMPL_HPP__