diff --git a/plugins/proxqp/QpSolversEigenProxqp.cpp b/plugins/proxqp/QpSolversEigenProxqp.cpp index 3cf9936..68192ca 100644 --- a/plugins/proxqp/QpSolversEigenProxqp.cpp +++ b/plugins/proxqp/QpSolversEigenProxqp.cpp @@ -7,6 +7,7 @@ // proxsuite #include +#include #include @@ -18,8 +19,18 @@ class ProxqpSolver final: public SolverInterface private: // proxqp settings proxsuite::proxqp::Settings proxqpSettings; + + // backend used by the solver (sparse or dense) + enum class Backend + { + Sparse, + Dense + } backend{Backend::Dense}; + // proxqp sparse solver std::unique_ptr> proxqpSparseSolver; + // proxqp dense solver + std::unique_ptr> proxqpDenseSolver; struct InitialSparseSolverData { int numberOfVariables = 0; @@ -28,6 +39,7 @@ class ProxqpSolver final: public SolverInterface // Hessian bool isHessianSet = false; Eigen::SparseMatrix H; + Eigen::MatrixXd Hdense; // Gradient bool isGradientSet = false; @@ -35,11 +47,13 @@ class ProxqpSolver final: public SolverInterface // Equality constraints data (unused) Eigen::SparseMatrix A; + Eigen::MatrixXd Adense; Eigen::VectorXd b; // Inequality constraints data bool isLinearConstraintsSet = false; Eigen::SparseMatrix C; + Eigen::MatrixXd Cdense; bool isLowerBoundSet = false; Eigen::VectorXd l; bool isUpperBoundSet = false; @@ -137,6 +151,11 @@ void ProxqpSolver::syncSettings() { proxqpSparseSolver->settings = proxqpSettings; } + + if (proxqpDenseSolver) + { + proxqpDenseSolver->settings = proxqpSettings; + } } std::string ProxqpSolver::getSolverName() const @@ -164,23 +183,42 @@ bool ProxqpSolver::initSolver() // See https://github.com/ami-iit/qpsolvers-eigen/issues/4 int numberOfEqualityConstraints = 0; - proxqpSparseSolver = std::make_unique>(initialSparseSolverData.numberOfVariables, numberOfEqualityConstraints, initialSparseSolverData.numberOfConstraints); - syncSettings(); - proxqpSparseSolver->init(initialSparseSolverData.H, initialSparseSolverData.g, - initialSparseSolverData.A, initialSparseSolverData.b, - initialSparseSolverData.C, initialSparseSolverData.l, initialSparseSolverData.u); + + if (backend == Backend::Sparse) + { + proxqpSparseSolver = std::make_unique>(initialSparseSolverData.numberOfVariables, numberOfEqualityConstraints, initialSparseSolverData.numberOfConstraints); + syncSettings(); + proxqpSparseSolver->init(initialSparseSolverData.H, initialSparseSolverData.g, + initialSparseSolverData.A, initialSparseSolverData.b, + initialSparseSolverData.C, initialSparseSolverData.l, initialSparseSolverData.u); + } else if (backend == Backend::Dense) + { + proxqpDenseSolver = std::make_unique>(initialSparseSolverData.numberOfVariables, numberOfEqualityConstraints, initialSparseSolverData.numberOfConstraints); + syncSettings(); + proxqpDenseSolver->init(initialSparseSolverData.Hdense, initialSparseSolverData.g, + initialSparseSolverData.Adense, initialSparseSolverData.b, + initialSparseSolverData.Cdense, initialSparseSolverData.l, initialSparseSolverData.u); + } return isInitialized(); } bool ProxqpSolver::isInitialized() { - return static_cast(proxqpSparseSolver); + if (backend == Backend::Sparse) + { + return static_cast(proxqpSparseSolver); + } else if (backend == Backend::Dense) + { + return static_cast(proxqpDenseSolver); + } + return false; } void ProxqpSolver::clearSolver() { proxqpSparseSolver.reset(); + proxqpDenseSolver.reset(); } bool ProxqpSolver::clearSolverVariables() @@ -191,13 +229,18 @@ bool ProxqpSolver::clearSolverVariables() QpSolversEigen::ErrorExitFlag ProxqpSolver::solveProblem() { - if (!proxqpSparseSolver) + if (!isInitialized()) { QpSolversEigen::debugStream() << "QpSolversEigen::ProxqpSolver::solveProblem: solver not initialized." << std::endl; return QpSolversEigen::ErrorExitFlag::WorkspaceNotInitError; } - proxqpSparseSolver->solve(); + if (backend == Backend::Sparse) + { + proxqpSparseSolver->solve(); + } else { + proxqpDenseSolver->solve(); + } return QpSolversEigen::ErrorExitFlag::NoError; @@ -205,28 +248,49 @@ QpSolversEigen::ErrorExitFlag ProxqpSolver::solveProblem() QpSolversEigen::Status ProxqpSolver::getStatus() const { - if (!proxqpSparseSolver) + if (! (static_cast(proxqpSparseSolver) || static_cast(proxqpDenseSolver))) { QpSolversEigen::debugStream() << "QpSolversEigen::ProxqpSolver::solveProblem: solver not initialized." << std::endl; return QpSolversEigen::Status::SolverNotInitialized; } - return this->convertStatus(proxqpSparseSolver->results.info.status); + + if (backend == Backend::Sparse) + { + return this->convertStatus(proxqpSparseSolver->results.info.status); + } else { + return this->convertStatus(proxqpDenseSolver->results.info.status); + } } const double ProxqpSolver::getObjValue() const { - return proxqpSparseSolver->results.info.objValue; + if (backend == Backend::Sparse) + { + return proxqpSparseSolver->results.info.objValue; + } else { + return proxqpDenseSolver->results.info.objValue; + } } const Eigen::Matrix& ProxqpSolver::getSolution() { - return proxqpSparseSolver->results.x; + if (backend == Backend::Sparse) + { + return proxqpSparseSolver->results.x; + } else { + return proxqpDenseSolver->results.x; + } } const Eigen::Matrix& ProxqpSolver::getDualSolution() { - return proxqpSparseSolver->results.z; + if (backend == Backend::Sparse) + { + return proxqpSparseSolver->results.z; + } else { + return proxqpDenseSolver->results.z; + } } bool ProxqpSolver::updateHessianMatrix(const Eigen::SparseMatrix &hessianMatrix) @@ -237,51 +301,103 @@ bool ProxqpSolver::updateHessianMatrix(const Eigen::SparseMatrix &hessia return false; } - proxqpSparseSolver->update(initialSparseSolverData.H, proxsuite::nullopt, + + if (backend == Backend::Sparse) + { + proxqpSparseSolver->update(hessianMatrix, proxsuite::nullopt, proxsuite::nullopt, proxsuite::nullopt, proxsuite::nullopt, proxsuite::nullopt, proxsuite::nullopt); + } else { + initialSparseSolverData.Hdense = hessianMatrix; + proxqpDenseSolver->update(initialSparseSolverData.Hdense, proxsuite::nullopt, + proxsuite::nullopt, proxsuite::nullopt, + proxsuite::nullopt, proxsuite::nullopt, proxsuite::nullopt); + } + return true; } bool ProxqpSolver::updateLinearConstraintsMatrix(const Eigen::SparseMatrix &linearConstraintsMatrix) { - proxqpSparseSolver->update(proxsuite::nullopt, proxsuite::nullopt, + if (!isInitialized()) + { + debugStream() << "QpSolversEigen::ProxqpSolver::updateLinearConstraintsMatrix: solver was not initialized." << std::endl; + return false; + } + + if (backend == Backend::Sparse) + { + proxqpSparseSolver->update(proxsuite::nullopt, proxsuite::nullopt, + proxsuite::nullopt, proxsuite::nullopt, + linearConstraintsMatrix, proxsuite::nullopt, proxsuite::nullopt); + } else { + initialSparseSolverData.Cdense = linearConstraintsMatrix; + proxqpDenseSolver->update(proxsuite::nullopt, proxsuite::nullopt, proxsuite::nullopt, proxsuite::nullopt, - linearConstraintsMatrix, proxsuite::nullopt, proxsuite::nullopt); + initialSparseSolverData.Cdense, proxsuite::nullopt, proxsuite::nullopt); + } return true; } bool ProxqpSolver::updateGradient(const Eigen::Ref>& gradient) { - proxqpSparseSolver->update(proxsuite::nullopt, gradient, + if (backend == Backend::Sparse) + { + proxqpSparseSolver->update(proxsuite::nullopt, gradient, proxsuite::nullopt, proxsuite::nullopt, proxsuite::nullopt, proxsuite::nullopt, proxsuite::nullopt); + } else { + proxqpDenseSolver->update(proxsuite::nullopt, gradient, + proxsuite::nullopt, proxsuite::nullopt, + proxsuite::nullopt, proxsuite::nullopt, proxsuite::nullopt); + } return true; } bool ProxqpSolver::updateLowerBound(const Eigen::Ref>& lowerBound) { - proxqpSparseSolver->update(proxsuite::nullopt, proxsuite::nullopt, - proxsuite::nullopt, proxsuite::nullopt, - proxsuite::nullopt, lowerBound, proxsuite::nullopt); + if (backend == Backend::Sparse) + { + proxqpSparseSolver->update(proxsuite::nullopt, proxsuite::nullopt, + proxsuite::nullopt, proxsuite::nullopt, + proxsuite::nullopt, lowerBound, proxsuite::nullopt); + } else { + proxqpDenseSolver->update(proxsuite::nullopt, proxsuite::nullopt, + proxsuite::nullopt, proxsuite::nullopt, + proxsuite::nullopt, lowerBound, proxsuite::nullopt); + } return true; } bool ProxqpSolver::updateUpperBound(const Eigen::Ref>& upperBound) { - proxqpSparseSolver->update(proxsuite::nullopt, proxsuite::nullopt, + if (backend == Backend::Sparse) + { + proxqpSparseSolver->update(proxsuite::nullopt, proxsuite::nullopt, proxsuite::nullopt, proxsuite::nullopt, proxsuite::nullopt, proxsuite::nullopt, upperBound); + } else { + proxqpDenseSolver->update(proxsuite::nullopt, proxsuite::nullopt, + proxsuite::nullopt, proxsuite::nullopt, + proxsuite::nullopt, proxsuite::nullopt, upperBound); + } return true; } bool ProxqpSolver::updateBounds(const Eigen::Ref>& lowerBound, const Eigen::Ref>& upperBound) { - proxqpSparseSolver->update(proxsuite::nullopt, proxsuite::nullopt, - proxsuite::nullopt, proxsuite::nullopt, - proxsuite::nullopt, lowerBound, upperBound); + if (backend == Backend::Sparse) + { + proxqpSparseSolver->update(proxsuite::nullopt, proxsuite::nullopt, + proxsuite::nullopt, proxsuite::nullopt, + proxsuite::nullopt, lowerBound, upperBound); + } else { + proxqpDenseSolver->update(proxsuite::nullopt, proxsuite::nullopt, + proxsuite::nullopt, proxsuite::nullopt, + proxsuite::nullopt, lowerBound, upperBound); + } return true; } @@ -299,7 +415,12 @@ void ProxqpSolver::clearLinearConstraintsMatrix() bool ProxqpSolver::setHessianMatrix(const Eigen::SparseMatrix& hessianMatrix) { - initialSparseSolverData.H = hessianMatrix; + if (backend == Backend::Sparse) + { + initialSparseSolverData.H = hessianMatrix; + } else { + initialSparseSolverData.Hdense = hessianMatrix; + } initialSparseSolverData.isHessianSet = true; return true; } @@ -319,7 +440,13 @@ Eigen::Matrix ProxqpSolver::getGradient() bool ProxqpSolver::setLinearConstraintsMatrix(const Eigen::SparseMatrix& linearConstraintsMatrix) { - initialSparseSolverData.C = linearConstraintsMatrix; + if (backend == Backend::Sparse) + { + initialSparseSolverData.C = linearConstraintsMatrix; + } else { + initialSparseSolverData.Cdense = linearConstraintsMatrix; + } + initialSparseSolverData.isLinearConstraintsSet = true; return true; } diff --git a/tests/MPCUpdateMatricesTest.cpp b/tests/MPCUpdateMatricesTest.cpp index d119726..d06f759 100644 --- a/tests/MPCUpdateMatricesTest.cpp +++ b/tests/MPCUpdateMatricesTest.cpp @@ -301,19 +301,25 @@ TEST_CASE("MPCTest Update matrices") setDynamicsMatrices(a, b, c, i * T); // update the constraint bound + std::cerr << "=======> Update hessian " << std::endl; REQUIRE(updateHessianMatrix(solver, Q, R, mpcWindow, i)); + std::cerr << "=======> Update linear " << std::endl; REQUIRE(updateLinearConstraintsMatrix(solver, mpcWindow, i)); castMPCToQPGradient(Q, yRef, mpcWindow, i, gradient); + std::cerr << "=======> Update gradient " << std::endl; REQUIRE(solver.updateGradient(gradient)); updateConstraintVectors(x0, lowerBound, upperBound); + std::cerr << "=======> updateBoundsn " << std::endl; REQUIRE(solver.updateBounds(lowerBound, upperBound)); // solve the QP problem + std::cerr << "=======> solveProblem " << std::endl; REQUIRE(solver.solveProblem() == QpSolversEigen::ErrorExitFlag::NoError); // get the controller input + std::cerr << "=======> get solution " << std::endl; QPSolution = solver.getSolution(); ctr = QPSolution.block(2 * (mpcWindow + 1), 0, 1, 1);