Fitting a 2D B-Spline curve to 2D point-clouds using point-distance-minimization Based on paper: TODO. More...
#include <fitting_curve_2d.h>
Classes | |
struct | FitParameter |
struct | Parameter |
Parameters for fitting. More... | |
Public Member Functions | |
virtual void | addControlPointConstraint (int i, const Eigen::Vector2d &f, double weight) |
virtual void | assemble (const Parameter ¶meter) |
Assemble the system of equations for fitting. | |
FittingCurve2d (int order, NurbsDataCurve2d *data) | |
Constructor initializing B-Spline curve using initNurbsCurve2D(...). | |
FittingCurve2d (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 | initNurbsCPS (int order, const vector_vec2d &cps) |
Initialize a closed B-Spline curve given a list of control points. | |
static ON_NurbsCurve | initNurbsPCA (int order, NurbsDataCurve2d *data, int ncps=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 void | reverse (ON_NurbsCurve &curve) |
Reverse direction of rotation of a closed B-spline curve. | |
Public Attributes | |
NurbsDataCurve2d * | m_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 ¶m, 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 |
Fitting a 2D B-Spline curve to 2D point-clouds using point-distance-minimization Based on paper: TODO.
Definition at line 56 of file fitting_curve_2d.h.
FittingCurve2d::FittingCurve2d | ( | int | order, |
NurbsDataCurve2d * | data | ||
) |
Constructor initializing B-Spline curve using initNurbsCurve2D(...).
[in] | order | the polynomial order of the B-Spline curve. |
[in] | data | pointer to the 2D point-cloud data to be fit. |
Definition at line 44 of file fitting_curve_2d.cpp.
FittingCurve2d::FittingCurve2d | ( | NurbsDataCurve2d * | data, |
const ON_NurbsCurve & | nc | ||
) |
Constructor initializing with the B-Spline curve given in argument 2.
[in] | data | pointer to the 2D point-cloud data to be fit. |
[in] | nc | B-Spline curve used for fitting. |
Definition at line 59 of file fitting_curve_2d.cpp.
void FittingCurve2d::addCageRegularisation | ( | double | weight, |
unsigned & | row | ||
) | [protected, virtual] |
Add minimization constraint: smoothness by control point regularisation.
Definition at line 228 of file fitting_curve_2d.cpp.
void FittingCurve2d::addControlPointConstraint | ( | int | i, |
const Eigen::Vector2d & | f, | ||
double | weight | ||
) | [virtual] |
Definition at line 147 of file fitting_curve_2d.cpp.
void FittingCurve2d::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 208 of file fitting_curve_2d.cpp.
void FittingCurve2d::assemble | ( | const Parameter & | parameter | ) | [virtual] |
Assemble the system of equations for fitting.
Definition at line 117 of file fitting_curve_2d.cpp.
void FittingCurve2d::assembleInterior | ( | double | wInt, |
double | rScale, | ||
unsigned & | row | ||
) | [protected, virtual] |
Assemble point-to-curve constraints.
Definition at line 396 of file fitting_curve_2d.cpp.
double FittingCurve2d::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.
[in] | nurbs | the B-Spline curve. |
[in] | pt | the point to which the closest midpoint of the elements will be computed. return closest midpoint in parametric domain. |
Definition at line 710 of file fitting_curve_2d.cpp.
double FittingCurve2d::findClosestElementMidPoint | ( | const ON_NurbsCurve & | nurbs, |
const Eigen::Vector2d & | pt, | ||
double | hint | ||
) | [static] |
Definition at line 661 of file fitting_curve_2d.cpp.
int FittingCurve2d::findElement | ( | double | xi, |
const std::vector< double > & | elements | ||
) | [static] |
Find the element in which the parameter xi lies.
[in] | xi | value in parameter domain of the B-Spline curve. |
[in] | elements | the vector of elements of the curve. |
Definition at line 72 of file fitting_curve_2d.cpp.
std::vector< double > FittingCurve2d::getElementVector | ( | const ON_NurbsCurve & | nurbs | ) | [static] |
Get the elements of a B-Spline curve.
Definition at line 367 of file fitting_curve_2d.cpp.
ON_NurbsCurve FittingCurve2d::initNurbsCPS | ( | int | order, |
const vector_vec2d & | cps | ||
) | [static] |
Initialize a closed B-Spline curve given a list of control points.
[in] | order | polynomial order of the curve. |
[in] | cps | sequence of control points. |
Definition at line 246 of file fitting_curve_2d.cpp.
ON_NurbsCurve FittingCurve2d::initNurbsPCA | ( | int | order, |
NurbsDataCurve2d * | data, | ||
int | ncps = 0 |
||
) | [static] |
Initialize a closed B-Spline curve using the bounding circle of the point-cloud.
[in] | order | polynomial order of the curve. |
[in] | data | 2D point-cloud |
[in] | ncps | number of control points (if 0, minimum number of control points required are used) |
Definition at line 282 of file fitting_curve_2d.cpp.
double FittingCurve2d::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).
[in] | nurbs | the B-Spline curve. |
[in] | pt | the point to which the closest point on the curve will be computed. |
[in] | hint | the starting point in parametric domain (warning: may lead to convergence at local minima). |
[in] | error | the distance between the point pt and p after convergence. |
[in] | p | closest point on curve. |
[in] | t | the tangent vector at point p. |
[in] | maxSteps | maximum number of iterations. |
[in] | accuracy | convergence criteria: if error is lower than accuracy the function returns |
Definition at line 438 of file fitting_curve_2d.cpp.
double FittingCurve2d::inverseMappingO2 | ( | const ON_NurbsCurve & | nurbs, |
const Eigen::Vector2d & | pt, | ||
double & | error, | ||
Eigen::Vector2d & | p, | ||
Eigen::Vector2d & | t | ||
) | [static] |
Definition at line 505 of file fitting_curve_2d.cpp.
void FittingCurve2d::refine | ( | ) |
Refines curve by inserting a knot in the middle of each element.
Definition at line 91 of file fitting_curve_2d.cpp.
void FittingCurve2d::refine | ( | double | xi | ) |
Refines curve by inserting a knot in the middle of the element belonging to xi.
[in] | xi | parameter defining the element to be refined. |
Definition at line 105 of file fitting_curve_2d.cpp.
void FittingCurve2d::reverse | ( | ON_NurbsCurve & | curve | ) | [static] |
Reverse direction of rotation of a closed B-spline curve.
[in] | curve | the curve to be reversed |
Definition at line 352 of file fitting_curve_2d.cpp.
void pcl::on_nurbs::FittingCurve2d::setInverseParams | ( | int | max_steps = 200 , |
double | accuracy = 1e-6 |
||
) | [inline] |
Set parameters for inverse mapping.
Definition at line 205 of file fitting_curve_2d.h.
void pcl::on_nurbs::FittingCurve2d::setQuiet | ( | bool | val | ) | [inline] |
Enable/Disable debug outputs in console.
Definition at line 197 of file fitting_curve_2d.h.
double FittingCurve2d::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.
Definition at line 169 of file fitting_curve_2d.cpp.
double FittingCurve2d::updateCurve | ( | double | damp | ) | [virtual] |
Update curve according to the current system of equations.
[in] | damp | damping factor from one iteration to the other. |
Definition at line 180 of file fitting_curve_2d.cpp.
double pcl::on_nurbs::FittingCurve2d::in_accuracy [protected] |
Definition at line 227 of file fitting_curve_2d.h.
int pcl::on_nurbs::FittingCurve2d::in_max_steps [protected] |
Definition at line 226 of file fitting_curve_2d.h.
Definition at line 83 of file fitting_curve_2d.h.
Definition at line 82 of file fitting_curve_2d.h.
Definition at line 81 of file fitting_curve_2d.h.
bool pcl::on_nurbs::FittingCurve2d::m_quiet [protected] |
Definition at line 225 of file fitting_curve_2d.h.
NurbsSolve pcl::on_nurbs::FittingCurve2d::m_solver [protected] |
Definition at line 224 of file fitting_curve_2d.h.