Fitting a 2D B-Spline curve to 2D point-clouds using asymmetric point-distance-minimization Based on paper: TODO. More...
#include <fitting_curve_2d_apdm.h>
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 ¶meter) |
Assemble the system of equations for fitting. | |
void | fitting (FitParameter ¶m) |
Fitting with iterative refinement and adaptive knot insertion. | |
FittingCurve2dAPDM (int order, NurbsDataCurve2d *data) | |
Constructor initializing B-Spline curve using initNurbsCurve2D(...). | |
FittingCurve2dAPDM (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. | |
Public Attributes | |
NurbsDataCurve2d * | m_data |
ON_NurbsCurve | m_nurbs |
ON_TextLog | m_out |
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 ¶m, const Eigen::Vector2d &point, double weight, unsigned &row) |
Add minimization constraint: point-to-curve distance (point-distance-minimization). | |
virtual void | assembleClosestPoints (const std::vector< double > &elements, double weight, double sigma2, unsigned samples_per_element, unsigned &row) |
Assemble closest points constraints. At each midpoint of the curve elements the closest data points are computed and point-to-curve constraints are added. | |
virtual void | assembleInterior (double wInt, double sigma2, 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 asymmetric point-distance-minimization Based on paper: TODO.
Definition at line 55 of file fitting_curve_2d_apdm.h.
FittingCurve2dAPDM::FittingCurve2dAPDM | ( | 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_apdm.cpp.
FittingCurve2dAPDM::FittingCurve2dAPDM | ( | 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_apdm.cpp.
void FittingCurve2dAPDM::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 in pcl::on_nurbs::FittingCurve2dASDM, and pcl::on_nurbs::FittingCurve2dATDM.
Definition at line 410 of file fitting_curve_2d_apdm.cpp.
void FittingCurve2dAPDM::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.
[in] | max_error | defining the max allowed distance between data points and curve. |
Definition at line 237 of file fitting_curve_2d_apdm.cpp.
void FittingCurve2dAPDM::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 388 of file fitting_curve_2d_apdm.cpp.
void FittingCurve2dAPDM::assemble | ( | const Parameter & | parameter | ) | [virtual] |
Assemble the system of equations for fitting.
Reimplemented in pcl::on_nurbs::FittingCurve2dASDM, and pcl::on_nurbs::FittingCurve2dATDM.
Definition at line 142 of file fitting_curve_2d_apdm.cpp.
void FittingCurve2dAPDM::assembleClosestPoints | ( | const std::vector< double > & | elements, |
double | weight, | ||
double | sigma2, | ||
unsigned | samples_per_element, | ||
unsigned & | row | ||
) | [protected, virtual] |
Assemble closest points constraints. At each midpoint of the curve elements the closest data points are computed and point-to-curve constraints are added.
Definition at line 736 of file fitting_curve_2d_apdm.cpp.
void FittingCurve2dAPDM::assembleInterior | ( | double | wInt, |
double | sigma2, | ||
double | rScale, | ||
unsigned & | row | ||
) | [protected, virtual] |
Assemble point-to-curve constraints.
Reimplemented in pcl::on_nurbs::FittingCurve2dASDM, and pcl::on_nurbs::FittingCurve2dATDM.
Definition at line 641 of file fitting_curve_2d_apdm.cpp.
double FittingCurve2dAPDM::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 1084 of file fitting_curve_2d_apdm.cpp.
double FittingCurve2dAPDM::findClosestElementMidPoint | ( | const ON_NurbsCurve & | nurbs, |
const Eigen::Vector2d & | pt, | ||
double | hint | ||
) | [static] |
Definition at line 1035 of file fitting_curve_2d_apdm.cpp.
int FittingCurve2dAPDM::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_apdm.cpp.
void FittingCurve2dAPDM::fitting | ( | FitParameter & | param | ) |
Fitting with iterative refinement and adaptive knot insertion.
[in] | param | The parameters for fitting |
Definition at line 117 of file fitting_curve_2d_apdm.cpp.
std::vector< double > FittingCurve2dAPDM::getElementVector | ( | const ON_NurbsCurve & | nurbs | ) | [static] |
Get the elements of a B-Spline curve.
Definition at line 612 of file fitting_curve_2d_apdm.cpp.
ON_NurbsCurve FittingCurve2dAPDM::initCPsNurbsCurve2D | ( | 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 504 of file fitting_curve_2d_apdm.cpp.
ON_NurbsCurve FittingCurve2dAPDM::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.
[in] | order | polynomial order of the curve. |
[in] | data | 2D point-cloud |
[in] | ncps | number of control points |
[in] | radiusF | radius factor multiplied to the radius of the bounding circle. |
Definition at line 539 of file fitting_curve_2d_apdm.cpp.
double FittingCurve2dAPDM::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 802 of file fitting_curve_2d_apdm.cpp.
double FittingCurve2dAPDM::inverseMappingO2 | ( | const ON_NurbsCurve & | nurbs, |
const Eigen::Vector2d & | pt, | ||
double & | error, | ||
Eigen::Vector2d & | p, | ||
Eigen::Vector2d & | t | ||
) | [static] |
Definition at line 879 of file fitting_curve_2d_apdm.cpp.
void FittingCurve2dAPDM::refine | ( | ) |
Refines curve by inserting a knot in the middle of each element.
Definition at line 91 of file fitting_curve_2d_apdm.cpp.
void FittingCurve2dAPDM::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_apdm.cpp.
ON_NurbsCurve FittingCurve2dAPDM::removeCPsOnLine | ( | const ON_NurbsCurve & | nurbs, |
double | min_curve_th = -0.9 |
||
) | [static] |
Removes control points when it is collinear with its neighboring control points.
[in] | nurbs | the B-Spline curve to be altered. |
[in] | min_curve_th | threshold for dot product of vector to neighboring control points (negative). |
Definition at line 303 of file fitting_curve_2d_apdm.cpp.
void pcl::on_nurbs::FittingCurve2dAPDM::setInverseParams | ( | int | max_steps = 200 , |
double | accuracy = 1e-6 |
||
) | [inline] |
Set parameters for inverse mapping.
Definition at line 211 of file fitting_curve_2d_apdm.h.
void pcl::on_nurbs::FittingCurve2dAPDM::setQuiet | ( | bool | val | ) | [inline] |
Enable/Disable debug outputs in console.
Definition at line 203 of file fitting_curve_2d_apdm.h.
double FittingCurve2dAPDM::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::FittingCurve2dASDM, and pcl::on_nurbs::FittingCurve2dATDM.
Definition at line 184 of file fitting_curve_2d_apdm.cpp.
double FittingCurve2dAPDM::updateCurve | ( | double | damp | ) | [virtual] |
Update curve according to the current system of equations.
[in] | damp | damping factor from one iteration to the other. |
Reimplemented in pcl::on_nurbs::FittingCurve2dASDM, and pcl::on_nurbs::FittingCurve2dATDM.
Definition at line 195 of file fitting_curve_2d_apdm.cpp.
double pcl::on_nurbs::FittingCurve2dAPDM::in_accuracy [protected] |
Definition at line 239 of file fitting_curve_2d_apdm.h.
int pcl::on_nurbs::FittingCurve2dAPDM::in_max_steps [protected] |
Definition at line 238 of file fitting_curve_2d_apdm.h.
Definition at line 89 of file fitting_curve_2d_apdm.h.
Definition at line 88 of file fitting_curve_2d_apdm.h.
Definition at line 87 of file fitting_curve_2d_apdm.h.
bool pcl::on_nurbs::FittingCurve2dAPDM::m_quiet [protected] |
Definition at line 237 of file fitting_curve_2d_apdm.h.
Definition at line 236 of file fitting_curve_2d_apdm.h.