Noether  0.0.0
Loading...
Searching...
No Matches
noether::CylinderProjectionModifier Class Reference

Mesh modifier that fits a specifiable number of cylinders to the input mesh and projects the inlier vertices onto the fitted cylinder models. More...

Detailed Description

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 into a new submesh and then projected onto the fitted cylinder model. 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 <cylinder_projection_modifier.h>

Inheritance diagram for noether::CylinderProjectionModifier:

Public Member Functions

 CylinderProjectionModifier (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.
 
std::vector< pcl::PolygonMesh > modify (const pcl::PolygonMesh &mesh) const override
 

Protected Attributes

float min_radius_
 
float max_radius_
 
float distance_threshold_
 
Eigen::Vector3f axis_
 
float axis_threshold_
 
float normal_distance_weight_
 
unsigned min_vertices_
 
int max_cylinders_
 
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 >
 

Constructor & Destructor Documentation

◆ CylinderProjectionModifier()

noether::CylinderProjectionModifier::CylinderProjectionModifier ( 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 
)
Parameters
min_radiusMinimum required cylinder radius (m)
max_radiusMaximum required cylinder radius (m)
distance_thresholdMaximum distance (m) a point can be from a model of a cylinder to be considered an inlier
axisPredicted cylinder axis
axis_thresholdMaximum angle (radians) by which the axis of a detected cylinder can differ from the axis of the defined model cylinder
normal_distance_weightDistance weighting amount given to normals (vs point positions) when comparing to the cylinder model (value from [0, 1])
min_verticesMinimum number of vertices that a cluster (identfied as a cylinder) must have
max_cylindersMaximum number of cylinders to detect
max_iterationsMaximum number of RANSAC iterations to perform

Member Function Documentation

◆ modify()

std::vector< pcl::PolygonMesh > noether::CylinderProjectionModifier::modify ( const pcl::PolygonMesh &  mesh) const
overridevirtual

Reimplemented from noether::MeshModifier.