diff --git a/noether_tpp/CMakeLists.txt b/noether_tpp/CMakeLists.txt index 7cfdbdab..86774bb5 100644 --- a/noether_tpp/CMakeLists.txt +++ b/noether_tpp/CMakeLists.txt @@ -7,7 +7,7 @@ extract_package_metadata(pkg) project(${pkg_extracted_name} VERSION ${pkg_extracted_version} LANGUAGES C CXX) find_package(Eigen3 REQUIRED) -find_package(PCL REQUIRED COMPONENTS common io surface) +find_package(PCL REQUIRED COMPONENTS common io surface segmentation) find_package(VTK REQUIRED NO_MODULE) if(VTK_FOUND AND ("${VTK_VERSION}" VERSION_LESS 7.1)) @@ -33,6 +33,10 @@ add_library(${PROJECT_NAME} SHARED src/mesh_modifiers/subset_extraction/subset_extractor.cpp src/mesh_modifiers/subset_extraction/extruded_polygon_subset_extractor.cpp src/mesh_modifiers/compound_modifier.cpp + src/mesh_modifiers/clean_data_modifier.cpp + src/mesh_modifiers/euclidean_clustering_modifier.cpp + src/mesh_modifiers/fill_holes_modifier.cpp + src/mesh_modifiers/windowed_sinc_smoothing.cpp # Tool Path Modifiers src/tool_path_modifiers/circular_lead_in_modifier.cpp src/tool_path_modifiers/circular_lead_out_modifier.cpp @@ -59,6 +63,21 @@ add_library(${PROJECT_NAME} SHARED src/tool_path_planners/raster/plane_slicer_raster_planner.cpp ) +if(${CMAKE_VERSION} VERSION_GREATER 3.15) + try_compile( + NURBS_FOUND + ${CMAKE_CURRENT_BINARY_DIR}/pcl_nurbs_try_compile + ${CMAKE_CURRENT_SOURCE_DIR}/src/mesh_modifiers/test/check_pcl_nurbs.cpp + CMAKE_FLAGS ${CMAKE_FLAGS} -DINCLUDE_DIRECTORIES=${PCL_INCLUDE_DIRS} + LINK_LIBRARIES ${PCL_LIBRARIES} + ) + if (${NURBS_FOUND}) + target_sources(${PROJECT_NAME} src/mesh_modifiers/bspline_reconstruction_modifier.cpp) + else() + message("PCL NURBS not found; skipping compilation of BSpline reconstruction mesh modifier") + endif() +endif() + target_include_directories(${PROJECT_NAME} PUBLIC "$" "$") @@ -82,4 +101,4 @@ if(${NOETHER_ENABLE_TESTING}) endif() # Package configuration -configure_package(NAMESPACE noether DEPENDENCIES Eigen3 "PCL REQUIRED COMPONENTS common io surface" VTK TARGETS ${PROJECT_NAME}) +configure_package(NAMESPACE noether DEPENDENCIES Eigen3 "PCL REQUIRED COMPONENTS common io surface segmentation" VTK TARGETS ${PROJECT_NAME}) diff --git a/noether_tpp/include/noether_tpp/mesh_modifiers/bspline_reconstruction_modifier.h b/noether_tpp/include/noether_tpp/mesh_modifiers/bspline_reconstruction_modifier.h new file mode 100644 index 00000000..cdb68c20 --- /dev/null +++ b/noether_tpp/include/noether_tpp/mesh_modifiers/bspline_reconstruction_modifier.h @@ -0,0 +1,78 @@ +/** + * @author Jorge Nicho + * @file bspline_reconstruction.cpp + * @date Oct 10, 2019 + * @copyright Copyright (c) 2019, Southwest Research Institute + * + * @par License + * Software License Agreement (Apache License) + * @par + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * http://www.apache.org/licenses/LICENSE-2.0 + * @par + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#pragma once + +#include +#include +#include + +namespace noether +{ +/** + * @class noether_filtering::filters::BSplineReconstruction + * @details: Smoothes a mesh by fitting a bspline surface to it. The details of this implementation' + * can be in found in http://pointclouds.org/documentation/tutorials/bspline_fitting.php + */ +class BSplineReconstruction : public MeshModifier +{ +public: + enum class SurfInitMethod : int + { + PCA = 1, + PCA_BB, + CUSTOM_PLANE, // not implemented yet but will use pcl::on_nurbs::FittingSurface::initNurbs4Corners + }; + + struct Parameters + { + /** @brief print more info */ + bool verbosity_on = false; + /** @brief is the polynomial order of the B-spline surface. */ + int order = 3; + /** @brief refinement is the number of refinement iterations, where for each iteration control-points are inserted */ + int refinement = 3; + /** @brief is the number of iterations that are performed after refinement is completed */ + unsigned iterations = 1; + /** @brief the number of vertices in each parametric direction, used for triangulation of the B-spline surface.*/ + unsigned mesh_resolution = 50; + /** @brief method for creating the initial surface to be fit */ + SurfInitMethod surf_init_method = SurfInitMethod::PCA_BB; + /** @brief parameters to fit the surface**/ + pcl::on_nurbs::FittingSurface::Parameter surface_params; + /** @brief whether to fit the boundary curve and clip every that extends past it*/ + bool clip_boundary_curve = true; + /** @brief applicable only when clip_boundary_curve = true */ + int boundary_fit_order = 2; + /** @brief initial number of control points */ + int boundary_startCPs = 0; + /** @brief if True then algorithm will fail if the boundary could not be clipped */ + bool boundary_clipping_required = false; + pcl::on_nurbs::FittingCurve2dAPDM::FitParameter boundary_curve_params; + }; + + std::vector modify(const pcl::PolygonMesh &mesh) const override; + +protected: + Parameters parameters_; +}; + +} // namespace noether diff --git a/noether_tpp/include/noether_tpp/mesh_modifiers/clean_data_modifier.h b/noether_tpp/include/noether_tpp/mesh_modifiers/clean_data_modifier.h new file mode 100644 index 00000000..9d4f386f --- /dev/null +++ b/noether_tpp/include/noether_tpp/mesh_modifiers/clean_data_modifier.h @@ -0,0 +1,40 @@ +/** + * @author Jorge Nicho + * @file clean_data.h + * @date Dec 6, 2019 + * @copyright Copyright (c) 2019, Southwest Research Institute + * + * @par License + * Software License Agreement (Apache License) + * @par + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * http://www.apache.org/licenses/LICENSE-2.0 + * @par + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#pragma once + +#include + +namespace noether +{ +/** + * @class noether_filtering::mesh::CleanData + * @details Uses the VTK capability shown in this example + * https://lorensen.github.io/VTKExamples/site/Cxx/PolyData/CleanPolyData/ Merges duplicate points, and/or remove unused + * points and/or remove degenerate cells + */ +class CleanData : public MeshModifier +{ +public: + std::vector modify(const pcl::PolygonMesh& mesh) const override; +}; + +} // namespace noether diff --git a/noether_tpp/include/noether_tpp/mesh_modifiers/euclidean_clustering_modifier.h b/noether_tpp/include/noether_tpp/mesh_modifiers/euclidean_clustering_modifier.h new file mode 100644 index 00000000..b3cbd25e --- /dev/null +++ b/noether_tpp/include/noether_tpp/mesh_modifiers/euclidean_clustering_modifier.h @@ -0,0 +1,44 @@ +/** + * @author Jorge Nicho + * @file euclidean_clustering.h + * @date Nov 26, 2019 + * @copyright Copyright (c) 2019, Southwest Research Institute + * + * @par License + * Software License Agreement (Apache License) + * @par + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * http://www.apache.org/licenses/LICENSE-2.0 + * @par + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#pragma once + +#include + +namespace noether +{ +class EuclideanClustering : public MeshModifier +{ +public: + struct Parameters + { + double tolerance = 0.02; // meters + int min_cluster_size = 100; + int max_cluster_size = -1; // will use input point cloud size when negative + }; + + std::vector modify(const pcl::PolygonMesh& mesh_in) const override; + +protected: + Parameters parameters_; +}; + +} // namespace noether diff --git a/noether_tpp/include/noether_tpp/mesh_modifiers/fill_holes_modifier.h b/noether_tpp/include/noether_tpp/mesh_modifiers/fill_holes_modifier.h new file mode 100644 index 00000000..b19e206b --- /dev/null +++ b/noether_tpp/include/noether_tpp/mesh_modifiers/fill_holes_modifier.h @@ -0,0 +1,41 @@ +/** + * @author Jorge Nicho + * @file fill_holes.h + * @date Dec 16, 2019 + * @copyright Copyright (c) 2019, Southwest Research Institute + * + * @par License + * Software License Agreement (Apache License) + * @par + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * http://www.apache.org/licenses/LICENSE-2.0 + * @par + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#pragma once + +#include + +namespace noether +{ +/** + * @class noether_filtering::mesh::FillHoles + * @brief Applies the vtkFillHoles filter, more details can be found on + * https://vtk.org/doc/nightly/html/classvtkFillHolesFilter.html#details + */ +class FillHoles : public MeshModifier +{ +public: + std::vector modify(const pcl::PolygonMesh &mesh) const override; + +protected: + double hole_size_ = 1.0; +}; + +} // namespace noether diff --git a/noether_tpp/include/noether_tpp/mesh_modifiers/windowed_sinc_smoothing_modifier.h b/noether_tpp/include/noether_tpp/mesh_modifiers/windowed_sinc_smoothing_modifier.h new file mode 100644 index 00000000..2f6834f8 --- /dev/null +++ b/noether_tpp/include/noether_tpp/mesh_modifiers/windowed_sinc_smoothing_modifier.h @@ -0,0 +1,48 @@ +/* + * window_sinc_smoothing.h + * + * Created on: Dec 6, 2019 + * Author: jrgnicho + */ + +#pragma once + +#include + +namespace noether +{ +/** + * @class noether_filtering:;mesh::WindowedSincSmoothing + * @details uses the vtkWindowedSincPolyDataFilter to smooth out the mesh, details of the implementation + * and the configuration parameters can be found here + * https://vtk.org/doc/nightly/html/classvtkWindowedSincPolyDataFilter.html + */ +class WindowedSincSmoothing : public MeshModifier +{ +public: + struct Config + { + std::size_t num_iter = 100; + /**@brief Set to true to enable */ + bool enable_boundary_smoothing = true; + /**@brief Set to true to enable */ + bool enable_feature_edge_smoothing = false; + /**@brief Set to true to enable */ + bool enable_non_manifold_smoothing = true; + /**@brief Set to true to enable */ + bool enable_normalize_coordinates = true; + /**@brief degrees, only applicable when feature_edge_smoothing = true */ + double feature_angle = 10.0; + /**@brief degrees, only applicable when feature_edge_smoothing = true */ + double edge_angle = 150.0; + /**@brief PassBand for the windowed sinc filter, see explanation in reference link */ + double pass_band = 0.01; + }; + + std::vector modify(const pcl::PolygonMesh &mesh) const override; + +protected: + Config config_; +}; + +} /* namespace noether_filtering */ diff --git a/noether_tpp/src/mesh_modifiers/bspline_reconstruction_modifier.cpp b/noether_tpp/src/mesh_modifiers/bspline_reconstruction_modifier.cpp new file mode 100644 index 00000000..251c0b0c --- /dev/null +++ b/noether_tpp/src/mesh_modifiers/bspline_reconstruction_modifier.cpp @@ -0,0 +1,124 @@ +/** + * @author Jorge Nicho + * @file bspline_reconstruction.cpp + * @date Oct 10, 2019 + * @copyright Copyright (c) 2019, Southwest Research Institute + * + * @par License + * Software License Agreement (Apache License) + * @par + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * http://www.apache.org/licenses/LICENSE-2.0 + * @par + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include +#include +#include + +static pcl::on_nurbs::vector_vec3d createNurbData(pcl::PointCloud::ConstPtr cloud) +{ + pcl::on_nurbs::vector_vec3d data; + for (unsigned i = 0; i < cloud->size(); i++) + { + const pcl::PointXYZ& p = cloud->at(i); + if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) + data.push_back(Eigen::Vector3d(p.x, p.y, p.z)); + } + return std::move(data); +} + +namespace noether +{ +pcl::PolygonMesh BSplineReconstruction::modify(const pcl::PolygonMesh& mesh_in) const +{ + using Cloud = pcl::PointCloud; + + // converting to point cloud + Cloud::Ptr cloud_in = boost::make_shared(); + pcl::fromPCLPointCloud2(mesh_in.cloud, *cloud_in); + + // initializing nurbs_surface surface + pcl::on_nurbs::NurbsDataSurface nurbs_data = pcl::on_nurbs::NurbsDataSurface(); + nurbs_data.interior = createNurbData(cloud_in); + ON_NurbsSurface nurbs_surface; + switch (parameters_.surf_init_method) + { + case SurfInitMethod::PCA: + nurbs_surface = + pcl::on_nurbs::FittingSurface::initNurbsPCA(parameters_.order, &nurbs_data, Eigen::Vector3d::UnitZ()); + break; + case SurfInitMethod::PCA_BB: + nurbs_surface = pcl::on_nurbs::FittingSurface::initNurbsPCABoundingBox( + parameters_.order, &nurbs_data, Eigen::Vector3d::UnitZ()); + break; + case SurfInitMethod::CUSTOM_PLANE: + throw std::runtime_error("The surface initialization method 'CUSTOM_PLANE' is not yet implemented"); + default: + throw std::runtime_error("The surface initialization method was not recognized"); + } + + // fitting surface + pcl::on_nurbs::FittingSurface fit(&nurbs_data, nurbs_surface); + fit.setQuiet(!parameters_.verbosity_on); // enable/disable debug output + pcl::on_nurbs::FittingSurface::Parameter surf_params = parameters_.surface_params; + for (int i = 0; i < parameters_.refinement; i++) + { + fit.refine(0); + fit.refine(1); + fit.assemble(surf_params); + fit.solve(); + } + + // improving fit + for (unsigned i = 0; i < parameters_.iterations; i++) + { + fit.assemble(surf_params); + fit.solve(); + } + + if (!fit.m_nurbs.IsValid()) + throw std::runtime_error("Surface fitting failed"); + + // fit B-spline boundary curve + std::shared_ptr curve_fit = nullptr; + if (parameters_.clip_boundary_curve) + { + // initialisation (circular) + pcl::on_nurbs::NurbsDataCurve2d curve_data; + curve_data.interior = nurbs_data.interior_param; + curve_data.interior_weight_function.push_back(true); + ON_NurbsCurve curve_nurbs = pcl::on_nurbs::FittingCurve2dAPDM::initNurbsCurve2D( + parameters_.boundary_fit_order, curve_data.interior, parameters_.boundary_startCPs); + + // curve fitting + curve_fit = std::make_shared(&curve_data, curve_nurbs); + curve_fit->setQuiet(!parameters_.verbosity_on); // enable/disable debug output + curve_fit->fitting(parameters_.boundary_curve_params); + + if (!curve_fit->m_nurbs.IsValid() && parameters_.boundary_clipping_required) + throw std::runtime_error("Failed to fit boundary curve"); + } + + pcl::PolygonMesh mesh_out; + if (curve_fit && curve_fit->m_nurbs.IsValid()) + { + pcl::on_nurbs::Triangulation::convertTrimmedSurface2PolygonMesh( + fit.m_nurbs, curve_fit->m_nurbs, mesh_out, parameters_.mesh_resolution); + } + else + { + pcl::on_nurbs::Triangulation::convertSurface2PolygonMesh(fit.m_nurbs, mesh_out, parameters_.mesh_resolution); + } + + return { mesh_out }; +} + +} // namespace noether diff --git a/noether_tpp/src/mesh_modifiers/clean_data_modifier.cpp b/noether_tpp/src/mesh_modifiers/clean_data_modifier.cpp new file mode 100644 index 00000000..8809e426 --- /dev/null +++ b/noether_tpp/src/mesh_modifiers/clean_data_modifier.cpp @@ -0,0 +1,33 @@ +/* + * clean_data.cpp + * + * Created on: Dec 6, 2019 + * Author: jrgnicho + */ + +#include + +#include +#include + +namespace noether +{ +std::vector CleanData::modify(const pcl::PolygonMesh& mesh_in) const +{ + vtkSmartPointer mesh_data = vtkSmartPointer::New(); + pcl::VTKUtils::mesh2vtk(mesh_in, mesh_data); + + mesh_data->BuildCells(); + mesh_data->BuildLinks(); + + vtkSmartPointer cleanPolyData = vtkSmartPointer::New(); + cleanPolyData->SetInputData(mesh_data); + cleanPolyData->Update(); + mesh_data = cleanPolyData->GetOutput(); + + pcl::PolygonMesh mesh_out; + pcl::VTKUtils::vtk2mesh(mesh_data, mesh_out); + return { mesh_out }; +} + +} // namespace noether diff --git a/noether_tpp/src/mesh_modifiers/euclidean_clustering_modifier.cpp b/noether_tpp/src/mesh_modifiers/euclidean_clustering_modifier.cpp new file mode 100644 index 00000000..116e5f5e --- /dev/null +++ b/noether_tpp/src/mesh_modifiers/euclidean_clustering_modifier.cpp @@ -0,0 +1,60 @@ +/** + * @author Jorge Nicho + * @file euclidean_clustering.cpp + * @date Nov 26, 2019 + * @copyright Copyright (c) 2019, Southwest Research Institute + * + * @par License + * Software License Agreement (Apache License) + * @par + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * http://www.apache.org/licenses/LICENSE-2.0 + * @par + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#include +#include + +#include +#include +#include +#include + +namespace noether +{ +std::vector EuclideanClustering::modify(const pcl::PolygonMesh& mesh_in) const +{ + // converting to point cloud + auto mesh_points = pcl::make_shared>(); + pcl::fromPCLPointCloud2(mesh_in.cloud, *mesh_points); + + // computing clusters + auto tree = pcl::make_shared>(); + tree->setInputCloud(mesh_points); + std::vector cluster_indices; + pcl::EuclideanClusterExtraction ec; + ec.setClusterTolerance(parameters_.tolerance); + ec.setMinClusterSize(parameters_.min_cluster_size); + ec.setMaxClusterSize(parameters_.max_cluster_size <= 0 ? mesh_points->size() : parameters_.max_cluster_size); + ec.setSearchMethod(tree); + ec.setInputCloud(mesh_points); + ec.extract(cluster_indices); + + if (cluster_indices.empty()) + throw std::runtime_error("No clusters found"); + + std::vector meshes; + meshes.reserve(cluster_indices.size()); + for(const pcl::PointIndices& cluster : cluster_indices) + meshes.push_back(extractSubMeshFromInlierVertices(mesh_in, cluster.indices)); + + return meshes; +} + +} // namespace noether diff --git a/noether_tpp/src/mesh_modifiers/fill_holes_modifier.cpp b/noether_tpp/src/mesh_modifiers/fill_holes_modifier.cpp new file mode 100644 index 00000000..c9d521e2 --- /dev/null +++ b/noether_tpp/src/mesh_modifiers/fill_holes_modifier.cpp @@ -0,0 +1,51 @@ +/** + * @author Jorge Nicho + * @file fill_holes.pp + * @date Dec 16, 2019 + * @copyright Copyright (c) 2019, Southwest Research Institute + * + * @par License + * Software License Agreement (Apache License) + * @par + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * http://www.apache.org/licenses/LICENSE-2.0 + * @par + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +#include + +#include +#include +#include + +namespace noether +{ +std::vector FillHoles::modify(const pcl::PolygonMesh& mesh_in) const +{ + vtkSmartPointer mesh_data = vtkSmartPointer::New(); + pcl::VTKUtils::mesh2vtk(mesh_in, mesh_data); + + vtkSmartPointer fill_holes_filter = vtkSmartPointer::New(); + fill_holes_filter->SetInputData(mesh_data); + fill_holes_filter->SetHoleSize(hole_size_); + fill_holes_filter->Update(); + + vtkSmartPointer normals_rectifier = vtkSmartPointer::New(); + normals_rectifier->SetInputData(fill_holes_filter->GetOutput()); + normals_rectifier->ConsistencyOn(); + normals_rectifier->SplittingOff(); + normals_rectifier->Update(); + + pcl::PolygonMesh mesh_out; + pcl::VTKUtils::vtk2mesh(normals_rectifier->GetOutput(), mesh_out); + return { mesh_out }; +} + +} // namespace noether diff --git a/noether_tpp/src/mesh_modifiers/test/check_pcl_nurbs.cpp b/noether_tpp/src/mesh_modifiers/test/check_pcl_nurbs.cpp new file mode 100644 index 00000000..4cf44ef0 --- /dev/null +++ b/noether_tpp/src/mesh_modifiers/test/check_pcl_nurbs.cpp @@ -0,0 +1,31 @@ +/** + * @brief This file was designed to be used with CMake CheckCXXSourceCompiles to see if PCL was compiled with OpenNurbs + * support + * @author Matthew Powelson + * @file check_pcl_nurbs.cpp + * @date June 18, 2020 + * @copyright Copyright (c) 2020, Southwest Research Institute + * + * @par License + * Software License Agreement (Apache License) + * @par + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * http://www.apache.org/licenses/LICENSE-2.0 + * @par + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#include +#include +#include + +int main(int argc, char** argv) +{ + pcl::on_nurbs::FittingSurface::Parameter surface_params; + pcl::on_nurbs::FittingCurve2dAPDM::FitParameter boundary_curve_params; +} diff --git a/noether_tpp/src/mesh_modifiers/windowed_sinc_smoothing.cpp b/noether_tpp/src/mesh_modifiers/windowed_sinc_smoothing.cpp new file mode 100644 index 00000000..e8e55e1e --- /dev/null +++ b/noether_tpp/src/mesh_modifiers/windowed_sinc_smoothing.cpp @@ -0,0 +1,40 @@ +/* + * window_sinc_smoothing.cpp + * + * Created on: Dec 6, 2019 + * Author: jrgnicho + */ + +#include + +#include +#include + +namespace noether +{ +std::vector WindowedSincSmoothing::modify(const pcl::PolygonMesh& mesh_in) const +{ + vtkSmartPointer mesh_data = vtkSmartPointer::New(); + pcl::VTKUtils::mesh2vtk(mesh_in, mesh_data); + + mesh_data->BuildCells(); + mesh_data->BuildLinks(); + + vtkSmartPointer smoother = vtkSmartPointer::New(); + smoother->SetInputData(mesh_data); + smoother->SetNumberOfIterations(config_.num_iter); + smoother->SetFeatureAngle(config_.feature_angle); + smoother->SetEdgeAngle(config_.edge_angle); + smoother->SetPassBand(config_.pass_band); + smoother->SetBoundarySmoothing(config_.enable_boundary_smoothing); + smoother->SetFeatureEdgeSmoothing(config_.enable_feature_edge_smoothing); + smoother->SetNonManifoldSmoothing(config_.enable_non_manifold_smoothing); + smoother->SetNormalizeCoordinates(config_.enable_normalize_coordinates); + smoother->Update(); + + pcl::PolygonMesh mesh_out; + pcl::VTKUtils::vtk2mesh(smoother->GetOutput(), mesh_out); + return { mesh_out }; +} + +} // namespace noether