Public Member Functions | Static Public Member Functions | Public Attributes | Protected Member Functions | Private Member Functions | Private Attributes
pcl::on_nurbs::FittingSphere Class Reference

Fitting a cylindric (dim 0 clamped, dim 1 periodic) B-Spline surface to 3D point-clouds using point-distance-minimization Based on paper: TODO. More...

#include <fitting_sphere_pdm.h>

List of all members.

Public Member Functions

void assemble (double smoothness=0.000001f)
 Assemble the system of equations for fitting.
 FittingSphere (int order, NurbsDataSurface *data)
 Constructor initializing B-Spline surface using initNurbsPCACylinder(...).
 FittingSphere (NurbsDataSurface *data, const ON_NurbsSurface &ns)
 Constructor initializing with the B-Spline surface given in argument 2.
void setInvMapParams (int in_max_steps, double invMapInt_accuracy)
 Set parameters for inverse mapping.
void setQuiet (bool val)
void solve (double damp=1.0)
 Solve system of equations using Eigen or UmfPack (can be defined in on_nurbs.cmake), and updates B-Spline surface if a solution can be obtained.
void updateSurf (double damp)
 Update surface according to the current system of equations.

Static Public Member Functions

static Eigen::Vector2d findClosestElementMidPoint (const ON_NurbsSurface &nurbs, const Eigen::Vector3d &pt)
 Given a point pt, the function finds the closest midpoint of the elements of the surface.
static std::vector< double > getElementVector (const ON_NurbsSurface &nurbs, int dim)
 Get the elements of a cylindric B-Spline surface.
static ON_NurbsSurface initNurbsSphere (int order, NurbsDataSurface *data, Eigen::Vector3d pole_axis=Eigen::Vector3d(0.0, 0.0, 1.0))
 Initializing a cylindric B-Spline surface using principal-component-analysis and eigen values.
static Eigen::Vector2d inverseMapping (const ON_NurbsSurface &nurbs, const Eigen::Vector3d &pt, const Eigen::Vector2d &hint, double &error, Eigen::Vector3d &p, Eigen::Vector3d &tu, Eigen::Vector3d &tv, int maxSteps=100, double accuracy=1e-6, bool quiet=true)
 Inverse mapping / point inversion: Given a point pt, this function finds the closest point on the B-Spline surface using Newtons method and point-distance (L2-, Euclidean norm).

Public Attributes

NurbsDataSurfacem_data
ON_NurbsSurface m_nurbs
ON_TextLog m_out

Protected Member Functions

void addCageBoundaryRegularisation (double weight, int side, unsigned &row)
 Add minimization constraint: corner smoothness by control point regularisation.
void addCageInteriorRegularisation (double weight, unsigned &row)
 Add minimization constraint: interior smoothness by control point regularisation.
void addPointConstraint (const Eigen::Vector2d &params, const Eigen::Vector3d &point, double weight, unsigned &row)
 Add minimization constraint: point-to-surface distance (point-distance-minimization).
void assembleInterior (double wInt, unsigned &row)
 Assemble point-to-surface constraints for interior points.
void init ()
 Initialisation of member variables.

Private Member Functions

int gl2gc (int A)
int gl2gr (int A)
int grc2gl (int I, int J)
int lrc2gl (int E, int F, int i, int j)

Private Attributes

double in_accuracy
int in_max_steps
bool m_quiet
NurbsSolve m_solver

Detailed Description

Fitting a cylindric (dim 0 clamped, dim 1 periodic) B-Spline surface to 3D point-clouds using point-distance-minimization Based on paper: TODO.

Author:
Thomas Mörwald

Definition at line 55 of file fitting_sphere_pdm.h.


Constructor & Destructor Documentation

FittingSphere::FittingSphere ( int  order,
NurbsDataSurface data 
)

Constructor initializing B-Spline surface using initNurbsPCACylinder(...).

Parameters:
[in]orderthe polynomial order of the B-Spline surface.
[in]datapointer to the 2D point-cloud data to be fit.
[in]zvector defining front face of surface.

Definition at line 45 of file fitting_sphere_pdm.cpp.

Constructor initializing with the B-Spline surface given in argument 2.

Parameters:
[in]datapointer to the 3D point-cloud data to be fit.
[in]nsB-Spline surface used for fitting.

Definition at line 58 of file fitting_sphere_pdm.cpp.


Member Function Documentation

void FittingSphere::addCageBoundaryRegularisation ( double  weight,
int  side,
unsigned &  row 
) [protected]

Add minimization constraint: corner smoothness by control point regularisation.

Definition at line 401 of file fitting_sphere_pdm.cpp.

void FittingSphere::addCageInteriorRegularisation ( double  weight,
unsigned &  row 
) [protected]

Add minimization constraint: interior smoothness by control point regularisation.

Definition at line 376 of file fitting_sphere_pdm.cpp.

void FittingSphere::addPointConstraint ( const Eigen::Vector2d &  params,
const Eigen::Vector3d &  point,
double  weight,
unsigned &  row 
) [protected]

Add minimization constraint: point-to-surface distance (point-distance-minimization).

