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

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

#include <fitting_curve_2d_pdm.h>

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

List of all members.

Classes

struct  FitParameter
struct  Parameter
 Parameters for fitting. More...

Public Member Functions

void addCPsOnClosestPointViolation (double max_error)
 Adds control points in the middle and of elements, if the ends or the middle of the element is farther than max_error to the closest data point.
virtual void assemble (const Parameter &parameter)
 Assemble the system of equations for fitting.
 FittingCurve2dPDM (int order, NurbsDataCurve2d *data)
 Constructor initializing B-Spline curve using initNurbsCurve2D(...).
 FittingCurve2dPDM (NurbsDataCurve2d *data, const ON_NurbsCurve &nc)
 Constructor initializing with the B-Spline curve given in argument 2.
void refine ()
 Refines curve by inserting a knot in the middle of each element.
void refine (double xi)
 Refines curve by inserting a knot in the middle of the element belonging to xi.
void setInverseParams (int max_steps=200, double accuracy=1e-6)
 Set parameters for inverse mapping.
void setQuiet (bool val)
 Enable/Disable debug outputs in console.
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.

Static Public Member Functions

static double findClosestElementMidPoint (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt)
 Given a point pt, the function finds the closest midpoint of the elements of the curve.
static double findClosestElementMidPoint (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt, double hint)
static int findElement (double xi, const std::vector< double > &elements)
 Find the element in which the parameter xi lies.
static std::vector< double > getElementVector (const ON_NurbsCurve &nurbs)
 Get the elements of a B-Spline curve.
static ON_NurbsCurve initCPsNurbsCurve2D (int order, const vector_vec2d &cps)
 Initialize a closed B-Spline curve given a list of control points.
static ON_NurbsCurve initNurbsCurve2D (int order, const vector_vec2d &data, int ncps=0, double radiusF=1.0)
 Initialize a closed B-Spline curve using the bounding circle of the point-cloud.
