Fitting and optimizing multiple B-Spline surfaces to 3D point-clouds using point-distance-minimization in a single system of equations (global). Based on paper: TODO. More...
#include <global_optimization_pdm.h>
Classes | |
struct | Parameter |
Parameters for fitting. More... | |
Public Member Functions | |
virtual void | assemble (Parameter params=Parameter()) |
Assemble the system of equations for fitting. | |
GlobalOptimization (const std::vector< NurbsDataSurface * > &data, const std::vector< ON_NurbsSurface * > &nurbs) | |
Constructor with a set of data and a set of B-Spline surfaces. | |
void | refine (unsigned id, int dim) |
Refines specified surface by inserting a knot in the middle of each element. | |
void | setCommonBoundary (const vector_vec3d &boundary, const vector_vec2i &nurbs_indices) |
Set common boundary points two NURBS should lie on. | |
void | setInvMapParams (double im_max_steps, double im_accuracy) |
Set parameters for inverse mapping. | |
void | setQuiet (bool val) |
virtual 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 surface if a solution can be obtained. | |
virtual void | updateSurf (double damp) |
Update surface according to the current system of equations. | |
Protected Member Functions | |
virtual void | addCageBoundaryRegularisation (unsigned id, int ncps, double weight, int side, unsigned &row) |
Add minimization constraint: boundary smoothness by control point regularisation. | |
virtual void | addCageCornerRegularisation (unsigned id, int ncps, double weight, unsigned &row) |
Add minimization constraint: corner smoothness by control point regularisation. | |
virtual void | addCageInteriorRegularisation (unsigned id, int ncps, double weight, unsigned &row) |
Add minimization constraint: interior smoothness by control point regularisation. | |
virtual void | addParamConstraint (const Eigen::Vector2i &id, const Eigen::Vector2d ¶ms1, const Eigen::Vector2d ¶ms2, double weight, unsigned &row) |
Add minimization constraint: two points in parametric domain of two surfaces should lie on each other. | |
virtual void | addPointConstraint (unsigned id, int ncps, const Eigen::Vector2d ¶ms, const Eigen::Vector3d &point, double weight, unsigned &row) |
Add minimization constraint: point-to-surface distance (point-distance-minimization). | |
virtual void | assembleBoundaryPoints (unsigned id, int ncps, double weight, unsigned &row) |
Assemble point-to-surface constraints for boundary points. | |
virtual void | assembleClosingBoundaries (unsigned id, unsigned samples, double sigma, double weight, unsigned &row) |
Assemble closing-constraint of boundaries by sampling from nurbs boundary and find closest point on closest nurbs. | |
virtual void | assembleCommonBoundaries (unsigned id1, double weight, unsigned &row) |
Assemble closing-constraint of boundaries using data.boundary for getting closest points. | |
void | assembleCommonParams (unsigned id1, double weight, unsigned &row) |
virtual void | assembleInteriorPoints (unsigned id, int ncps, double weight, unsigned &row) |
Assemble point-to-surface constraints for interior points. | |
virtual void | assembleRegularisation (unsigned id, int ncps, double wCageRegInt, double wCageRegBnd, unsigned &row) |
Assemble smoothness constraints. | |
int | gl2gc (const ON_NurbsSurface &nurbs, int A) |
int | gl2gr (const ON_NurbsSurface &nurbs, int A) |
int | grc2gl (const ON_NurbsSurface &nurbs, int I, int J) |
int | lrc2gl (const ON_NurbsSurface &nurbs, int E, int F, int i, int j) |
Protected Attributes | |
double | im_accuracy |
int | im_max_steps |
std::vector< NurbsDataSurface * > | m_data |
unsigned | m_ncols |
unsigned | m_nrows |
std::vector< ON_NurbsSurface * > | m_nurbs |
bool | m_quiet |
NurbsSolve | m_solver |
Fitting and optimizing multiple B-Spline surfaces to 3D point-clouds using point-distance-minimization in a single system of equations (global). Based on paper: TODO.
Definition at line 55 of file global_optimization_pdm.h.
GlobalOptimization::GlobalOptimization | ( | const std::vector< NurbsDataSurface * > & | data, |
const std::vector< ON_NurbsSurface * > & | nurbs | ||
) |
Constructor with a set of data and a set of B-Spline surfaces.
[in] | data | set of 3D point-cloud data to be fit. |
[in] | nurbs | set of B-Spline surface used for fitting. |
Definition at line 48 of file global_optimization_pdm.cpp.
void GlobalOptimization::addCageBoundaryRegularisation | ( | unsigned | id, |
int | ncps, | ||
double | weight, | ||
int | side, | ||
unsigned & | row | ||
) | [protected, virtual] |
Add minimization constraint: boundary smoothness by control point regularisation.
Reimplemented in pcl::on_nurbs::GlobalOptimizationTDM.
Definition at line 605 of file global_optimization_pdm.cpp.
void GlobalOptimization::addCageCornerRegularisation | ( | unsigned | id, |
int | ncps, | ||
double | weight, | ||
unsigned & | row | ||
) | [protected, virtual] |
Add minimization constraint: corner smoothness by control point regularisation.
Reimplemented in pcl::on_nurbs::GlobalOptimizationTDM.
Definition at line 655 of file global_optimization_pdm.cpp.
void GlobalOptimization::addCageInteriorRegularisation | ( | unsigned | id, |
int | ncps, | ||
double | weight, | ||
unsigned & | row | ||
) | [protected, virtual] |
Add minimization constraint: interior smoothness by control point regularisation.
Reimplemented in pcl::on_nurbs::GlobalOptimizationTDM.
Definition at line 578 of file global_optimization_pdm.cpp.
void GlobalOptimization::addParamConstraint | ( | const Eigen::Vector2i & | id, |
const Eigen::Vector2d & | params1, | ||
const Eigen::Vector2d & | params2, | ||
double | weight, | ||
unsigned & | row | ||
) | [protected, virtual] |
Add minimization constraint: two points in parametric domain of two surfaces should lie on each other.
Reimplemented in pcl::on_nurbs::GlobalOptimizationTDM.
Definition at line 483 of file global_optimization_pdm.cpp.
void GlobalOptimization::addPointConstraint | ( | unsigned | id, |
int | ncps, | ||
const Eigen::Vector2d & | params, | ||
const Eigen::Vector3d & | point, | ||
double | weight, | ||
unsigned & | row | ||
) | [protected, virtual] |
Add minimization constraint: point-to-surface distance (point-distance-minimization).
Reimplemented in pcl::on_nurbs::GlobalOptimizationTDM.
Definition at line 538 of file global_optimization_pdm.cpp.
void GlobalOptimization::assemble | ( | Parameter | params = Parameter () | ) | [virtual] |
Assemble the system of equations for fitting.
Reimplemented in pcl::on_nurbs::GlobalOptimizationTDM.
Definition at line 74 of file global_optimization_pdm.cpp.
void GlobalOptimization::assembleBoundaryPoints | ( | unsigned | id, |
int | ncps, | ||
double | weight, | ||
unsigned & | row | ||
) | [protected, virtual] |
Assemble point-to-surface constraints for boundary points.
Reimplemented in pcl::on_nurbs::GlobalOptimizationTDM.
Definition at line 408 of file global_optimization_pdm.cpp.
void GlobalOptimization::assembleClosingBoundaries | ( | unsigned | id, |
unsigned | samples, | ||
double | sigma, | ||
double | weight, | ||
unsigned & | row | ||
) | [protected, virtual] |
Assemble closing-constraint of boundaries by sampling from nurbs boundary and find closest point on closest nurbs.
Reimplemented in pcl::on_nurbs::GlobalOptimizationTDM.
Definition at line 312 of file global_optimization_pdm.cpp.
void GlobalOptimization::assembleCommonBoundaries | ( | unsigned | id1, |
double | weight, | ||
unsigned & | row | ||
) | [protected, virtual] |
Assemble closing-constraint of boundaries using data.boundary for getting closest points.
Reimplemented in pcl::on_nurbs::GlobalOptimizationTDM.
Definition at line 225 of file global_optimization_pdm.cpp.
void GlobalOptimization::assembleCommonParams | ( | unsigned | id1, |
double | weight, | ||
unsigned & | row | ||
) | [protected] |
Reimplemented in pcl::on_nurbs::GlobalOptimizationTDM.
Definition at line 212 of file global_optimization_pdm.cpp.
void GlobalOptimization::assembleInteriorPoints | ( | unsigned | id, |
int | ncps, | ||
double | weight, | ||
unsigned & | row | ||
) | [protected, virtual] |
Assemble point-to-surface constraints for interior points.
Reimplemented in pcl::on_nurbs::GlobalOptimizationTDM.
Definition at line 355 of file global_optimization_pdm.cpp.
void GlobalOptimization::assembleRegularisation | ( | unsigned | id, |
int | ncps, | ||
double | wCageRegInt, | ||
double | wCageRegBnd, | ||
unsigned & | row | ||
) | [protected, virtual] |
Assemble smoothness constraints.
Reimplemented in pcl::on_nurbs::GlobalOptimizationTDM.
Definition at line 460 of file global_optimization_pdm.cpp.
int pcl::on_nurbs::GlobalOptimization::gl2gc | ( | const ON_NurbsSurface & | nurbs, |
int | A | ||
) | [inline, protected] |
Definition at line 202 of file global_optimization_pdm.h.
int pcl::on_nurbs::GlobalOptimization::gl2gr | ( | const ON_NurbsSurface & | nurbs, |
int | A | ||
) | [inline, protected] |
Definition at line 197 of file global_optimization_pdm.h.
int pcl::on_nurbs::GlobalOptimization::grc2gl | ( | const ON_NurbsSurface & | nurbs, |
int | I, | ||
int | J | ||
) | [inline, protected] |
Definition at line 187 of file global_optimization_pdm.h.
int pcl::on_nurbs::GlobalOptimization::lrc2gl | ( | const ON_NurbsSurface & | nurbs, |
int | E, | ||
int | F, | ||
int | i, | ||
int | j | ||
) | [inline, protected] |
Definition at line 192 of file global_optimization_pdm.h.
void GlobalOptimization::refine | ( | unsigned | id, |
int | dim | ||
) |
Refines specified surface by inserting a knot in the middle of each element.
[in] | id | the index of the surface to be refined. |
[in] | dim | dimension of refinement (0,1) |
Definition at line 197 of file global_optimization_pdm.cpp.
void GlobalOptimization::setCommonBoundary | ( | const vector_vec3d & | boundary, |
const vector_vec2i & | nurbs_indices | ||
) |
Set common boundary points two NURBS should lie on.
[in] | boundary | vector of boundary points. |
[in] | nurbs_indices | vector of 2 NURBS indices sharing the boundary point. |
Definition at line 64 of file global_optimization_pdm.cpp.
void GlobalOptimization::setInvMapParams | ( | double | im_max_steps, |
double | im_accuracy | ||
) |
Set parameters for inverse mapping.
[in] | in_max_steps | maximum number of iterations. |
[in] | in_accuracy | stops iteration if specified accuracy is reached. |
Definition at line 190 of file global_optimization_pdm.cpp.
void pcl::on_nurbs::GlobalOptimization::setQuiet | ( | bool | val | ) | [inline] |
Definition at line 122 of file global_optimization_pdm.h.
void GlobalOptimization::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 surface if a solution can be obtained.
Reimplemented in pcl::on_nurbs::GlobalOptimizationTDM.
Definition at line 151 of file global_optimization_pdm.cpp.
void GlobalOptimization::updateSurf | ( | double | damp | ) | [virtual] |
Update surface according to the current system of equations.
[in] | damp | damping factor from one iteration to the other. |
Reimplemented in pcl::on_nurbs::GlobalOptimizationTDM.
Definition at line 158 of file global_optimization_pdm.cpp.
double pcl::on_nurbs::GlobalOptimization::im_accuracy [protected] |
Definition at line 183 of file global_optimization_pdm.h.
int pcl::on_nurbs::GlobalOptimization::im_max_steps [protected] |
Definition at line 182 of file global_optimization_pdm.h.
std::vector<NurbsDataSurface*> pcl::on_nurbs::GlobalOptimization::m_data [protected] |
Definition at line 130 of file global_optimization_pdm.h.
unsigned pcl::on_nurbs::GlobalOptimization::m_ncols [protected] |
Definition at line 181 of file global_optimization_pdm.h.
unsigned pcl::on_nurbs::GlobalOptimization::m_nrows [protected] |
Definition at line 181 of file global_optimization_pdm.h.
std::vector<ON_NurbsSurface*> pcl::on_nurbs::GlobalOptimization::m_nurbs [protected] |
Definition at line 131 of file global_optimization_pdm.h.
bool pcl::on_nurbs::GlobalOptimization::m_quiet [protected] |
Definition at line 180 of file global_optimization_pdm.h.
Definition at line 179 of file global_optimization_pdm.h.