Definition at line 341 of file fitting_sphere_pdm.cpp.

void FittingSphere::assemble ( double  smoothness = 0.000001f)

Assemble the system of equations for fitting.

  • for large point-clouds this is time consuming.
  • should be done once before refinement to initialize the starting points for point inversion.

Definition at line 78 of file fitting_sphere_pdm.cpp.

void FittingSphere::assembleInterior ( double  wInt,
unsigned &  row 
) [protected]

Assemble point-to-surface constraints for interior points.

Definition at line 300 of file fitting_sphere_pdm.cpp.

Vector2d FittingSphere::findClosestElementMidPoint ( const ON_NurbsSurface nurbs,
const Eigen::Vector3d &  pt 
) [static]

Given a point pt, the function finds the closest midpoint of the elements of the surface.

Parameters:
[in]nurbsthe B-Spline surface.
[in]ptthe point to which the closest midpoint of the elements will be computed. return closest midpoint in parametric domain.

Definition at line 509 of file fitting_sphere_pdm.cpp.

std::vector< double > FittingSphere::getElementVector ( const ON_NurbsSurface nurbs,
int  dim 
) [static]

Get the elements of a cylindric B-Spline surface.

Definition at line 242 of file fitting_sphere_pdm.cpp.

int pcl::on_nurbs::FittingSphere::gl2gc ( int  A) [inline, private]

Definition at line 184 of file fitting_sphere_pdm.h.

int pcl::on_nurbs::FittingSphere::gl2gr ( int  A) [inline, private]

Definition at line 179 of file fitting_sphere_pdm.h.

int pcl::on_nurbs::FittingSphere::grc2gl ( int  I,
int  J 
) [inline, private]

Definition at line 167 of file fitting_sphere_pdm.h.

void FittingSphere::init ( ) [protected]

Initialisation of member variables.

Definition at line 69 of file fitting_sphere_pdm.cpp.

ON_NurbsSurface FittingSphere::initNurbsSphere ( int  order,
NurbsDataSurface data,
Eigen::Vector3d  pole_axis = Eigen::Vector3d (0.0, 0.0, 1.0) 
) [static]

Initializing a cylindric B-Spline surface using principal-component-analysis and eigen values.

Definition at line 164 of file fitting_sphere_pdm.cpp.

Vector2d FittingSphere::inverseMapping ( const ON_NurbsSurface nurbs,
const Eigen::Vector3d &  pt,
const Eigen::Vector2d &  hint,
double &  error,
Eigen::Vector3d &  p,
Eigen::Vector3d &  tu,
Eigen::Vector3d &  tv,
int  maxSteps = 100,
double  accuracy = 1e-6,
bool  quiet = true 
) [static]

Inverse mapping / point inversion: Given a point pt, this function finds the closest point on the B-Spline surface using Newtons method and point-distance (L2-, Euclidean norm).

Parameters:
[in]nurbsthe B-Spline surface.
[in]ptthe point to which the closest point on the surface will be computed.
[in]hintthe starting point in parametric domain (warning: may lead to convergence at local minima).
[in]errorthe distance between the point pt and p after convergence.
[in]pclosest boundary point on surface.
[in]tuthe tangent vector at point p in u-direction.
[in]tvthe tangent vector at point p in v-direction.
[in]maxStepsmaximum number of iterations.
[in]accuracyconvergence criteria: if error is lower than accuracy the function returns
Returns:
closest point on surface in parametric domain.

Definition at line 430 of file fitting_sphere_pdm.cpp.

int pcl::on_nurbs::FittingSphere::lrc2gl ( int  E,
int  F,
int  i,
int  j 
) [inline, private]

Definition at line 174 of file fitting_sphere_pdm.h.

void FittingSphere::setInvMapParams ( int  in_max_steps,
double  invMapInt_accuracy 
)

Set parameters for inverse mapping.

Parameters:
[in]in_max_stepsmaximum number of iterations.
[in]in_accuracystops iteration if specified accuracy is reached.

Definition at line 157 of file fitting_sphere_pdm.cpp.

void pcl::on_nurbs::FittingSphere::setQuiet ( bool  val) [inline]

Definition at line 97 of file fitting_sphere_pdm.h.

void FittingSphere::solve ( double  damp = 1.0)

Solve system of equations using Eigen or UmfPack (can be defined in on_nurbs.cmake), and updates B-Spline surface if a solution can be obtained.

Definition at line 114 of file fitting_sphere_pdm.cpp.

void FittingSphere::updateSurf ( double  damp)

Update surface according to the current system of equations.

Parameters:
[in]dampdamping factor from one iteration to the other.

Definition at line 121 of file fitting_sphere_pdm.cpp.


Member Data Documentation

Definition at line 163 of file fitting_sphere_pdm.h.

Definition at line 162 of file fitting_sphere_pdm.h.

Definition at line 61 of file fitting_sphere_pdm.h.

Definition at line 60 of file fitting_sphere_pdm.h.

Definition at line 59 of file fitting_sphere_pdm.h.

Definition at line 160 of file fitting_sphere_pdm.h.

Definition at line 159 of file fitting_sphere_pdm.h.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:44:32