Public Member Functions | Protected Member Functions
pcl::on_nurbs::FittingCurve2dATDM Class Reference

Fitting a 2D B-Spline curve to 2D point-clouds using asymmetric-tangent-distance-minimization Based on paper: TODO. More...

#include <fitting_curve_2d_atdm.h>

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

List of all members.

Public Member Functions

void assemble (const FittingCurve2dAPDM::Parameter &parameter)
 Assemble the system of equations for fitting.
 FittingCurve2dATDM (int order, NurbsDataCurve2d *data)
 Constructor initializing B-Spline curve using initNurbsCurve2D(...).
 FittingCurve2dATDM (NurbsDataCurve2d *data, const ON_NurbsCurve &nc)
 Constructor initializing with the B-Spline curve given in argument 2.
virtual double solve (double damp=1.0)
 Solve system of equations using Eigen or UmfPack (can be defined in on_nurbs.cmake), and updates B-Spline curve if a solution can be obtained.
virtual double updateCurve (double damp)
 Update curve according to the current system of equations.

Protected Member Functions

virtual void addCageRegularisation (double weight, unsigned &row, const std::vector< double > &elements, double wConcav=0.0)
 Add minimization constraint: smoothness by control point regularisation.
virtual void addPointConstraint (const double &param, const Eigen::Vector2d &point, const Eigen::Vector2d &normal, double weight, unsigned &row)
 Add minimization constraint: point-to-surface distance (tangent-distance-minimization).
virtual void assembleClosestPoints (const std::vector< double > &elements, double weight, double sigma2, unsigned &row)
 Assemble closest points constraints. At each midpoint of the curve elements the closest data points are computed and point-to-surface constraints are added.
virtual void assembleClosestPoints (int res, double weight, unsigned &row)
 Assemble closest points constraints. Samples curve and searches for close data points, and adds point-to-surface constraint.
virtual void assembleInterior (double wInt, double sigma2, double rScale, unsigned &row)
 Assemble point-to-surface constraints.

Detailed Description

Fitting a 2D B-Spline curve to 2D point-clouds using asymmetric-tangent-distance-minimization Based on paper: TODO.

Author:
Thomas Mörwald

Definition at line 55 of file fitting_curve_2d_atdm.h.


Constructor & Destructor Documentation

Constructor initializing B-Spline curve using initNurbsCurve2D(...).

Parameters:
[in]orderthe polynomial order of the B-Spline curve.
[in]datapointer to the 2D point-cloud data to be fit.

Definition at line 44 of file fitting_curve_2d_atdm.cpp.

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

Parameters:
[in]datapointer to the 2D point-cloud data to be fit.
[in]ncB-Spline curve used for fitting.

Definition at line 49 of file fitting_curve_2d_atdm.cpp.


Member Function Documentation

void FittingCurve2dATDM::addCageRegularisation ( double  weight,
unsigned &  row,
const std::vector< double > &  elements,
double  wConcav = 0.0 
) [protected, virtual]

Add minimization constraint: smoothness by control point regularisation.

Reimplemented from pcl::on_nurbs::FittingCurve2dAPDM.

Definition at line 173 of file fitting_curve_2d_atdm.cpp.

void FittingCurve2dATDM::addPointConstraint ( const double &  param,
const Eigen::Vector2d &  point,
const Eigen::Vector2d &  normal,
double  weight,
unsigned &  row 
) [protected, virtual]

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

Definition at line 146 of file fitting_curve_2d_atdm.cpp.

void FittingCurve2dATDM::assemble ( const FittingCurve2dAPDM::Parameter 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.

Reimplemented from pcl::on_nurbs::FittingCurve2dAPDM.

Definition at line 55 of file fitting_curve_2d_atdm.cpp.

void FittingCurve2dATDM::assembleClosestPoints ( const std::vector< double > &  elements,
double  weight,
double  sigma2,
unsigned &  row 
) [protected, virtual]

Assemble closest points constraints. At each midpoint of the curve elements the closest data points are computed and point-to-surface constraints are added.

Definition at line 313 of file fitting_curve_2d_atdm.cpp.

void FittingCurve2dATDM::assembleClosestPoints ( int  res,
double  weight,
unsigned &  row 
) [protected, virtual]

Assemble closest points constraints. Samples curve and searches for close data points, and adds point-to-surface constraint.

Definition at line 377 of file fitting_curve_2d_atdm.cpp.

void FittingCurve2dATDM::assembleInterior ( double  wInt,
double  sigma2,
double  rScale,
unsigned &  row 
) [protected, virtual]

Assemble point-to-surface constraints.

Reimplemented from pcl::on_nurbs::FittingCurve2dAPDM.

Definition at line 235 of file fitting_curve_2d_atdm.cpp.

double FittingCurve2dATDM::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 curve if a solution can be obtained.

Reimplemented from pcl::on_nurbs::FittingCurve2dAPDM.

Definition at line 98 of file fitting_curve_2d_atdm.cpp.

double FittingCurve2dATDM::updateCurve ( double  damp) [virtual]

Update curve according to the current system of equations.

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

Reimplemented from pcl::on_nurbs::FittingCurve2dAPDM.

Definition at line 109 of file fitting_curve_2d_atdm.cpp.


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


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