Solving the linear system of equations using Eigen or UmfPack. (can be defined in on_nurbs.cmake) More...
#include <nurbs_solve.h>
Public Member Functions | |
| void | assign (unsigned rows, unsigned cols, unsigned dims) |
| Assign size and dimension (2D, 3D) of system of equations. | |
| Eigen::MatrixXd | diff () |
| Compute the difference between solution K*x and target f. | |
| void | f (unsigned i, unsigned j, double v) |
| Set value for target vector f (force vector) | |
| double | f (unsigned i, unsigned j) |
| Get value for target vector f (force vector) | |
| void | getSize (unsigned &rows, unsigned &cols, unsigned &dims) |
| get size of system | |
| void | K (unsigned i, unsigned j, double v) |
| Set value for system matrix K (stiffness matrix, basis functions) | |
| double | K (unsigned i, unsigned j) |
| Get value for system matrix K (stiffness matrix, basis functions) | |
| NurbsSolve () | |
| Empty constructor. | |
| void | printF () |
| Print target vector f (force vector) | |
| void | printK () |
| Print system matrix K (stiffness matrix, basis functions) | |
| void | printX () |
| Print state vector x (control points) | |
| void | resize (unsigned rows) |
| Resize target vector f (force vector) | |
| void | setQuiet (bool val) |
| Enable/Disable debug outputs in console. | |
| bool | solve () |
| Solves the system of equations with respect to x. | |
| void | x (unsigned i, unsigned j, double v) |
| Set value for state vector x (control points) | |
| double | x (unsigned i, unsigned j) |
| Get value for state vector x (control points) | |
Private Attributes | |
| Eigen::MatrixXd | m_feig |
| Eigen::MatrixXd | m_Keig |
| SparseMat | m_Ksparse |
| bool | m_quiet |
| Eigen::MatrixXd | m_xeig |
Solving the linear system of equations using Eigen or UmfPack. (can be defined in on_nurbs.cmake)
Definition at line 53 of file nurbs_solve.h.
| pcl::on_nurbs::NurbsSolve::NurbsSolve | ( | ) | [inline] |
Empty constructor.
Definition at line 57 of file nurbs_solve.h.
| void NurbsSolve::assign | ( | unsigned | rows, |
| unsigned | cols, | ||
| unsigned | dims | ||
| ) |
Assign size and dimension (2D, 3D) of system of equations.
Definition at line 48 of file nurbs_solve_eigen.cpp.
| Eigen::MatrixXd NurbsSolve::diff | ( | ) |
Compute the difference between solution K*x and target f.
Definition at line 144 of file nurbs_solve_eigen.cpp.
| void NurbsSolve::f | ( | unsigned | i, |
| unsigned | j, | ||
| double | v | ||
| ) |
Set value for target vector f (force vector)
Definition at line 66 of file nurbs_solve_eigen.cpp.
| double NurbsSolve::f | ( | unsigned | i, |
| unsigned | j | ||
| ) |
Get value for target vector f (force vector)
Definition at line 82 of file nurbs_solve_eigen.cpp.
| void pcl::on_nurbs::NurbsSolve::getSize | ( | unsigned & | rows, |
| unsigned & | cols, | ||
| unsigned & | dims | ||
| ) | [inline] |
get size of system
Definition at line 118 of file nurbs_solve.h.
| void NurbsSolve::K | ( | unsigned | i, |
| unsigned | j, | ||
| double | v | ||
| ) |
Set value for system matrix K (stiffness matrix, basis functions)
Definition at line 56 of file nurbs_solve_eigen.cpp.
| double NurbsSolve::K | ( | unsigned | i, |
| unsigned | j | ||
| ) |
Get value for system matrix K (stiffness matrix, basis functions)
Definition at line 72 of file nurbs_solve_eigen.cpp.
| void NurbsSolve::printF | ( | ) |
Print target vector f (force vector)
Definition at line 121 of file nurbs_solve_eigen.cpp.
| void NurbsSolve::printK | ( | ) |
Print system matrix K (stiffness matrix, basis functions)
Definition at line 95 of file nurbs_solve_eigen.cpp.
| void NurbsSolve::printX | ( | ) |
Print state vector x (control points)
Definition at line 108 of file nurbs_solve_eigen.cpp.
| void NurbsSolve::resize | ( | unsigned | rows | ) |
Resize target vector f (force vector)
Definition at line 88 of file nurbs_solve_eigen.cpp.
| void pcl::on_nurbs::NurbsSolve::setQuiet | ( | bool | val | ) | [inline] |
Enable/Disable debug outputs in console.
Definition at line 111 of file nurbs_solve.h.
| bool NurbsSolve::solve | ( | ) |
Solves the system of equations with respect to x.
Definition at line 134 of file nurbs_solve_eigen.cpp.
| void NurbsSolve::x | ( | unsigned | i, |
| unsigned | j, | ||
| double | v | ||
| ) |
Set value for state vector x (control points)
Definition at line 61 of file nurbs_solve_eigen.cpp.
| double NurbsSolve::x | ( | unsigned | i, |
| unsigned | j | ||
| ) |
Get value for state vector x (control points)
Definition at line 77 of file nurbs_solve_eigen.cpp.
Eigen::MatrixXd pcl::on_nurbs::NurbsSolve::m_feig [private] |
Definition at line 130 of file nurbs_solve.h.
Eigen::MatrixXd pcl::on_nurbs::NurbsSolve::m_Keig [private] |
Definition at line 128 of file nurbs_solve.h.
Definition at line 127 of file nurbs_solve.h.
bool pcl::on_nurbs::NurbsSolve::m_quiet [private] |
Definition at line 126 of file nurbs_solve.h.
Eigen::MatrixXd pcl::on_nurbs::NurbsSolve::m_xeig [private] |
Definition at line 129 of file nurbs_solve.h.