Classes | Public Member Functions | Static Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes
pcl::on_nurbs::FittingSurface Class Reference

Fitting a B-Spline surface to 3D point-clouds using point-distance-minimization Based on paper: TODO. More...

#include <fitting_surface_pdm.h>

Inheritance diagram for pcl::on_nurbs::FittingSurface:
Inheritance graph
[legend]

List of all members.

Classes

class  myvec
struct  Parameter
 Parameters for fitting. More...

Public Member Functions

virtual void assemble (Parameter param=Parameter())
 Assemble the system of equations for fitting.
 FittingSurface (NurbsDataSurface *data, const ON_NurbsSurface &ns)
 Constructor initializing with the B-Spline surface given in argument 2.
 FittingSurface (int order, NurbsDataSurface *data, Eigen::Vector3d z=Eigen::Vector3d(0.0, 0.0, 1.0))
 Constructor initializing B-Spline surface using initNurbsPCA(...).
void refine (int dim)
 Refines surface by inserting a knot in the middle of each element.
void setInvMapParams (unsigned in_max_steps, double in_accuracy)
 Set parameters for inverse mapping.
void setQuiet (bool val)
 Enable/Disable debug outputs in console.
virtual 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.
virtual 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 B-Spline surface.
static ON_NurbsSurface initNurbs4Corners (int order, ON_3dPoint ll, ON_3dPoint lr, ON_3dPoint ur, ON_3dPoint ul)
 Initializing a B-Spline surface using 4 corners.
static ON_NurbsSurface initNurbsPCA (int order, NurbsDataSurface *data, Eigen::Vector3d z=Eigen::Vector3d(0.0, 0.0, 1.0))
 Initializing a B-Spline surface using principal-component-analysis and eigen values.
