Fitting and optimizing multiple B-Spline surfaces to 3D point-clouds using tangent-distance-minimization (TDM) in a single system of equations (global). Based on paper: TODO. More...
#include <global_optimization_tdm.h>

Classes | |
| struct | ParameterTDM |
| Parameters for fitting. More... | |
Public Member Functions | |
| virtual void | assemble (Parameter params) |
| Assemble the system of equations for fitting. | |
| void | assemble (ParameterTDM params=ParameterTDM()) |
| Assemble the system of equations for fitting. | |
| GlobalOptimizationTDM (const std::vector< NurbsDataSurface * > &data, const std::vector< ON_NurbsSurface * > &nurbs) | |
| Constructor with a set of data and a set of B-Spline surfaces. | |
| 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. | |
Private 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 | addParamConstraintTD (const Eigen::Vector2i &id, const Eigen::Vector2d ¶ms1, const Eigen::Vector2d ¶ms2, const Eigen::Vector3d &n, const Eigen::Vector3d &tu, const Eigen::Vector3d &tv, double tangent_weight, double weight, unsigned &row) |
| Add minimization constraint: two points in parametric domain of two surfaces should lie on each other and using the tangent-distance (TD). | |
| 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). | |
| void | addPointConstraintTD (unsigned id, int ncps, const Eigen::Vector2d ¶ms, const Eigen::Vector3d &p, const Eigen::Vector3d &n, const Eigen::Vector3d &tu, const Eigen::Vector3d &tv, double tangent_weight, double weight, unsigned &row) |
| Add minimization constraint: point-to-surface distance (tangent-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. | |
| void | assembleClosingBoundariesTD (unsigned id, unsigned samples, double sigma, double wTangent, double weight, unsigned &row) |
| Assemble closing-constraint of boundaries by sampling from nurbs boundary and find closest point on closest nurbs using the tangent-distance (TD) | |
| virtual void | assembleCommonBoundaries (unsigned id1, double weight, unsigned &row) |
| Assemble closing-constraint of boundaries using data.boundary for getting closest points. | |
| void | assembleCommonBoundariesTD (unsigned id1, double wTangent, double weight, unsigned &row) |
| Assemble closing-constraint of boundaries using data.boundary for getting closest points and using the tangent-distance (TD) | |
| virtual 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. | |
| void | assembleInteriorPointsTD (unsigned id, int ncps, double wTangent, double weight, unsigned &row) |
| Assemble point-to-surface constraints for interior points using the tangent-distance (TD). | |
| virtual void | assembleRegularisation (unsigned id, int ncps, double wCageRegInt, double wCageRegBnd, unsigned &row) |
| Assemble smoothness constraints. | |
Fitting and optimizing multiple B-Spline surfaces to 3D point-clouds using tangent-distance-minimization (TDM) in a single system of equations (global). Based on paper: TODO.
Definition at line 53 of file global_optimization_tdm.h.
| GlobalOptimizationTDM::GlobalOptimizationTDM | ( | 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 46 of file global_optimization_tdm.cpp.
| void GlobalOptimizationTDM::addCageBoundaryRegularisation | ( | unsigned | id, |
| int | ncps, | ||
| double | weight, | ||
| int | side, | ||
| unsigned & | row | ||
| ) | [private, virtual] |
Add minimization constraint: boundary smoothness by control point regularisation.
Reimplemented from pcl::on_nurbs::GlobalOptimization.
Definition at line 882 of file global_optimization_tdm.cpp.
| void GlobalOptimizationTDM::addCageCornerRegularisation | ( | unsigned | id, |
| int | ncps, | ||
| double | weight, | ||
| unsigned & | row | ||
| ) | [private, virtual] |
Add minimization constraint: corner smoothness by control point regularisation.
Reimplemented from pcl::on_nurbs::GlobalOptimization.
Definition at line 948 of file global_optimization_tdm.cpp.
| void GlobalOptimizationTDM::addCageInteriorRegularisation | ( | unsigned | id, |
| int | ncps, | ||
| double | weight, | ||
| unsigned & | row | ||
| ) | [private, virtual] |
Add minimization constraint: interior smoothness by control point regularisation.
Reimplemented from pcl::on_nurbs::GlobalOptimization.
Definition at line 843 of file global_optimization_tdm.cpp.
| void GlobalOptimizationTDM::addParamConstraint | ( | const Eigen::Vector2i & | id, |
| const Eigen::Vector2d & | params1, | ||
| const Eigen::Vector2d & | params2, | ||
| double | weight, | ||
| unsigned & | row | ||
| ) | [private, virtual] |
Add minimization constraint: two points in parametric domain of two surfaces should lie on each other.
Reimplemented from pcl::on_nurbs::GlobalOptimization.
Definition at line 630 of file global_optimization_tdm.cpp.
| void GlobalOptimizationTDM::addParamConstraintTD | ( | const Eigen::Vector2i & | id, |
| const Eigen::Vector2d & | params1, | ||
| const Eigen::Vector2d & | params2, | ||
| const Eigen::Vector3d & | n, | ||
| const Eigen::Vector3d & | tu, | ||
| const Eigen::Vector3d & | tv, | ||
| double | tangent_weight, | ||
| double | weight, | ||
| unsigned & | row | ||
| ) | [private, virtual] |
Add minimization constraint: two points in parametric domain of two surfaces should lie on each other and using the tangent-distance (TD).
Definition at line 687 of file global_optimization_tdm.cpp.
| void GlobalOptimizationTDM::addPointConstraint | ( | unsigned | id, |
| int | ncps, | ||
| const Eigen::Vector2d & | params, | ||
| const Eigen::Vector3d & | point, | ||
| double | weight, | ||
| unsigned & | row | ||
| ) | [private, virtual] |
Add minimization constraint: point-to-surface distance (point-distance-minimization).
Reimplemented from pcl::on_nurbs::GlobalOptimization.
Definition at line 748 of file global_optimization_tdm.cpp.
| void GlobalOptimizationTDM::addPointConstraintTD | ( | unsigned | id, |
| int | ncps, | ||
| const Eigen::Vector2d & | params, | ||
| const Eigen::Vector3d & | p, | ||
| const Eigen::Vector3d & | n, | ||
| const Eigen::Vector3d & | tu, | ||
| const Eigen::Vector3d & | tv, | ||
| double | tangent_weight, | ||
| double | weight, | ||
| unsigned & | row | ||
| ) | [private] |
Add minimization constraint: point-to-surface distance (tangent-distance-minimization).
Definition at line 793 of file global_optimization_tdm.cpp.
| void GlobalOptimizationTDM::assemble | ( | Parameter | params | ) | [virtual] |
Assemble the system of equations for fitting.
Reimplemented from pcl::on_nurbs::GlobalOptimization.
Definition at line 53 of file global_optimization_tdm.cpp.
| void GlobalOptimizationTDM::assemble | ( | ParameterTDM | params = ParameterTDM () | ) |
Assemble the system of equations for fitting.
Definition at line 123 of file global_optimization_tdm.cpp.
| void GlobalOptimizationTDM::assembleBoundaryPoints | ( | unsigned | id, |
| int | ncps, | ||
| double | weight, | ||
| unsigned & | row | ||
| ) | [private, virtual] |
Assemble point-to-surface constraints for boundary points.
Reimplemented from pcl::on_nurbs::GlobalOptimization.
Definition at line 555 of file global_optimization_tdm.cpp.
| void GlobalOptimizationTDM::assembleClosingBoundaries | ( | unsigned | id, |
| unsigned | samples, | ||
| double | sigma, | ||
| double | weight, | ||
| unsigned & | row | ||
| ) | [private, virtual] |
Assemble closing-constraint of boundaries by sampling from nurbs boundary and find closest point on closest nurbs.
Reimplemented from pcl::on_nurbs::GlobalOptimization.
Definition at line 355 of file global_optimization_tdm.cpp.
| void GlobalOptimizationTDM::assembleClosingBoundariesTD | ( | unsigned | id, |
| unsigned | samples, | ||
| double | sigma, | ||
| double | wTangent, | ||
| double | weight, | ||
| unsigned & | row | ||
| ) | [private] |
Assemble closing-constraint of boundaries by sampling from nurbs boundary and find closest point on closest nurbs using the tangent-distance (TD)
Definition at line 398 of file global_optimization_tdm.cpp.
| void GlobalOptimizationTDM::assembleCommonBoundaries | ( | unsigned | id1, |
| double | weight, | ||
| unsigned & | row | ||
| ) | [private, virtual] |
Assemble closing-constraint of boundaries using data.boundary for getting closest points.
Reimplemented from pcl::on_nurbs::GlobalOptimization.
Definition at line 264 of file global_optimization_tdm.cpp.
| void pcl::on_nurbs::GlobalOptimizationTDM::assembleCommonBoundariesTD | ( | unsigned | id1, |
| double | wTangent, | ||
| double | weight, | ||
| unsigned & | row | ||
| ) | [private] |
Assemble closing-constraint of boundaries using data.boundary for getting closest points and using the tangent-distance (TD)
| void GlobalOptimizationTDM::assembleCommonParams | ( | unsigned | id1, |
| double | weight, | ||
| unsigned & | row | ||
| ) | [private, virtual] |
Reimplemented from pcl::on_nurbs::GlobalOptimization.
Definition at line 239 of file global_optimization_tdm.cpp.
| void GlobalOptimizationTDM::assembleInteriorPoints | ( | unsigned | id, |
| int | ncps, | ||
| double | weight, | ||
| unsigned & | row | ||
| ) | [private, virtual] |
Assemble point-to-surface constraints for interior points.
Reimplemented from pcl::on_nurbs::GlobalOptimization.
Definition at line 448 of file global_optimization_tdm.cpp.
| void GlobalOptimizationTDM::assembleInteriorPointsTD | ( | unsigned | id, |
| int | ncps, | ||
| double | wTangent, | ||
| double | weight, | ||
| unsigned & | row | ||
| ) | [private] |
Assemble point-to-surface constraints for interior points using the tangent-distance (TD).
Definition at line 501 of file global_optimization_tdm.cpp.
| void GlobalOptimizationTDM::assembleRegularisation | ( | unsigned | id, |
| int | ncps, | ||
| double | wCageRegInt, | ||
| double | wCageRegBnd, | ||
| unsigned & | row | ||
| ) | [private, virtual] |
Assemble smoothness constraints.
Reimplemented from pcl::on_nurbs::GlobalOptimization.
Definition at line 607 of file global_optimization_tdm.cpp.
| void GlobalOptimizationTDM::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 from pcl::on_nurbs::GlobalOptimization.
Definition at line 200 of file global_optimization_tdm.cpp.
| void GlobalOptimizationTDM::updateSurf | ( | double | damp | ) | [virtual] |
Update surface according to the current system of equations.
| [in] | damp | damping factor from one iteration to the other. |
Reimplemented from pcl::on_nurbs::GlobalOptimization.
Definition at line 207 of file global_optimization_tdm.cpp.