Skip to content

Commit

Permalink
Ported noether_filtering mesh filters to noether_tpp mesh modifiers
Browse files Browse the repository at this point in the history
  • Loading branch information
marip8 committed Jan 4, 2024
1 parent 140cfb3 commit 8973047
Show file tree
Hide file tree
Showing 12 changed files with 612 additions and 2 deletions.
23 changes: 21 additions & 2 deletions noether_tpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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))
Expand All @@ -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
Expand All @@ -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
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include>")
Expand All @@ -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})
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
/**
* @author Jorge Nicho <jrgnichodevel@gmail.com>
* @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 <noether_tpp/core/mesh_modifier.h>
#include <pcl/surface/on_nurbs/fitting_surface_tdm.h>
#include <pcl/surface/on_nurbs/fitting_curve_2d_asdm.h>

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<pcl::PolygonMesh> modify(const pcl::PolygonMesh& mesh) const override;

protected:
Parameters parameters_;
};

} // namespace noether
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
/**
* @author Jorge Nicho <jrgnichodevel@gmail.com>
* @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 <noether_tpp/core/mesh_modifier.h>

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<pcl::PolygonMesh> modify(const pcl::PolygonMesh& mesh) const override;
};

} // namespace noether
Original file line number Diff line number Diff line change
@@ -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 <noether_tpp/core/mesh_modifier.h>

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<pcl::PolygonMesh> modify(const pcl::PolygonMesh& mesh_in) const override;

protected:
Parameters parameters_;
};

} // namespace noether
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
/**
* @author Jorge Nicho <jrgnichodevel@gmail.com>
* @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 <noether_tpp/core/mesh_modifier.h>

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<pcl::PolygonMesh> modify(const pcl::PolygonMesh& mesh) const override;

protected:
double hole_size_ = 1.0;
};

} // namespace noether
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
/*
* window_sinc_smoothing.h
*
* Created on: Dec 6, 2019
* Author: jrgnicho
*/

#pragma once

#include <noether_tpp/core/mesh_modifier.h>

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<pcl::PolygonMesh> modify(const pcl::PolygonMesh& mesh) const override;

protected:
Config config_;
};

} // namespace noether
Loading

0 comments on commit 8973047

Please sign in to comment.