25 using namespace Eigen;
27 SolverHQuadProg::SolverHQuadProg(
const std::string&
name)
36 std::cout <<
"[SolverHQuadProg." <<
m_name <<
"] " << s << std::endl;
41 const bool resizeVar = n !=
m_n;
42 const bool resizeEq = (resizeVar || neq !=
m_neq);
43 const bool resizeIn = (resizeVar || nin !=
m_nin);
77 if (problemData.size() > 2) {
79 false,
"Solver not implemented for more than 2 hierarchical levels.");
83 unsigned int neq = 0,
nin = 0;
86 const unsigned int n = cl0[0].second->cols();
87 for (ConstraintLevel::const_iterator it = cl0.begin(); it != cl0.end();
89 auto constr = it->second;
90 assert(n == constr->cols());
91 if (constr->isEquality())
92 neq += constr->rows();
94 nin += constr->rows();
99 int i_eq = 0, i_in = 0;
100 for (ConstraintLevel::const_iterator it = cl0.begin(); it != cl0.end();
102 auto constr = it->second;
103 if (constr->isEquality()) {
104 m_qpData.
CE.middleRows(i_eq, constr->rows()) = constr->matrix();
105 m_qpData.
ce0.segment(i_eq, constr->rows()) = -constr->vector();
106 i_eq += constr->rows();
107 }
else if (constr->isInequality()) {
108 m_qpData.
CI.middleRows(i_in, constr->rows()) = constr->matrix();
109 m_qpData.
ci0.segment(i_in, constr->rows()) = -constr->lowerBound();
110 i_in += constr->rows();
111 m_qpData.
CI.middleRows(i_in, constr->rows()) = -constr->matrix();
112 m_qpData.
ci0.segment(i_in, constr->rows()) = constr->upperBound();
113 i_in += constr->rows();
114 }
else if (constr->isBound()) {
115 m_qpData.
CI.middleRows(i_in, constr->rows()).setIdentity();
116 m_qpData.
ci0.segment(i_in, constr->rows()) = -constr->lowerBound();
117 i_in += constr->rows();
118 m_qpData.
CI.middleRows(i_in, constr->rows()) =
119 -Matrix::Identity(
m_n,
m_n);
120 m_qpData.
ci0.segment(i_in, constr->rows()) = constr->upperBound();
121 i_in += constr->rows();
127 if (problemData.size() > 1) {
131 for (ConstraintLevel::const_iterator it = cl1.begin(); it != cl1.end();
133 const double&
w = it->first;
134 auto constr = it->second;
135 if (!constr->isEquality())
137 false,
"Inequalities in the cost function are not implemented yet");
139 m_qpData.
H += w * constr->matrix().transpose() * constr->matrix();
140 m_qpData.
g -= w * (constr->matrix().transpose() * constr->vector());
145 #ifdef ELIMINATE_EQUALITY_CONSTRAINTS 151 m_ZT_H_Z.resize(
m_n - r,
m_n - r);
175 const Index rank =
m_qpData.CE_dec.rank();
177 for (Index k = 0; k < rank; ++k) {
178 if (k != rank - 1) ZT.row(k).swap(ZT.row(rank - 1));
179 ZT.middleRows(rank - 1,
m_n - rank + 1)
180 .applyHouseholderOnTheLeft(
181 m_qpData.CE_dec.matrixQTZ().row(k).tail(
m_n - rank).adjoint(),
182 m_qpData.CE_dec.zCoeffs()(k), &temp(0));
183 if (k != rank - 1) ZT.row(k).swap(ZT.row(rank - 1));
200 for (ConstraintLevel::const_iterator it = cl1.begin(); it != cl1.end();
202 const double&
w = it->first;
203 auto constr = it->second;
204 if (!constr->isEquality())
206 false,
"Inequalities in the cost function are not implemented yet");
208 AZ.noalias() = constr->matrix() * Z.rightCols(
m_n - r);
209 m_ZT_H_Z += w * AZ.transpose() * AZ;
240 if (
m_objValue == std::numeric_limits<double>::infinity())
247 if (cl0.size() > 0) {
248 for (ConstraintLevel::const_iterator it = cl0.begin(); it != cl0.end();
250 auto constr = it->second;
251 if (constr->checkConstraint(
x) ==
false) {
252 if (constr->isEquality()) {
253 sendMsg(
"Equality " + constr->name() +
" violated: " +
254 toString((constr->matrix() *
x - constr->vector()).norm()));
255 }
else if (constr->isInequality()) {
257 "Inequality " + constr->name() +
" violated: " +
259 (constr->matrix() *
x - constr->lowerBound()).minCoeff()) +
262 (constr->upperBound() - constr->matrix() *
x).minCoeff()));
263 }
else if (constr->isBound()) {
264 sendMsg(
"Bound " + constr->name() +
" violated: " +
265 toString((
x - constr->lowerBound()).minCoeff()) +
"\n" +
266 toString((constr->upperBound() -
x).minCoeff()));
#define STOP_PROFILER(name)
tsid::math::Index m_activeSetSize
vector containing the indexes of the active inequalities
double m_hessian_regularization
#define START_PROFILER(name)
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > Matrix
std::string toString(const T &v)
#define DEFAULT_HESSIAN_REGULARIZATION
void retrieveQPData(const HQPData &problemData, const bool hessianRegularization=true)
unsigned int m_n
number of inequality constraints
void sendMsg(const std::string &s)
unsigned int m_nin
number of equality constraints
Eigen::VectorXi m_activeSet
QPDataQuadProgTpl< double > m_qpData
number of variables
void resize(unsigned int n, unsigned int neq, unsigned int nin)
double solve_quadprog(MatrixXd &G, VectorXd &g0, const MatrixXd &CE, const VectorXd &ce0, const MatrixXd &CI, const VectorXd &ci0, VectorXd &x, VectorXi &activeSet, size_t &activeSetSize)
const HQPOutput & solve(const HQPData &problemData)
#define PINOCCHIO_CHECK_INPUT_ARGUMENT(...)
double getObjectiveValue()
Abstract interface for a Quadratic Program (HQP) solver.