static double inverseMapping (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt, const double &hint, double &error, Eigen::Vector2d &p, Eigen::Vector2d &t, double rScale, 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 curve using Newtons method and point-distance (L2-, Euclidean norm).
static double inverseMappingO2 (const ON_NurbsCurve &nurbs, const Eigen::Vector2d &pt, double &error, Eigen::Vector2d &p, Eigen::Vector2d &t)
static ON_NurbsCurve removeCPsOnLine (const ON_NurbsCurve &nurbs, double min_curve_th=-0.9)
 Removes control points when it is collinear with its neighboring control points.
static void reverse (ON_NurbsCurve &curve)
 Reverse direction of rotation of a closed B-spline curve.

Public Attributes

NurbsDataCurve2dm_data
ON_NurbsCurve m_nurbs
ON_TextLog m_out

Protected Member Functions

virtual void addCageRegularisation (double weight, unsigned &row)
 Add minimization constraint: smoothness by control point regularisation.
virtual void addPointConstraint (const double &param, const Eigen::Vector2d &point, double weight, unsigned &row)
 Add minimization constraint: point-to-curve distance (point-distance-minimization).
virtual void assembleInterior (double wInt, double rScale, unsigned &row)
 Assemble point-to-curve constraints.

Protected Attributes

double in_accuracy
int in_max_steps
bool m_quiet
NurbsSolve m_solver

Detailed Description

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

Author:
Thomas Mörwald

Definition at line 56 of file fitting_curve_2d_pdm.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_pdm.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 59 of file fitting_curve_2d_pdm.cpp.


Member Function Documentation

void FittingCurve2dPDM::addCageRegularisation ( double  weight,
unsigned &  row 
) [protected, virtual]

Add minimization constraint: smoothness by control point regularisation.

Reimplemented in pcl::on_nurbs::FittingCurve2dTDM, and pcl::on_nurbs::FittingCurve2dSDM.

Definition at line 341 of file fitting_curve_2d_pdm.cpp.

Adds control points in the middle and of elements, if the ends or the middle of the element is farther than max_error to the closest data point.

Parameters:
[in]max_errordefining the max allowed distance between data points and curve.

Definition at line 202 of file fitting_curve_2d_pdm.cpp.

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

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

Definition at line 319 of file fitting_curve_2d_pdm.cpp.

void FittingCurve2dPDM::assemble ( const 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 in pcl::on_nurbs::FittingCurve2dTDM, and pcl::on_nurbs::FittingCurve2dSDM.

Definition at line 117 of file fitting_curve_2d_pdm.cpp.

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

Assemble point-to-curve constraints.

Reimplemented in pcl::on_nurbs::FittingCurve2dTDM, and pcl::on_nurbs::FittingCurve2dSDM.

Definition at line 515 of file fitting_curve_2d_pdm.cpp.

double FittingCurve2dPDM::findClosestElementMidPoint ( const ON_NurbsCurve nurbs,
const Eigen::Vector2d &  pt 
) [static]

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

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

Definition at line 839 of file fitting_curve_2d_pdm.cpp.

double FittingCurve2dPDM::findClosestElementMidPoint ( const ON_NurbsCurve nurbs,
const Eigen::Vector2d &  pt,
double  hint 
) [static]

Definition at line 790 of file fitting_curve_2d_pdm.cpp.

int FittingCurve2dPDM::findElement ( double  xi,
const std::vector< double > &  elements 
) [static]

Find the element in which the parameter xi lies.

Parameters:
[in]xivalue in parameter domain of the B-Spline curve.
[in]elementsthe vector of elements of the curve.
Returns:
index of the element with respect to elements.

Definition at line 72 of file fitting_curve_2d_pdm.cpp.

std::vector< double > FittingCurve2dPDM::getElementVector ( const ON_NurbsCurve nurbs) [static]

Get the elements of a B-Spline curve.

Definition at line 486 of file fitting_curve_2d_pdm.cpp.

ON_NurbsCurve FittingCurve2dPDM::initCPsNurbsCurve2D ( int  order,
const vector_vec2d cps 
) [static]

Initialize a closed B-Spline curve given a list of control points.

Parameters:
[in]orderpolynomial order of the curve.
[in]cpssequence of control points.
Returns:
B-Spline curve.

Definition at line 363 of file fitting_curve_2d_pdm.cpp.

ON_NurbsCurve FittingCurve2dPDM::initNurbsCurve2D ( int  order,
const vector_vec2d data,
int  ncps = 0,
double  radiusF = 1.0 
) [static]

Initialize a closed B-Spline curve using the bounding circle of the point-cloud.

Parameters:
[in]orderpolynomial order of the curve.
[in]data2D point-cloud
[in]ncpsnumber of control points
[in]radiusFradius factor multiplied to the radius of the bounding circle.
Returns:
B-Spline curve.

Definition at line 398 of file fitting_curve_2d_pdm.cpp.

double FittingCurve2dPDM::inverseMapping ( const ON_NurbsCurve nurbs,
const Eigen::Vector2d &  pt,
const double &  hint,
double &  error,
Eigen::Vector2d &  p,
Eigen::Vector2d &  t,
double  rScale,
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 curve using Newtons method and point-distance (L2-, Euclidean norm).

Parameters:
[in]nurbsthe B-Spline curve.
[in]ptthe point to which the closest point on the curve 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 curve.
[in]tthe tangent vector at point p.
[in]maxStepsmaximum number of iterations.
[in]accuracyconvergence criteria: if error is lower than accuracy the function returns
Returns:
closest point on curve in parametric domain.

Definition at line 557 of file fitting_curve_2d_pdm.cpp.

double FittingCurve2dPDM::inverseMappingO2 ( const ON_NurbsCurve nurbs,
const Eigen::Vector2d &  pt,
double &  error,
Eigen::Vector2d &  p,
Eigen::Vector2d &  t 
) [static]

Definition at line 634 of file fitting_curve_2d_pdm.cpp.

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

Definition at line 91 of file fitting_curve_2d_pdm.cpp.

void FittingCurve2dPDM::refine ( double  xi)

Refines curve by inserting a knot in the middle of the element belonging to xi.

Parameters:
[in]xiparameter defining the element to be refined.

Definition at line 105 of file fitting_curve_2d_pdm.cpp.

ON_NurbsCurve FittingCurve2dPDM::removeCPsOnLine ( const ON_NurbsCurve nurbs,
double  min_curve_th = -0.9 
) [static]

Removes control points when it is collinear with its neighboring control points.

Parameters:
[in]nurbsthe B-Spline curve to be altered.
[in]min_curve_ththreshold for dot product of vector to neighboring control points (negative).
Returns:
the altered curve.

Definition at line 268 of file fitting_curve_2d_pdm.cpp.

void FittingCurve2dPDM::reverse ( ON_NurbsCurve curve) [static]

Reverse direction of rotation of a closed B-spline curve.

Parameters:
[in]curvethe curve to be reversed

Definition at line 437 of file fitting_curve_2d_pdm.cpp.

void pcl::on_nurbs::FittingCurve2dPDM::setInverseParams ( int  max_steps = 200,
double  accuracy = 1e-6 
) [inline]

Set parameters for inverse mapping.

Definition at line 219 of file fitting_curve_2d_pdm.h.

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

Enable/Disable debug outputs in console.

Definition at line 211 of file fitting_curve_2d_pdm.h.

double FittingCurve2dPDM::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 in pcl::on_nurbs::FittingCurve2dTDM, and pcl::on_nurbs::FittingCurve2dSDM.

Definition at line 149 of file fitting_curve_2d_pdm.cpp.

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

Update curve according to the current system of equations.

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

Reimplemented in pcl::on_nurbs::FittingCurve2dTDM, and pcl::on_nurbs::FittingCurve2dSDM.

Definition at line 160 of file fitting_curve_2d_pdm.cpp.


Member Data Documentation

Definition at line 241 of file fitting_curve_2d_pdm.h.

Definition at line 240 of file fitting_curve_2d_pdm.h.

Definition at line 83 of file fitting_curve_2d_pdm.h.

Definition at line 82 of file fitting_curve_2d_pdm.h.

Definition at line 81 of file fitting_curve_2d_pdm.h.

Definition at line 239 of file fitting_curve_2d_pdm.h.

Definition at line 238 of file fitting_curve_2d_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:31