|
Noether
0.0.0
|
MeshModifier that fits a specifiable number of cylinders to the input mesh and returns the fitted primitive models. More...
This modifier uses RANSAC to sequentially fit cylinder models to the input mesh. When a valid cylinder model is identified, the inlier vertices are removed from the input mesh and the fitted primitive model is returned. New cylinder models are then fitted to the remainder of vertices in the input mesh until either 1) the maximum number of cylinder models have been fitted 2) too few inliers remain in the input mesh, or 3) no more valid cylinders can be fit to the input mesh.
#include <ransac_cylinder_fit_modifier.h>

Public Member Functions | |
| RansacCylinderFitMeshModifier (float min_radius, float max_radius, float distance_threshold, const Eigen::Vector3f &axis=Eigen::Vector3f::UnitZ(), float axis_threshold=10.0 *M_PI/180.0, float normal_distance_weight=0.1, unsigned min_vertices=1, int max_cylinders=-1, unsigned max_iterations=100, unsigned resolution=20, bool include_caps=false, bool uniform_triangles=true) | |
| Constructor. | |
Public Member Functions inherited from noether::RansacCylinderProjectionMeshModifier | |
| RansacCylinderProjectionMeshModifier (float min_radius, float max_radius, float distance_threshold, const Eigen::Vector3f &axis=Eigen::Vector3f::UnitZ(), float axis_threshold=10.0 *M_PI/180.0, float normal_distance_weight=0.1, unsigned min_vertices=1, int max_cylinders=-1, unsigned max_iterations=100) | |
| Constructor. | |
Public Member Functions inherited from noether::RansacPrimitiveFitMeshModifier | |
| RansacPrimitiveFitMeshModifier (float distance_threshold, unsigned min_vertices=1, int max_primitives=-1, unsigned max_iterations=100) | |
| Constructor. | |
| std::vector< pcl::PolygonMesh > | modify (const pcl::PolygonMesh &mesh) const override |
Protected Member Functions | |
| pcl::PolygonMesh | createSubMesh (const pcl::PolygonMesh &mesh, std::shared_ptr< const pcl::RandomSampleConsensus< pcl::PointXYZ > > ransac) const override |
| Creates a sub-mesh from the results of the model primitive fitting. | |
Protected Member Functions inherited from noether::RansacCylinderProjectionMeshModifier | |
| std::shared_ptr< pcl::SampleConsensusModel< pcl::PointXYZ > > | createModel (const pcl::PolygonMesh &mesh) const override |
| Creates a sample consensus model for the primitive. | |
| pcl::PolygonMesh | createSubMesh (const pcl::PolygonMesh &mesh, std::shared_ptr< const pcl::RandomSampleConsensus< pcl::PointXYZ > > ransac) const override |
| Creates a sub-mesh from the results of the model primitive fitting. | |
Protected Attributes | |
| unsigned | resolution_ |
| bool | include_caps_ |
| bool | uniform_triangles_ |
Protected Attributes inherited from noether::RansacCylinderProjectionMeshModifier | |
| float | min_radius_ |
| float | max_radius_ |
| Eigen::Vector3f | axis_ |
| float | axis_threshold_ |
| float | normal_distance_weight_ |
Protected Attributes inherited from noether::RansacPrimitiveFitMeshModifier | |
| float | distance_threshold_ |
| unsigned | min_vertices_ |
| int | max_primitives_ |
| unsigned | max_iterations_ |
Additional Inherited Members | |
Public Types inherited from noether::MeshModifier | |
| using | Ptr = std::unique_ptr< MeshModifier > |
| using | ConstPtr = std::unique_ptr< const MeshModifier > |
| noether::RansacCylinderFitMeshModifier::RansacCylinderFitMeshModifier | ( | float | min_radius, |
| float | max_radius, | ||
| float | distance_threshold, | ||
| const Eigen::Vector3f & | axis = Eigen::Vector3f::UnitZ(), |
||
| float | axis_threshold = 10.0 * M_PI / 180.0, |
||
| float | normal_distance_weight = 0.1, |
||
| unsigned | min_vertices = 1, |
||
| int | max_cylinders = -1, |
||
| unsigned | max_iterations = 100, |
||
| unsigned | resolution = 20, |
||
| bool | include_caps = false, |
||
| bool | uniform_triangles = true |
||
| ) |
| min_radius | Minimum required cylinder radius (m) |
| max_radius | Maximum required cylinder radius (m) |
| distance_threshold | Maximum distance (m) a point can be from a model of a cylinder to be considered an inlier |
| axis | Predicted cylinder axis |
| axis_threshold | Maximum angle (radians) by which the axis of a detected cylinder can differ from the axis of the defined model cylinder |
| normal_distance_weight | Distance weighting amount given to normals (vs point positions) when comparing to the cylinder model (value from [0, 1]) |
| min_vertices | Minimum number of vertices that a cluster (identfied as a cylinder) must have |
| max_cylinders | Maximum number of cylinders to detect |
| max_iterations | Maximum number of RANSAC iterations to perform |
| resolution | Number of vertices around the perimeter of the cylinder primitive |
| include_caps | Flag to indicate whether the caps should be included on the fitted cylinder primitive(s) |
| uniform_triangles | Flag to indicate whether the cylinder body should be constructed of uniform shaped triangles (true) or a minimum set of triangles (false) |
|
overrideprotectedvirtual |
| mesh | Full input mesh |
| ransac | RANSAC model after successful completion of the model primitive fit |
Implements noether::RansacPrimitiveFitMeshModifier.