18 #ifndef __solvers_osqp_hpp__ 19 #define __solvers_osqp_hpp__ 22 #include "OsqpEigen/OsqpEigen.h" 23 #include <Eigen/Sparse> 26 #define START_PROFILER_OSQP(x) START_PROFILER(x) 27 #define STOP_PROFILER_OSQP(x) STOP_PROFILER(x) 29 #define START_PROFILER_OSQP(x) 30 #define STOP_PROFILER_OSQP(x) 40 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
51 void resize(
unsigned int n,
unsigned int neq,
unsigned int nin);
54 void retrieveQPData(
const HQPData& problemData,
55 const bool hessianRegularization =
false);
64 double getObjectiveValue();
67 bool setMaximumIterations(
unsigned int maxIter);
69 void setSigma(
double sigma);
70 void setAlpha(
double alpha);
71 void setRho(
double rho);
72 void setEpsilonAbsolute(
double epsAbs);
73 void setEpsilonRelative(
double epsRel);
74 void setVerbose(
bool isVerbose =
false);
77 void sendMsg(
const std::string&
s);
101 #endif // ifndef __solvers_osqp_hpp__ Eigen::Ref< Vector > RefVector
const Eigen::Ref< const Matrix > ConstRefMatrix
QPDataTpl< double > m_qpData
number of variables
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > Matrix
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Matrix Matrix
math::ConstRefMatrix ConstRefMatrix
double m_hessian_regularization
unsigned int m_nin
number of equality constraints
const QPData getQPData() const
const Eigen::Ref< const Vector > ConstRefVector
math::RefVector RefVector
Mat & solve(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< Mat > &y)
OsqpEigen::Solver m_solver
unsigned int m_n
number of inequality constraints
math::ConstRefVector ConstRefVector
Abstract interface for a Quadratic Program (HQP) solver.