-
Notifications
You must be signed in to change notification settings - Fork 49
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Ported noether_filtering mesh filters to noether_tpp mesh modifiers
- Loading branch information
Showing
12 changed files
with
612 additions
and
2 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
79 changes: 79 additions & 0 deletions
79
noether_tpp/include/noether_tpp/mesh_modifiers/bspline_reconstruction_modifier.h
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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 |
40 changes: 40 additions & 0 deletions
40
noether_tpp/include/noether_tpp/mesh_modifiers/clean_data_modifier.h
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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 |
44 changes: 44 additions & 0 deletions
44
noether_tpp/include/noether_tpp/mesh_modifiers/euclidean_clustering_modifier.h
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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 |
41 changes: 41 additions & 0 deletions
41
noether_tpp/include/noether_tpp/mesh_modifiers/fill_holes_modifier.h
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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 |
48 changes: 48 additions & 0 deletions
48
noether_tpp/include/noether_tpp/mesh_modifiers/windowed_sinc_smoothing_modifier.h
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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 |
Oops, something went wrong.