3 #ifndef __YARP_CLOUD_UTILS_PCL_IMPL_HPP__
4 #define __YARP_CLOUD_UTILS_PCL_IMPL_HPP__
6 #define _USE_MATH_DEFINES
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>
58 auto getTransformation(
const yarp::os::Searchable & options)
60 auto transformation = Eigen::Transform<double, 3, Eigen::Affine>::Identity();
62 if (
const auto & translation = options.find(
"translation"); !translation.isNull())
64 if (!translation.isList() || translation.asList()->size() != 3)
66 throw std::runtime_error(
"translation is not a list or size not equal to 3");
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);
74 if (
const auto & rotation = options.find(
"rotation"); !rotation.isNull())
76 if (!rotation.isList() || rotation.asList()->size() != 3)
78 throw std::runtime_error(
"rotation is not a list or size not equal to 3");
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);
87 return transformation;
91 void checkOutput(
const typename pcl::PointCloud<T>::ConstPtr & cloud,
const std::string & caller)
95 throw std::runtime_error(caller +
" returned an empty cloud");
99 inline void checkOutput(
const pcl::PolygonMesh::ConstPtr & mesh,
const std::string & caller)
101 if (mesh->cloud.data.empty() || mesh->polygons.empty())
103 throw std::runtime_error(caller +
" returned an empty or incomplete mesh");
107 template <
typename T>
108 void doTransformPointCloud(
const typename pcl::PointCloud<T>::ConstPtr & in,
const typename pcl::PointCloud<T>::Ptr & out,
const yarp::os::Searchable & options)
110 auto transformation = getTransformation(options);
111 pcl::transformPointCloud(*in, *out, transformation);
112 checkOutput<T>(out,
"transformPointCloud");
115 template <
typename T>
116 void doTransformPointCloudWithNormals(
const typename pcl::PointCloud<T>::ConstPtr & in,
const typename pcl::PointCloud<T>::Ptr & out,
const yarp::os::Searchable & options)
118 auto transformation = getTransformation(options);
119 pcl::transformPointCloudWithNormals(*in, *out, transformation);
120 checkOutput<T>(out,
"transformPointCloudWithNormals");
123 template <
typename T>
124 void doApproximateVoxelGrid(
const typename pcl::PointCloud<T>::ConstPtr & in,
const typename pcl::PointCloud<T>::Ptr & out,
const yarp::os::Searchable & options)
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();
132 pcl::ApproximateVoxelGrid<T> grid;
133 grid.setDownsampleAllData(downsampleAllData);
134 grid.setInputCloud(in);
135 grid.setLeafSize(leafSizeX, leafSizeY, leafSizeZ);
138 checkOutput<T>(out,
"ApproximateVoxelGrid");
141 template <
typename T>
142 void doBilateralFilter(
const typename pcl::PointCloud<T>::ConstPtr & in,
const typename pcl::PointCloud<T>::Ptr & out,
const yarp::os::Searchable & options)
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();
147 auto tree = pcl::make_shared<pcl::search::KdTree<T>>();
148 tree->setInputCloud(in);
150 pcl::BilateralFilter<T> filter;
151 filter.setHalfSize(halfSize);
152 filter.setInputCloud(in);
153 filter.setSearchMethod(tree);
154 filter.setStdDev(stdDev);
157 checkOutput<T>(out,
"BilateralFilter");
160 template <
typename T>
161 void doBilateralUpsampling(
const typename pcl::PointCloud<T>::ConstPtr & in,
const typename pcl::PointCloud<T>::Ptr & out,
const yarp::os::Searchable & options)
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();
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);
174 checkOutput<T>(out,
"BilateralUpsampling");
177 template <
typename T>
178 void doConcaveHull(
const typename pcl::PointCloud<T>::ConstPtr & in,
const pcl::PolygonMesh::Ptr & out,
const yarp::os::Searchable & options)
180 auto alpha = options.check(
"alpha", yarp::os::Value(0.0)).asFloat64();
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);
189 checkOutput(out,
"ConcaveHull");
192 template <
typename T>
193 void doConvexHull(
const typename pcl::PointCloud<T>::ConstPtr & in,
const pcl::PolygonMesh::Ptr & out,
const yarp::os::Searchable & options)
195 pcl::ConvexHull<T> convex;
196 convex.setDimension(3);
197 convex.setInputCloud(in);
198 convex.reconstruct(*out);
200 checkOutput(out,
"ConvexHull");
203 template <
typename T>
204 void doCropBox(
const typename pcl::PointCloud<T>::ConstPtr & in,
const typename pcl::PointCloud<T>::Ptr & out,
const yarp::os::Searchable & options)
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();
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);
231 checkOutput<T>(out,
"CropBox");
234 template <
typename T>
235 void doFastBilateralFilter(
const typename pcl::PointCloud<T>::ConstPtr & in,
const typename pcl::PointCloud<T>::Ptr & out,
const yarp::os::Searchable & options)
237 auto sigmaR = options.check(
"sigmaR", yarp::os::Value(0.05f)).asFloat32();
238 auto sigmaS = options.check(
"sigmaS", yarp::os::Value(15.0f)).asFloat32();
240 pcl::FastBilateralFilter<T> fast;
241 fast.setInputCloud(in);
242 fast.setSigmaR(sigmaR);
243 fast.setSigmaS(sigmaS);
246 checkOutput<T>(out,
"FastBilateralFilter");
249 template <
typename T>
250 void doFastBilateralFilterOMP(
const typename pcl::PointCloud<T>::ConstPtr & in,
const typename pcl::PointCloud<T>::Ptr & out,
const yarp::os::Searchable & options)
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();
256 pcl::FastBilateralFilterOMP<T> fast;
257 fast.setInputCloud(in);
258 fast.setNumberOfThreads(numberOfThreads);
259 fast.setSigmaR(sigmaR);
260 fast.setSigmaS(sigmaS);
263 checkOutput<T>(out,
"FastBilateralFilterOMP");
266 template <
typename T>
267 void doGreedyProjectionTriangulation(
const typename pcl::PointCloud<T>::ConstPtr & in,
const pcl::PolygonMesh::Ptr & out,
const yarp::os::Searchable & options)
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();
278 auto tree = pcl::make_shared<pcl::search::KdTree<T>>();
279 tree->setInputCloud(in);
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);
289 gp3.setNormalConsistency(normalConsistency);
290 gp3.setSearchMethod(tree);
291 gp3.setSearchRadius(searchRadius);
292 gp3.reconstruct(*out);
294 checkOutput(out,
"GreedyProjectionTriangulation");
297 template <
typename T>
298 void doGridMinimum(
const typename pcl::PointCloud<T>::ConstPtr & in,
const typename pcl::PointCloud<T>::Ptr & out,
const yarp::os::Searchable & options)
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();
304 pcl::GridMinimum<T> grid(resolution);
306 grid.setInputCloud(in);
307 grid.setKeepOrganized(keepOrganized);
308 grid.setNegative(negative);
311 checkOutput<T>(out,
"GridMinimum");
314 template <
typename T>
315 void doGridProjection(
const typename pcl::PointCloud<T>::ConstPtr & in,
const pcl::PolygonMesh::Ptr & out,
const yarp::os::Searchable & options)
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();
322 auto tree = pcl::make_shared<pcl::search::KdTree<T>>();
323 tree->setInputCloud(in);
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);
334 checkOutput(out,
"GridProjection");
337 template <
typename T>
338 void doLocalMaximum(
const typename pcl::PointCloud<T>::ConstPtr & in,
const typename pcl::PointCloud<T>::Ptr & out,
const yarp::os::Searchable & options)
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();
344 pcl::LocalMaximum<T> local;
345 local.setInputCloud(in);
346 local.setKeepOrganized(keepOrganized);
347 local.setNegative(negative);
348 local.setRadius(radius);
351 checkOutput<T>(out,
"LocalMaximum");
354 template <
typename T>
355 void doMarchingCubesHoppe(
const typename pcl::PointCloud<T>::ConstPtr & in,
const pcl::PolygonMesh::Ptr & out,
const yarp::os::Searchable & options)
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();
365 auto tree = pcl::make_shared<pcl::search::KdTree<T>>();
366 tree->setInputCloud(in);
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);
377 checkOutput(out,
"MarchingCubesHoppe");
380 template <
typename T>
381 void doMarchingCubesRBF(
const typename pcl::PointCloud<T>::ConstPtr & in,
const pcl::PolygonMesh::Ptr & out,
const yarp::os::Searchable & options)
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();
391 auto tree = pcl::make_shared<pcl::search::KdTree<T>>();
392 tree->setInputCloud(in);
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);
403 checkOutput(out,
"MarchingCubesRBF");
406 template <
typename T>
407 void doMedianFilter(
const typename pcl::PointCloud<T>::ConstPtr & in,
const typename pcl::PointCloud<T>::Ptr & out,
const yarp::os::Searchable & options)
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();
412 pcl::MedianFilter<T> median;
413 median.setInputCloud(in);
414 median.setMaxAllowedMovement(maxAllowedMovement);
415 median.setWindowSize(windowSize);
418 checkOutput<T>(out,
"MedianFilter");
421 void doMeshQuadricDecimationVTK(
const pcl::PolygonMesh::ConstPtr & in,
const pcl::PolygonMesh::Ptr & out,
const yarp::os::Searchable & options)
423 auto targetReductionFactor = options.check(
"targetReductionFactor", yarp::os::Value(0.5f)).asFloat32();
425 pcl::MeshQuadricDecimationVTK quadric;
426 quadric.setInputMesh(in);
427 quadric.setTargetReductionFactor(targetReductionFactor);
428 quadric.process(*out);
430 checkOutput(out,
"MeshQuadricDecimationVTK");
433 void doMeshSmoothingLaplacianVTK(
const pcl::PolygonMesh::ConstPtr & in,
const pcl::PolygonMesh::Ptr & out,
const yarp::os::Searchable & options)
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();
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);
454 checkOutput(out,
"MeshSmoothingLaplacianVTK");
457 void doMeshSmoothingWindowedSincVTK(
const pcl::PolygonMesh::ConstPtr & in,
const pcl::PolygonMesh::Ptr & out,
const yarp::os::Searchable & options)
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();
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);
478 checkOutput(out,
"MeshSmoothingWindowedSincVTK");
481 void doMeshSubdivisionVTK(
const pcl::PolygonMesh::ConstPtr & in,
const pcl::PolygonMesh::Ptr & out,
const yarp::os::Searchable & options)
483 auto filterTypeStr = options.check(
"filterType", yarp::os::Value(
"linear")).asString();
485 pcl::MeshSubdivisionVTK::MeshSubdivisionVTKFilterType filterType;
487 if (filterTypeStr ==
"butterfly")
489 filterType = pcl::MeshSubdivisionVTK::MeshSubdivisionVTKFilterType::BUTTERFLY;
491 else if (filterTypeStr ==
"linear")
493 filterType = pcl::MeshSubdivisionVTK::MeshSubdivisionVTKFilterType::LINEAR;
495 else if (filterTypeStr ==
"loop")
497 filterType = pcl::MeshSubdivisionVTK::MeshSubdivisionVTKFilterType::LOOP;
501 throw std::invalid_argument(
"unknown filter type: " + filterTypeStr);
504 pcl::MeshSubdivisionVTK subdivision;
505 subdivision.setFilterType(filterType);
506 subdivision.setInputMesh(in);
507 subdivision.process(*out);
509 checkOutput(out,
"MeshSubdivisionVTK");
512 template <
typename T1,
typename T2 = T1>
513 void doMovingLeastSquares(
const typename pcl::PointCloud<T1>::ConstPtr & in,
const typename pcl::PointCloud<T2>::Ptr & out,
const yarp::os::Searchable & options)
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();
529 pcl::MLSResult::ProjectionMethod projectionMethod;
531 if (projectionMethodStr ==
"none")
533 projectionMethod = pcl::MLSResult::ProjectionMethod::NONE;
535 else if (projectionMethodStr ==
"orthogonal")
537 projectionMethod = pcl::MLSResult::ProjectionMethod::ORTHOGONAL;
539 else if (projectionMethodStr ==
"simple")
541 projectionMethod = pcl::MLSResult::ProjectionMethod::SIMPLE;
545 throw std::invalid_argument(
"unknown projection method: " + projectionMethodStr);
548 typename pcl::MovingLeastSquares<T1, T2>::UpsamplingMethod upsamplingMethod;
550 if (upsamplingMethodStr ==
"distinctCloud")
552 upsamplingMethod = decltype(upsamplingMethod)::DISTINCT_CLOUD;
554 else if (upsamplingMethodStr ==
"none")
556 upsamplingMethod = decltype(upsamplingMethod)::NONE;
558 else if (upsamplingMethodStr ==
"randomUniformDensity")
560 upsamplingMethod = decltype(upsamplingMethod)::RANDOM_UNIFORM_DENSITY;
562 else if (upsamplingMethodStr ==
"sampleLocalPlane")
564 upsamplingMethod = decltype(upsamplingMethod)::SAMPLE_LOCAL_PLANE;
566 else if (upsamplingMethodStr ==
"voxelGridDilation")
568 upsamplingMethod = decltype(upsamplingMethod)::VOXEL_GRID_DILATION;
572 throw std::invalid_argument(
"unknown upsampling method: " + upsamplingMethodStr);
575 auto tree = pcl::make_shared<pcl::search::KdTree<T1>>();
576 tree->setInputCloud(in);
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);
596 checkOutput<T2>(out,
"MovingLeastSquares");
599 template <
typename T1,
typename T2>
600 void doNormalEstimation(
const typename pcl::PointCloud<T1>::ConstPtr & in,
const typename pcl::PointCloud<T2>::Ptr & out,
const yarp::os::Searchable & options)
602 auto kSearch = options.check(
"kSearch", yarp::os::Value(0)).asInt32();
603 auto radiusSearch = options.check(
"radiusSearch", yarp::os::Value(0.0)).asFloat64();
605 auto tree = pcl::make_shared<pcl::search::KdTree<T1>>();
606 tree->setInputCloud(in);
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);
615 checkOutput<T2>(out,
"NormalEstimation");
618 template <
typename T1,
typename T2>
619 void doNormalEstimationOMP(
const typename pcl::PointCloud<T1>::ConstPtr & in,
const typename pcl::PointCloud<T2>::Ptr & out,
const yarp::os::Searchable & options)
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();
625 auto tree = pcl::make_shared<pcl::search::KdTree<T1>>();
626 tree->setInputCloud(in);
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);
636 checkOutput<T2>(out,
"NormalEstimationOMP");
639 template <
typename T>
640 void doOrganizedFastMesh(
const typename pcl::PointCloud<T>::ConstPtr & in,
const pcl::PolygonMesh::Ptr & out,
const yarp::os::Searchable & options)
642 if (!in->isOrganized())
645 throw std::invalid_argument(
"input cloud must be organized (height > 1) for OrganizedFastMesh");
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();
661 typename pcl::OrganizedFastMesh<T>::TriangulationType triangulationType;
663 if (triangulationTypeStr ==
"quadMesh")
665 triangulationType = decltype(triangulationType)::QUAD_MESH;
667 else if (triangulationTypeStr ==
"triangleAdaptiveCut")
669 triangulationType = decltype(triangulationType)::TRIANGLE_ADAPTIVE_CUT;
671 else if (triangulationTypeStr ==
"triangleLeftCut")
673 triangulationType = decltype(triangulationType)::TRIANGLE_LEFT_CUT;
675 else if (triangulationTypeStr ==
"triangleRightCut")
677 triangulationType = decltype(triangulationType)::TRIANGLE_RIGHT_CUT;
681 throw std::invalid_argument(
"unknown triangulation type: " + triangulationTypeStr);
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);
697 checkOutput(out,
"OrganizedFastMesh");
700 template <
typename T>
701 void doPassThrough(
const typename pcl::PointCloud<T>::ConstPtr & in,
const typename pcl::PointCloud<T>::Ptr & out,
const yarp::os::Searchable & options)
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();
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);
717 checkOutput<T>(out,
"PassThrough");
720 template <
typename T>
721 void doPoisson(
const typename pcl::PointCloud<T>::ConstPtr & in,
const pcl::PolygonMesh::Ptr & out,
const yarp::os::Searchable & options)
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();
738 auto tree = pcl::make_shared<pcl::search::KdTree<T>>();
739 tree->setInputCloud(in);
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);
758 poisson.reconstruct(*out);
760 checkOutput(out,
"Poisson");
763 template <
typename T>
764 void doRadiusOutlierRemoval(
const typename pcl::PointCloud<T>::ConstPtr & in,
const typename pcl::PointCloud<T>::Ptr & out,
const yarp::os::Searchable & options)
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();
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);
779 checkOutput<T>(out,
"RadiusOutlierRemoval");
782 template <
typename T>
783 void doRandomSample(
const typename pcl::PointCloud<T>::ConstPtr & in,
const typename pcl::PointCloud<T>::Ptr & out,
const yarp::os::Searchable & options)
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();
788 auto seed = options.check(
"seed", yarp::os::Value(
static_cast<int>(std::time(
nullptr)))).asInt64();
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);
798 checkOutput<T>(out,
"RandomSample");
801 template <
typename T>
802 void doSamplingSurfaceNormal(
const typename pcl::PointCloud<T>::ConstPtr & in,
const typename pcl::PointCloud<T>::Ptr & out,
const yarp::os::Searchable & options)
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();
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);
815 checkOutput<T>(out,
"SamplingSurfaceNormal");
818 template <
typename T>
819 void doShadowPoints(
const typename pcl::PointCloud<T>::ConstPtr & in,
const typename pcl::PointCloud<T>::Ptr & out,
const yarp::os::Searchable & options)
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();
825 #if PCL_VERSION_COMPARE(>=, 1, 11, 0)
826 auto temp = std::const_pointer_cast<pcl::PointCloud<T>>(in);
828 auto temp = boost::const_pointer_cast<pcl::PointCloud<T>>(in);
831 pcl::ShadowPoints<T, T> shadow;
832 shadow.setInputCloud(in);
833 shadow.setKeepOrganized(keepOrganized);
834 shadow.setNegative(negative);
835 shadow.setNormals(temp);
836 shadow.setThreshold(threshold);
839 checkOutput<T>(out,
"ShadowPoints");
842 void doSimplificationRemoveUnusedVertices(
const pcl::PolygonMesh::ConstPtr & in,
const pcl::PolygonMesh::Ptr & out,
const yarp::os::Searchable & options)
844 pcl::surface::SimplificationRemoveUnusedVertices cleaner;
845 cleaner.simplify(*in, *out);
846 checkOutput(out,
"doSimplificationRemoveUnusedVertices");
849 template <
typename T>
850 void doStatisticalOutlierRemoval(
const typename pcl::PointCloud<T>::ConstPtr & in,
const typename pcl::PointCloud<T>::Ptr & out,
const yarp::os::Searchable & options)
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();
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);
865 checkOutput<T>(out,
"StatisticalOutlierRemoval");
868 template <
typename T>
869 void doUniformSampling(
const typename pcl::PointCloud<T>::ConstPtr & in,
const typename pcl::PointCloud<T>::Ptr & out,
const yarp::os::Searchable & options)
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();
875 auto radiusSearch = options.check(
"radiusSearch", yarp::os::Value(0.0)).asFloat64();
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);
883 uniform.setRadiusSearch(radiusSearch);
884 uniform.filter(*out);
886 checkOutput<T>(out,
"UniformSampling");
889 template <
typename T>
890 void doVoxelGrid(
const typename pcl::PointCloud<T>::ConstPtr & in,
const typename pcl::PointCloud<T>::Ptr & out,
const yarp::os::Searchable & options)
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();
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);
912 checkOutput<T>(out,
"VoxelGrid");