Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -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)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down Expand Up @@ -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);
Expand Down Expand Up @@ -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();
Expand All @@ -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)
{
Expand Down Expand Up @@ -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<m_constraintsCorrections.size(); i++)
{
Expand All @@ -573,7 +573,7 @@ void QPInverseProblemSolver::computeResidual(const ExecParams* eparam)
}
}

bool QPInverseProblemSolver::applyCorrection(const ConstraintParams *cParams, MultiVecId res1, MultiVecId res2)
bool QPInverseProblemSolver::doApplyCorrection(const ConstraintParams *cParams, MultiVecId res1, MultiVecId res2)
{
AdvancedTimer::stepBegin("Compute And Apply Motion Correction");

Expand Down
14 changes: 7 additions & 7 deletions src/SoftRobots.Inverse/component/solver/QPInverseProblemSolver.h
Original file line number Diff line number Diff line change
Expand Up @@ -94,27 +94,27 @@ class SOFA_SOFTROBOTS_INVERSE_API QPInverseProblemSolver : public sofa::componen
////////////////////////////////////////////////////////////////////////////////

////////////////////// Inherited from ConstraintSolver ///////////////////////////
bool prepareStates(const ConstraintParams * cParams,
bool doPrepareStates(const ConstraintParams * cParams,
MultiVecId res1,
MultiVecId res2=MultiVecId::null()) override;

bool buildSystem(const ConstraintParams * cParams,
bool doBuildSystem(const ConstraintParams * cParams,
MultiVecId res1,
MultiVecId res2=MultiVecId::null()) override;

void rebuildSystem(double massFactor,
void doRebuildSystem(double massFactor,
double forceFactor) override;

bool solveSystem(const ConstraintParams* cParams,
bool doSolveSystem(const ConstraintParams* cParams,
MultiVecId res1, MultiVecId res2=MultiVecId::null()) override;

bool applyCorrection(const ConstraintParams * cParams,
bool doApplyCorrection(const ConstraintParams * cParams,
MultiVecId res1,
MultiVecId res2=MultiVecId::null()) override;

void computeResidual(const ExecParams* params) override;
void doComputeResidual(const ExecParams* params) override;

void removeConstraintCorrection(BaseConstraintCorrection *s) override;
void doRemoveConstraintCorrection(BaseConstraintCorrection *s) override;

MultiVecDerivId getLambda() const override
{
Expand Down
Loading