18 #ifndef __invdyn_solvers_hqp_eiquadprog_fast_hpp__ 19 #define __invdyn_solvers_hqp_eiquadprog_fast_hpp__ 21 #include "tsid/deprecated.hh" 32 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
42 void resize(
unsigned int n,
unsigned int neq,
unsigned int nin);
49 void retrieveQPData(
const HQPData& problemData,
50 const bool hessianRegularization =
true);
56 double getObjectiveValue();
59 bool setMaximumIterations(
unsigned int maxIter);
62 void sendMsg(
const std::string&
s);
67 TSID_DEPRECATED Matrix
m_H;
68 TSID_DEPRECATED Vector
m_g;
69 TSID_DEPRECATED Matrix
m_CE;
71 TSID_DEPRECATED Matrix
90 #endif // ifndef __invdyn_solvers_hqp_eiquadprog_fast_hpp__ Eigen::Ref< Vector > RefVector
const Eigen::Ref< const Matrix > ConstRefMatrix
int m_activeSetSize
vector containing the indexes of the active inequalities
Eigen::VectorXi m_activeSet
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > Matrix
TSID_DEPRECATED Vector m_g
math::ConstRefVector ConstRefVector
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
const QPDataQuadProg getQPData() const
TSID_DEPRECATED Matrix m_CI
double m_hessian_regularization
QPDataQuadProgTpl< double > m_qpData
number of variables
TSID_DEPRECATED Vector m_ce0
eiquadprog::solvers::EiquadprogFast m_solver
TSID_DEPRECATED Matrix m_CE
TSID_DEPRECATED Matrix m_H
TSID_DEPRECATED Vector m_ci0
twice the rows because inequality constraints are bilateral
math::ConstRefMatrix ConstRefMatrix
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)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Matrix Matrix
unsigned int m_n
number of inequality constraints
unsigned int m_nin
number of equality constraints
Abstract interface for a Quadratic Program (HQP) solver.