18 #ifndef __solvers_proxqp_hpp__ 19 #define __solvers_proxqp_hpp__ 22 #include <proxsuite/proxqp/dense/dense.hpp> 23 #include <proxsuite/proxqp/sparse/sparse.hpp> 24 #include <proxsuite/proxqp/results.hpp> 27 #define START_PROFILER_PROXQP(x) START_PROFILER(x) 28 #define STOP_PROFILER_PROXQP(x) STOP_PROFILER(x) 30 #define START_PROFILER_PROXQP(x) 31 #define STOP_PROFILER_PROXQP(x) 44 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
54 void resize(
unsigned int n,
unsigned int neq,
unsigned int nin);
57 void retrieveQPData(
const HQPData& problemData,
58 const bool hessianRegularization =
false);
68 double getObjectiveValue();
71 bool setMaximumIterations(
unsigned int maxIter);
73 void setMuInequality(
double muIn);
74 void setMuEquality(
double muEq);
75 void setRho(
double rho);
76 void setEpsilonAbsolute(
double epsAbs);
77 void setEpsilonRelative(
double epsRel);
78 void setVerbose(
bool isVerbose =
false);
81 void sendMsg(
const std::string&
s);
104 #endif // ifndef __solvers_proxqp_hpp__ Eigen::Ref< Vector > RefVector
const Eigen::Ref< const Matrix > ConstRefMatrix
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > Matrix
unsigned int m_n
number of inequality constraints
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Matrix Matrix
math::RefVector RefVector
math::ConstRefMatrix ConstRefMatrix
QPDataTpl< double > m_qpData
number of variables
const Eigen::Ref< const Vector > ConstRefVector
math::ConstRefVector ConstRefVector
double m_hessian_regularization
dense::QP< double > m_solver
Mat & solve(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< Mat > &y)
const QPData getQPData() const
unsigned int m_nin
number of equality constraints
Abstract interface for a Quadratic Program (HQP) solver.