Fitting a 3D B-Spline curve to point-clouds using point-distance-minimization and optionally asymmetric-distance-minimization Based on paper: TODO. More...
#include <fitting_curve_pdm.h>
Classes | |
struct | Parameter |
Public Member Functions | |
void | assemble (const Parameter ¶meter) |
Assemble the system of equations for fitting. | |
FittingCurve (int order, NurbsDataCurve *data) | |
Constructor initializing B-Spline curve using initNurbsCurve2D(...). | |
FittingCurve (NurbsDataCurve *data, const ON_NurbsCurve &ns) | |
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 | setQuiet (bool val) |
Enable/Disable debug outputs in console. | |
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 curve if a solution can be obtained. | |
void | 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::Vector3d &pt) |
Given a point pt, the function finds the closest midpoint of the elements of the curve. | |
static int | findElement (double xi, const std::vector< double > &elements) |
Find the element in which the parameter xi lies. | |
static ON_NurbsCurve | initNurbsCurve2D (int order, const vector_vec2d &data) |
Initialize a closed B-Spline curve using the bounding circle of the point-cloud. | |
static ON_NurbsCurve | initNurbsCurvePCA (int order, const vector_vec3d &data, int ncps=0, double rf=1.0) |
Initialize a closed B-Spline curve using the eigenvalues as elliptic parameters (z=0). | |
static double | inverseMapping (const ON_NurbsCurve &nurbs, const Eigen::Vector3d &pt, const double &hint, double &error, Eigen::Vector3d &p, Eigen::Vector3d &t, 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). | |
Public Attributes | |
NurbsDataCurve * | m_data |
ON_NurbsCurve | m_nurbs |
ON_TextLog | m_out |
Private Member Functions | |
void | addCageRegularisation (double weight, unsigned &row) |
Add minimization constraint: smoothness by control point regularisation. | |
void | addPointConstraint (const double ¶m, const Eigen::Vector3d &point, double weight, unsigned &row) |
Add minimization constraint: point-to-surface distance (point-distance-minimization). | |
void | assembleInterior (double wInt, unsigned &row) |
Assemble point-to-surface constraints. | |
Static Private Member Functions | |
static std::vector< double > | getElementVector (const ON_NurbsCurve &nurbs) |
Get the elements of a B-Spline curve. | |
Private Attributes | |
double | in_accuracy |
int | in_max_steps |
bool | m_quiet |
NurbsSolve | m_solver |
Fitting a 3D B-Spline curve to point-clouds using point-distance-minimization and optionally asymmetric-distance-minimization Based on paper: TODO.
Definition at line 57 of file fitting_curve_pdm.h.
FittingCurve::FittingCurve | ( | int | order, |
NurbsDataCurve * | data | ||
) |
Constructor initializing B-Spline curve using initNurbsCurve2D(...).
[in] | order | the polynomial order of the B-Spline curve. |
[in] | data | pointer to the 3D point-cloud data to be fit |
Definition at line 44 of file fitting_curve_pdm.cpp.
FittingCurve::FittingCurve | ( | NurbsDataCurve * | data, |
const ON_NurbsCurve & | ns | ||
) |
Constructor initializing with the B-Spline curve given in argument 2.
[in] | data | pointer to the 3D point-cloud data to be fit. |
[in] | nc | B-Spline curve used for fitting. |
Definition at line 59 of file fitting_curve_pdm.cpp.
void FittingCurve::addCageRegularisation | ( | double | weight, |
unsigned & | row | ||
) | [private] |
Add minimization constraint: smoothness by control point regularisation.
Definition at line 186 of file fitting_curve_pdm.cpp.
void FittingCurve::addPointConstraint | ( | const double & | param, |
const Eigen::Vector3d & | point, | ||
double | weight, | ||
unsigned & | row | ||
) | [private] |
Add minimization constraint: point-to-surface distance (point-distance-minimization).
Definition at line 163 of file fitting_curve_pdm.cpp.
void FittingCurve::assemble | ( | const Parameter & | parameter | ) |
Assemble the system of equations for fitting.
Definition at line 105 of file fitting_curve_pdm.cpp.
void FittingCurve::assembleInterior | ( | double | wInt, |
unsigned & | row | ||
) | [private] |
Assemble point-to-surface constraints.
Definition at line 311 of file fitting_curve_pdm.cpp.
double FittingCurve::findClosestElementMidPoint | ( | const ON_NurbsCurve & | nurbs, |
const Eigen::Vector3d & | 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 415 of file fitting_curve_pdm.cpp.
int FittingCurve::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_pdm.cpp.
std::vector< double > FittingCurve::getElementVector | ( | const ON_NurbsCurve & | nurbs | ) | [static, private] |
Get the elements of a B-Spline curve.
Definition at line 282 of file fitting_curve_pdm.cpp.
ON_NurbsCurve FittingCurve::initNurbsCurve2D | ( | int | order, |
const vector_vec2d & | data | ||
) | [static] |
Initialize a closed B-Spline curve using the bounding circle of the point-cloud.
[in] | order | polynomial order of the curve. |
[in] | data | 3D point-cloud |
Definition at line 207 of file fitting_curve_pdm.cpp.
ON_NurbsCurve FittingCurve::initNurbsCurvePCA | ( | int | order, |
const vector_vec3d & | data, | ||
int | ncps = 0 , |
||
double | rf = 1.0 |
||
) | [static] |
Initialize a closed B-Spline curve using the eigenvalues as elliptic parameters (z=0).
[in] | order | polynomial order of the curve. |
[in] | data | 3D point-cloud |
Definition at line 244 of file fitting_curve_pdm.cpp.
double FittingCurve::inverseMapping | ( | const ON_NurbsCurve & | nurbs, |
const Eigen::Vector3d & | pt, | ||
const double & | hint, | ||
double & | error, | ||
Eigen::Vector3d & | p, | ||
Eigen::Vector3d & | t, | ||
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 347 of file fitting_curve_pdm.cpp.
void FittingCurve::refine | ( | ) |
Refines curve by inserting a knot in the middle of each element.
Definition at line 91 of file fitting_curve_pdm.cpp.
void pcl::on_nurbs::FittingCurve::setQuiet | ( | bool | val | ) | [inline] |
Enable/Disable debug outputs in console.
Definition at line 159 of file fitting_curve_pdm.h.
void FittingCurve::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.
Definition at line 127 of file fitting_curve_pdm.cpp.
void FittingCurve::updateCurve | ( | double | damp | ) |
Update curve according to the current system of equations.
[in] | damp | damping factor from one iteration to the other. |
Definition at line 134 of file fitting_curve_pdm.cpp.
double pcl::on_nurbs::FittingCurve::in_accuracy [private] |
Definition at line 187 of file fitting_curve_pdm.h.
int pcl::on_nurbs::FittingCurve::in_max_steps [private] |
Definition at line 186 of file fitting_curve_pdm.h.
Definition at line 71 of file fitting_curve_pdm.h.
Definition at line 70 of file fitting_curve_pdm.h.
Definition at line 69 of file fitting_curve_pdm.h.
bool pcl::on_nurbs::FittingCurve::m_quiet [private] |
Definition at line 184 of file fitting_curve_pdm.h.
Definition at line 183 of file fitting_curve_pdm.h.