static ON_NurbsSurface initNurbsPCABoundingBox (int order, NurbsDataSurface *data, Eigen::Vector3d z=Eigen::Vector3d(0.0, 0.0, 1.0))
 Initializing a B-Spline surface using principal-component-analysis and bounding box of points.
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).
static Eigen::Vector2d inverseMapping (const ON_NurbsSurface &nurbs, const Eigen::Vector3d &pt, const Eigen::Vector2d &hint, Eigen::Vector3d &p, int maxSteps, double accuracy, bool quiet)
static Eigen::Vector2d inverseMappingBoundary (const ON_NurbsSurface &nurbs, const Eigen::Vector3d &pt, 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 boundary of the B-Spline surface using Newtons method and point-distance (L2-, Euclidean norm).
static Eigen::Vector2d inverseMappingBoundary (const ON_NurbsSurface &nurbs, const Eigen::Vector3d &pt, int side, double 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 one side of the boundary of the B-Spline surface using Newtons method and point-distance (L2-, Euclidean norm).
static void refine (ON_NurbsSurface &nurbs, int dim)

Public Attributes

NurbsDataSurfacem_data
ON_NurbsSurface m_nurbs

Protected Member Functions

virtual void addBoundaryRegularisation (int order, int resU, int resV, double weight, unsigned &row)
 Add minimization constraint: boundary smoothness by derivatives regularisation.
virtual void addCageBoundaryRegularisation (double weight, int side, unsigned &row)
 Add minimization constraint: boundary smoothness by control point regularisation.
virtual void addCageCornerRegularisation (double weight, unsigned &row)
 Add minimization constraint: corner smoothness by control point regularisation.
virtual void addCageInteriorRegularisation (double weight, unsigned &row)
 Add minimization constraint: interior smoothness by control point regularisation.
virtual void addInteriorRegularisation (int order, int resU, int resV, double weight, unsigned &row)
 Add minimization constraint: interior smoothness by derivatives regularisation.
virtual void addPointConstraint (const Eigen::Vector2d &params, const Eigen::Vector3d &point, double weight, unsigned &row)
 Add minimization constraint: point-to-surface distance (point-distance-minimization).
virtual void assembleBoundary (double wBnd, unsigned &row)
 Assemble point-to-surface constraints for boundary points.
virtual void assembleInterior (double wInt, unsigned &row)
 Assemble point-to-surface constraints for interior points.
int gl2gc (int A)
int gl2gr (int A)
int grc2gl (int I, int J)
void init ()
 Initialisation of member variables.
int lrc2gl (int E, int F, int i, int j)

Protected Attributes

double in_accuracy
int in_max_steps
std::vector< double > m_elementsU
std::vector< double > m_elementsV
double m_maxU
double m_maxV
double m_minU
double m_minV
bool m_quiet
NurbsSolve m_solver

Detailed Description

Fitting a 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_surface_pdm.h.


Constructor & Destructor Documentation

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 73 of file fitting_surface_pdm.cpp.

FittingSurface::FittingSurface ( int  order,
NurbsDataSurface data,
Eigen::Vector3d  z = Eigen::Vector3d (0.0, 0.0, 1.0) 
)

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

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 60 of file fitting_surface_pdm.cpp.


Member Function Documentation

void FittingSurface::addBoundaryRegularisation ( int  order,
int  resU,
int  resV,
double  weight,
unsigned &  row 
) [protected, virtual]

Add minimization constraint: boundary smoothness by derivatives regularisation.

Reimplemented in pcl::on_nurbs::FittingSurfaceTDM.

Definition at line 797 of file fitting_surface_pdm.cpp.

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

Add minimization constraint: boundary smoothness by control point regularisation.

Reimplemented in pcl::on_nurbs::FittingSurfaceTDM.

Definition at line 632 of file fitting_surface_pdm.cpp.

void FittingSurface::addCageCornerRegularisation ( double  weight,
unsigned &  row 
) [protected, virtual]

Add minimization constraint: corner smoothness by control point regularisation.

Reimplemented in pcl::on_nurbs::FittingSurfaceTDM.

Definition at line 678 of file fitting_surface_pdm.cpp.

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

Add minimization constraint: interior smoothness by control point regularisation.

Reimplemented in pcl::on_nurbs::FittingSurfaceTDM.

Definition at line 609 of file fitting_surface_pdm.cpp.

void FittingSurface::addInteriorRegularisation ( int  order,
int  resU,
int  resV,
double  weight,
unsigned &  row 
) [protected, virtual]

Add minimization constraint: interior smoothness by derivatives regularisation.

Reimplemented in pcl::on_nurbs::FittingSurfaceTDM.

Definition at line 743 of file fitting_surface_pdm.cpp.

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

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

Definition at line 529 of file fitting_surface_pdm.cpp.

void FittingSurface::assemble ( Parameter  param = Parameter ()) [virtual]

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 117 of file fitting_surface_pdm.cpp.

void FittingSurface::assembleBoundary ( double  wBnd,
unsigned &  row 
) [protected, virtual]

Assemble point-to-surface constraints for boundary points.

Definition at line 317 of file fitting_surface_pdm.cpp.

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

Assemble point-to-surface constraints for interior points.

Definition at line 273 of file fitting_surface_pdm.cpp.

Vector2d FittingSurface::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 1115 of file fitting_surface_pdm.cpp.

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

Get the elements of a B-Spline surface.

Definition at line 244 of file fitting_surface_pdm.cpp.

int pcl::on_nurbs::FittingSurface::gl2gc ( int  A) [inline, protected]

Definition at line 307 of file fitting_surface_pdm.h.

int pcl::on_nurbs::FittingSurface::gl2gr ( int  A) [inline, protected]

Definition at line 302 of file fitting_surface_pdm.h.

int pcl::on_nurbs::FittingSurface::grc2gl ( int  I,
int  J 
) [inline, protected]

Definition at line 292 of file fitting_surface_pdm.h.

void FittingSurface::init ( ) [protected]

Initialisation of member variables.

Definition at line 189 of file fitting_surface_pdm.cpp.

Initializing a B-Spline surface using 4 corners.

Definition at line 358 of file fitting_surface_pdm.cpp.

ON_NurbsSurface FittingSurface::initNurbsPCA ( int  order,
NurbsDataSurface data,
Eigen::Vector3d  z = Eigen::Vector3d (0.0, 0.0, 1.0) 
) [static]

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

Definition at line 398 of file fitting_surface_pdm.cpp.

ON_NurbsSurface FittingSurface::initNurbsPCABoundingBox ( int  order,
NurbsDataSurface data,
Eigen::Vector3d  z = Eigen::Vector3d (0.0, 0.0, 1.0) 
) [static]

Initializing a B-Spline surface using principal-component-analysis and bounding box of points.

Definition at line 446 of file fitting_surface_pdm.cpp.

static Eigen::Vector2d pcl::on_nurbs::FittingSurface::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 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.
static Eigen::Vector2d pcl::on_nurbs::FittingSurface::inverseMapping ( const ON_NurbsSurface nurbs,
const Eigen::Vector3d &  pt,
const Eigen::Vector2d &  hint,
Eigen::Vector3d &  p,
int  maxSteps,
double  accuracy,
bool  quiet 
) [static]
static Eigen::Vector2d pcl::on_nurbs::FittingSurface::inverseMappingBoundary ( const ON_NurbsSurface nurbs,
const Eigen::Vector3d &  pt,
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 boundary of 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]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.
static Eigen::Vector2d pcl::on_nurbs::FittingSurface::inverseMappingBoundary ( const ON_NurbsSurface nurbs,
const Eigen::Vector3d &  pt,
int  side,
double  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 one side of the boundary of 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]sidethe side of the boundary (NORTH, SOUTH, EAST, WEST)
[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.
int pcl::on_nurbs::FittingSurface::lrc2gl ( int  E,
int  F,
int  i,
int  j 
) [inline, protected]

Definition at line 297 of file fitting_surface_pdm.h.

void FittingSurface::refine ( int  dim)

Refines surface by inserting a knot in the middle of each element.

Parameters:
[in]dimdimension of refinement (0,1)

Definition at line 84 of file fitting_surface_pdm.cpp.

void FittingSurface::refine ( ON_NurbsSurface nurbs,
int  dim 
) [static]

Definition at line 104 of file fitting_surface_pdm.cpp.

void FittingSurface::setInvMapParams ( unsigned  in_max_steps,
double  in_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 237 of file fitting_surface_pdm.cpp.

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

Enable/Disable debug outputs in console.

Definition at line 230 of file fitting_surface_pdm.h.

void FittingSurface::solve ( double  damp = 1.0) [virtual]

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.

Reimplemented in pcl::on_nurbs::FittingSurfaceTDM.

Definition at line 205 of file fitting_surface_pdm.cpp.

void FittingSurface::updateSurf ( double  damp) [virtual]

Update surface according to the current system of equations.

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

Reimplemented in pcl::on_nurbs::FittingSurfaceTDM.

Definition at line 212 of file fitting_surface_pdm.cpp.


Member Data Documentation

Definition at line 288 of file fitting_surface_pdm.h.

Definition at line 287 of file fitting_surface_pdm.h.

Definition at line 59 of file fitting_surface_pdm.h.

std::vector<double> pcl::on_nurbs::FittingSurface::m_elementsU [protected]

Definition at line 279 of file fitting_surface_pdm.h.

std::vector<double> pcl::on_nurbs::FittingSurface::m_elementsV [protected]

Definition at line 280 of file fitting_surface_pdm.h.

Definition at line 284 of file fitting_surface_pdm.h.

Definition at line 285 of file fitting_surface_pdm.h.

Definition at line 282 of file fitting_surface_pdm.h.

Definition at line 283 of file fitting_surface_pdm.h.

Definition at line 58 of file fitting_surface_pdm.h.

Definition at line 277 of file fitting_surface_pdm.h.

Definition at line 275 of file fitting_surface_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