18 #ifndef __invdyn_solvers_hqp_eiquadprog_rt_hpp__ 19 #define __invdyn_solvers_hqp_eiquadprog_rt_hpp__ 32 template <
int nVars,
int nEqCon,
int nIneqCon>
35 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
45 void resize(
unsigned int n,
unsigned int neq,
unsigned int nin);
60 double getObjectiveValue();
63 bool setMaximumIterations(
unsigned int maxIter);
66 void sendMsg(
const std::string&
s);
95 #endif // ifndef __invdyn_solvers_hqp_eiquadprog_rt_hpp__ Eigen::Ref< Vector > RefVector
const Eigen::Ref< const Matrix > ConstRefMatrix
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > Matrix
RtVectorX< 2 *nIneqCon >::d m_ci0
twice the rows because inequality constraints are bilateral
Eigen::VectorXi m_activeSet
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
RtMatrixX< nEqCon, nVars >::d m_CE
class TSID_DLLAPI SolverHQuadProgRT
math::ConstRefMatrix ConstRefMatrix
RtVectorX< nVars >::d m_g
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Matrix Matrix
int m_nin
number of equality constraints
RtVectorX< nEqCon >::d m_ce0
int m_n
number of inequality constraints
int m_activeSetSize
vector containing the indexes of the active inequalities
RtMatrixX< nVars, nVars >::d m_H
const Eigen::Ref< const Vector > ConstRefVector
eiquadprog::solvers::RtEiquadprog< nVars, nEqCon, 2 *nIneqCon > m_solver
RtMatrixX< 2 *nIneqCon, nVars >::d m_CI
Mat & solve(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< Mat > &y)
double m_hessian_regularization
void retrieveQPData(const HQPData &, const bool)
math::ConstRefVector ConstRefVector
math::RefVector RefVector
Abstract interface for a Quadratic Program (HQP) solver.