diff --git a/src/SoftRobots.Inverse/binding/Binding_QPInverseProblemSolver.cpp b/src/SoftRobots.Inverse/binding/Binding_QPInverseProblemSolver.cpp index 8424c8d..7223c1d 100644 --- a/src/SoftRobots.Inverse/binding/Binding_QPInverseProblemSolver.cpp +++ b/src/SoftRobots.Inverse/binding/Binding_QPInverseProblemSolver.cpp @@ -65,7 +65,7 @@ bool QPInverseProblemSolver_Trampoline::solveSystem() ); } -bool QPInverseProblemSolver_Trampoline::solveSystem(const sofa::core::ConstraintParams* cParams, +bool QPInverseProblemSolver_Trampoline::doSolveSystem(const sofa::core::ConstraintParams* cParams, sofa::core::MultiVecId res1, sofa::core::MultiVecId res2) { diff --git a/src/SoftRobots.Inverse/binding/Binding_QPInverseProblemSolver.h b/src/SoftRobots.Inverse/binding/Binding_QPInverseProblemSolver.h index 4bc7880..2cadb2c 100644 --- a/src/SoftRobots.Inverse/binding/Binding_QPInverseProblemSolver.h +++ b/src/SoftRobots.Inverse/binding/Binding_QPInverseProblemSolver.h @@ -44,7 +44,7 @@ class QPInverseProblemSolver_Trampoline : public softrobotsinverse::solver::QPIn bool solveSystem(); - bool solveSystem(const sofa::core::ConstraintParams* cParams, + bool doSolveSystem(const sofa::core::ConstraintParams* cParams, sofa::core::MultiVecId res1, sofa::core::MultiVecId res2=sofa::core::MultiVecId::null()) override; diff --git a/src/SoftRobots.Inverse/component/solver/QPInverseProblemSolver.cpp b/src/SoftRobots.Inverse/component/solver/QPInverseProblemSolver.cpp index f76a696..7cdf4dd 100644 --- a/src/SoftRobots.Inverse/component/solver/QPInverseProblemSolver.cpp +++ b/src/SoftRobots.Inverse/component/solver/QPInverseProblemSolver.cpp @@ -296,12 +296,12 @@ void QPInverseProblemSolver::cleanup() ConstraintSolver::cleanup(); } -void QPInverseProblemSolver::removeConstraintCorrection(sofa::core::behavior::BaseConstraintCorrection *s) +void QPInverseProblemSolver::doRemoveConstraintCorrection(sofa::core::behavior::BaseConstraintCorrection *s) { m_constraintsCorrections.erase(std::remove(m_constraintsCorrections.begin(), m_constraintsCorrections.end(), s), m_constraintsCorrections.end()); } -bool QPInverseProblemSolver::prepareStates(const ConstraintParams *cParams, MultiVecId res1, MultiVecId res2) +bool QPInverseProblemSolver::doPrepareStates(const ConstraintParams *cParams, MultiVecId res1, MultiVecId res2) { SOFA_UNUSED(res1); SOFA_UNUSED(res2); @@ -341,7 +341,7 @@ bool QPInverseProblemSolver::prepareStates(const ConstraintParams *cParams, Mult return true; } -bool QPInverseProblemSolver::buildSystem(const ConstraintParams *cParams, MultiVecId res1, MultiVecId res2) +bool QPInverseProblemSolver::doBuildSystem(const ConstraintParams *cParams, MultiVecId res1, MultiVecId res2) { SOFA_UNUSED(res1); SOFA_UNUSED(res2); @@ -469,7 +469,7 @@ inline void QPInverseProblemSolver::buildCompliance(const ConstraintParams *cPar AdvancedTimer::stepEnd("Get Compliance"); } -void QPInverseProblemSolver::rebuildSystem(double massFactor, double forceFactor) +void QPInverseProblemSolver::doRebuildSystem(double massFactor, double forceFactor) { d_graph.beginEdit()->clear(); d_graph.endEdit(); @@ -482,7 +482,7 @@ void QPInverseProblemSolver::rebuildSystem(double massFactor, double forceFactor } } -bool QPInverseProblemSolver::solveSystem(const ConstraintParams * cParams, +bool QPInverseProblemSolver::doSolveSystem(const ConstraintParams * cParams, MultiVecId res1, MultiVecId res2) { @@ -564,7 +564,7 @@ bool QPInverseProblemSolver::solveSystem(const ConstraintParams * cParams, } -void QPInverseProblemSolver::computeResidual(const ExecParams* eparam) +void QPInverseProblemSolver::doComputeResidual(const ExecParams* eparam) { for (unsigned int i=0; i