solver-proxqp.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2022 INRIA
3 //
4 // This file is part of tsid
5 // tsid is free software: you can redistribute it
6 // and/or modify it under the terms of the GNU Lesser General Public
7 // License as published by the Free Software Foundation, either version
8 // 3 of the License, or (at your option) any later version.
9 // tsid is distributed in the hope that it will be
10 // useful, but WITHOUT ANY WARRANTY; without even the implied warranty
11 // of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
12 // General Lesser Public License for more details. You should have
13 // received a copy of the GNU Lesser General Public License along with
14 // tsid If not, see
15 // <http://www.gnu.org/licenses/>.
16 //
17 
19 #include "tsid/math/utils.hpp"
21 
22 namespace tsid {
23 namespace solvers {
24 
25 using namespace math;
26 SolverProxQP::SolverProxQP(const std::string& name)
28  m_hessian_regularization(DEFAULT_HESSIAN_REGULARIZATION),
29  m_solver(1, 0, 0) // dim of primal var needs to be strictly positiv
30 {
31  m_n = 0;
32  m_neq = 0;
33  m_nin = 0;
34  m_rho = 1e-6;
35  m_muIn = 1e-1;
36  m_muEq = 1e-3;
37  m_epsAbs = 1e-5;
38  m_epsRel = 0.;
39  m_isVerbose = false;
40 }
41 
42 void SolverProxQP::sendMsg(const std::string& s) {
43  std::cout << "[SolverProxQP." << m_name << "] " << s << std::endl;
44 }
45 
46 void SolverProxQP::resize(unsigned int n, unsigned int neq, unsigned int nin) {
47  const bool resizeVar = n != m_n;
48  const bool resizeEq = (resizeVar || neq != m_neq);
49  const bool resizeIn = (resizeVar || nin != m_nin);
50 
51  if (resizeEq) {
52 #ifndef NDEBUG
53  sendMsg("Resizing equality constraints from " + toString(m_neq) + " to " +
54  toString(neq));
55 #endif
56  m_qpData.CE.resize(neq, n);
57  m_qpData.ce0.resize(neq);
58  }
59  if (resizeIn) {
60 #ifndef NDEBUG
61  sendMsg("Resizing inequality constraints from " + toString(m_nin) + " to " +
62  toString(nin));
63 #endif
64  m_qpData.CI.resize(nin, n);
65  m_qpData.ci_lb.resize(nin);
66  m_qpData.ci_ub.resize(nin);
67  }
68  if (resizeVar) {
69 #ifndef NDEBUG
70  sendMsg("Resizing Hessian from " + toString(m_n) + " to " + toString(n));
71 #endif
72  m_qpData.H.resize(n, n);
73  m_qpData.g.resize(n);
74  m_output.x.resize(n);
75  }
76 
77  m_n = n;
78  m_neq = neq;
79  m_nin = nin;
80 
81  if (resizeVar || resizeEq || resizeIn) {
82  m_solver = dense::QP<double>(m_n, m_neq, m_nin);
86  setRho(m_rho);
90 #ifndef NDEBUG
91  setVerbose(true);
92 #endif
93  }
94 }
95 
96 void SolverProxQP::retrieveQPData(const HQPData& problemData,
97  const bool hessianRegularization) {
98  if (problemData.size() > 2) {
100  false, "Solver not implemented for more than 2 hierarchical levels.");
101  }
102 
103  // Compute the constraint matrix sizes
104  unsigned int neq = 0, nin = 0;
105  const ConstraintLevel& cl0 = problemData[0];
106 
107  if (cl0.size() > 0) {
108  const unsigned int n = cl0[0].second->cols();
109  for (ConstraintLevel::const_iterator it = cl0.begin(); it != cl0.end();
110  it++) {
111  auto constr = it->second;
112  assert(n == constr->cols());
113  if (constr->isEquality())
114  neq += constr->rows();
115  else
116  nin += constr->rows();
117  }
118  // If necessary, resize the constraint matrices
119  resize(n, neq, nin);
120 
121  unsigned int i_eq = 0, i_in = 0;
122  for (ConstraintLevel::const_iterator it = cl0.begin(); it != cl0.end();
123  it++) {
124  auto constr = it->second;
125  if (constr->isEquality()) {
126  m_qpData.CE.middleRows(i_eq, constr->rows()) = constr->matrix();
127  m_qpData.ce0.segment(i_eq, constr->rows()) = constr->vector();
128  i_eq += constr->rows();
129  } else if (constr->isInequality()) {
130  m_qpData.CI.middleRows(i_in, constr->rows()) = constr->matrix();
131  m_qpData.ci_lb.segment(i_in, constr->rows()) = constr->lowerBound();
132  m_qpData.ci_ub.segment(i_in, constr->rows()) = constr->upperBound();
133  i_in += constr->rows();
134  } else if (constr->isBound()) {
135  m_qpData.CI.middleRows(i_in, constr->rows()).setIdentity();
136  m_qpData.ci_lb.segment(i_in, constr->rows()) = constr->lowerBound();
137  m_qpData.ci_ub.segment(i_in, constr->rows()) = constr->upperBound();
138  i_in += constr->rows();
139  }
140  }
141  } else {
142  resize(m_n, neq, nin);
143  }
144 
146 
147  // Compute the cost
148  if (problemData.size() > 1) {
149  const ConstraintLevel& cl1 = problemData[1];
150  m_qpData.H.setZero();
151  m_qpData.g.setZero();
152 
153  for (ConstraintLevel::const_iterator it = cl1.begin(); it != cl1.end();
154  it++) {
155  const double& w = it->first;
156  auto constr = it->second;
157  if (!constr->isEquality())
159  false, "Inequalities in the cost function are not implemented yet");
160 
162  m_qpData.H.noalias() +=
163  w * constr->matrix().transpose() * constr->matrix();
165 
166  m_qpData.g.noalias() -=
167  w * constr->matrix().transpose() * constr->vector();
168  }
169 
170  if (hessianRegularization) {
172  m_qpData.H.diagonal().array() += m_hessian_regularization;
173  }
174  }
175 }
176 
177 const HQPOutput& SolverProxQP::solve(const HQPData& problemData) {
178  SolverProxQP::retrieveQPData(problemData);
179 
180  START_PROFILER_PROXQP("PROFILE_PROXQP_SOLUTION");
181  // min 0.5 * x^T H x + g^T x
182  // s.t.
183  // CE x + ce0 = 0
184  // ci_lb <= CI x <= ci_ub
185 
187 
190 
191  m_solver.solve();
192  STOP_PROFILER_PROXQP("PROFILE_PROXQP_SOLUTION");
193 
194  QPSolverOutput status = m_solver.results.info.status;
195 
196  if (status == QPSolverOutput::PROXQP_SOLVED) {
197  m_output.x = m_solver.results.x;
199  m_output.lambda = m_solver.results.y;
200  m_output.iterations = int(m_solver.results.info.iter);
201  m_output.activeSet.setZero();
202 
203 #ifndef NDEBUG
204  const Vector& x = m_solver.results.x;
205 
206  const ConstraintLevel& cl0 = problemData[0];
207 
208  if (cl0.size() > 0) {
209  for (ConstraintLevel::const_iterator it = cl0.begin(); it != cl0.end();
210  it++) {
211  auto constr = it->second;
212  if (constr->checkConstraint(x) == false) {
213  if (constr->isEquality()) {
214  sendMsg("Equality " + constr->name() + " violated: " +
215  toString((constr->matrix() * x - constr->vector()).norm()));
216  } else if (constr->isInequality()) {
217  sendMsg(
218  "Inequality " + constr->name() + " violated: " +
219  toString(
220  (constr->matrix() * x - constr->lowerBound()).minCoeff()) +
221  "\n" +
222  toString(
223  (constr->upperBound() - constr->matrix() * x).minCoeff()));
224  } else if (constr->isBound()) {
225  sendMsg("Bound " + constr->name() + " violated: " +
226  toString((x - constr->lowerBound()).minCoeff()) + "\n" +
227  toString((constr->upperBound() - x).minCoeff()));
228  }
229  }
230  }
231  }
232 #endif
233  } else if (status == QPSolverOutput::PROXQP_PRIMAL_INFEASIBLE)
235  else if (status == QPSolverOutput::PROXQP_MAX_ITER_REACHED)
237  else if (status == QPSolverOutput::PROXQP_DUAL_INFEASIBLE)
239 
240  return m_output;
241 }
242 
244  return m_solver.results.info.objValue;
245 }
246 
247 bool SolverProxQP::setMaximumIterations(unsigned int maxIter) {
249  m_solver.settings.max_iter = maxIter;
250  return true;
251 }
252 
253 void SolverProxQP::setMuInequality(double muIn) {
254  m_muIn = muIn;
255  m_solver.settings.default_mu_in = m_muIn;
256 }
257 void SolverProxQP::setMuEquality(double muEq) {
258  m_muEq = muEq;
259  m_solver.settings.default_mu_eq = m_muEq;
260 }
261 void SolverProxQP::setRho(double rho) {
262  m_rho = rho;
263  m_solver.settings.default_rho = m_rho;
264 }
265 void SolverProxQP::setEpsilonAbsolute(double epsAbs) {
266  m_epsAbs = epsAbs;
267  m_solver.settings.eps_abs = m_epsAbs;
268 }
269 void SolverProxQP::setEpsilonRelative(double epsRel) {
270  m_epsRel = epsRel;
271  m_solver.settings.eps_rel = m_epsRel;
272 }
273 void SolverProxQP::setVerbose(bool isVerbose) {
274  m_isVerbose = isVerbose;
275  m_solver.settings.verbose = m_isVerbose;
276 }
277 } // namespace solvers
278 } // namespace tsid
DEFAULT_HESSIAN_REGULARIZATION
#define DEFAULT_HESSIAN_REGULARIZATION
Definition: solvers/fwd.hpp:28
tsid::solvers::SolverProxQP::getObjectiveValue
double getObjectiveValue() override
Definition: solver-proxqp.cpp:243
tsid::solvers::QPDataTpl::CI
Matrix CI
Definition: solver-qpData.hpp:40
tsid::solvers::SolverProxQP::resize
void resize(unsigned int n, unsigned int neq, unsigned int nin) override
Definition: solver-proxqp.cpp:46
tsid::solvers::QPDataBaseTpl::g
Vector g
Definition: solver-qpData.hpp:30
EIGEN_MALLOC_ALLOWED
#define EIGEN_MALLOC_ALLOWED
Definition: math/fwd.hpp:27
tsid::solvers::HQPOutput::activeSet
VectorXi activeSet
Lagrange multipliers.
Definition: solver-HQP-output.hpp:39
tsid::solvers::SolverHQPBase::m_output
HQPOutput m_output
Definition: solver-HQP-base.hpp:84
tsid::solvers::QPDataBaseTpl::H
Matrix H
Definition: solver-qpData.hpp:29
PINOCCHIO_CHECK_INPUT_ARGUMENT
#define PINOCCHIO_CHECK_INPUT_ARGUMENT(...)
STOP_PROFILER_PROXQP
#define STOP_PROFILER_PROXQP(x)
Definition: solvers/solver-proxqp.hpp:31
START_PROFILER_PROXQP
#define START_PROFILER_PROXQP(x)
Definition: solvers/solver-proxqp.hpp:30
tsid::solvers::SolverProxQP::m_muEq
double m_muEq
Definition: solvers/solver-proxqp.hpp:96
tsid::solvers::QPDataTpl::ci_ub
Vector ci_ub
Definition: solver-qpData.hpp:42
tsid::solvers::SolverProxQP::m_solver
dense::QP< double > m_solver
Definition: solvers/solver-proxqp.hpp:86
tsid::solvers::SolverProxQP::m_n
unsigned int m_n
number of inequality constraints
Definition: solvers/solver-proxqp.hpp:90
test_Solvers.neq
int neq
Definition: test_Solvers.py:13
tsid::solvers::QPDataTpl::ci_lb
Vector ci_lb
Definition: solver-qpData.hpp:41
tsid::solvers::ConstraintLevel
pinocchio::container::aligned_vector< aligned_pair< double, std::shared_ptr< math::ConstraintBase > > > ConstraintLevel
Definition: solvers/fwd.hpp:95
utils.hpp
tsid::solvers::SolverProxQP::m_rho
double m_rho
Definition: solvers/solver-proxqp.hpp:94
tsid::solvers::SolverProxQP::SolverProxQP
SolverProxQP(const std::string &name)
Definition: solver-proxqp.cpp:26
tsid::solvers::SolverHQPBase::m_name
std::string m_name
Definition: solver-HQP-base.hpp:80
tsid::solvers::SolverProxQP::m_nin
unsigned int m_nin
number of equality constraints
Definition: solvers/solver-proxqp.hpp:89
tsid::solvers::HQPOutput::lambda
Vector lambda
solution
Definition: solver-HQP-output.hpp:38
tsid::solvers::QPDataBaseTpl::CE
Matrix CE
Definition: solver-qpData.hpp:31
tsid::solvers::SolverHQPBase::m_maxIter
unsigned int m_maxIter
Definition: solver-HQP-base.hpp:82
tsid::solvers::SolverProxQP::setMaximumIterations
bool setMaximumIterations(unsigned int maxIter) override
Definition: solver-proxqp.cpp:247
tsid::solvers::SolverProxQP::setMuEquality
void setMuEquality(double muEq)
Definition: solver-proxqp.cpp:257
tsid::solvers::SolverProxQP::setRho
void setRho(double rho)
Definition: solver-proxqp.cpp:261
tsid::solvers::SolverProxQP::m_hessian_regularization
double m_hessian_regularization
Definition: solvers/solver-proxqp.hpp:84
tsid::solvers::HQPOutput
Definition: solver-HQP-output.hpp:29
tsid::solvers::SolverProxQP::sendMsg
void sendMsg(const std::string &s)
Definition: solver-proxqp.cpp:42
tsid::solvers::SolverProxQP::retrieveQPData
void retrieveQPData(const HQPData &problemData, const bool hessianRegularization=false) override
Definition: solver-proxqp.cpp:96
tsid::solvers::SolverHQPBase
Abstract interface for a Quadratic Program (HQP) solver.
Definition: solver-HQP-base.hpp:34
test_Solvers.nin
int nin
Definition: test_Solvers.py:14
tsid::solvers::SolverProxQP::solve
const HQPOutput & solve(const HQPData &problemData) override
Definition: solver-proxqp.cpp:177
tsid::solvers::SolverProxQP::m_epsRel
double m_epsRel
Definition: solvers/solver-proxqp.hpp:98
tsid::solvers::QPDataBaseTpl::ce0
Vector ce0
Definition: solver-qpData.hpp:32
setup.name
name
Definition: setup.in.py:179
w
w
stop-watch.hpp
HQP_STATUS_OPTIMAL
HQP_STATUS_OPTIMAL
Definition: solvers/fwd.hpp:63
tsid::solvers::SolverProxQP::setMuInequality
void setMuInequality(double muIn)
Definition: solver-proxqp.cpp:253
tsid::solvers::SolverProxQP::setEpsilonRelative
void setEpsilonRelative(double epsRel)
Definition: solver-proxqp.cpp:269
it
int it
tsid::solvers::SolverProxQP::setEpsilonAbsolute
void setEpsilonAbsolute(double epsAbs)
Definition: solver-proxqp.cpp:265
HQP_STATUS_MAX_ITER_REACHED
HQP_STATUS_MAX_ITER_REACHED
Definition: solvers/fwd.hpp:66
tsid::solvers::SolverProxQP::m_neq
unsigned int m_neq
Definition: solvers/solver-proxqp.hpp:88
tsid::solvers::SolverProxQP::m_qpData
QPDataTpl< double > m_qpData
number of variables
Definition: solvers/solver-proxqp.hpp:92
tsid::solvers::SolverHQPBase::setMaximumIterations
virtual bool setMaximumIterations(unsigned int maxIter)
Definition: solver-HQP-base.cpp:36
tsid
Definition: bindings/python/constraint/constraint-bound.cpp:21
HQP_STATUS_INFEASIBLE
HQP_STATUS_INFEASIBLE
Definition: solvers/fwd.hpp:64
tsid::solvers::HQPOutput::x
Vector x
solver status
Definition: solver-HQP-output.hpp:37
test_Formulation.s
s
Definition: test_Formulation.py:115
test_Solvers.x
x
Definition: test_Solvers.py:67
tsid::solvers::SolverProxQP::m_isVerbose
bool m_isVerbose
Definition: solvers/solver-proxqp.hpp:99
tsid::solvers::SolverProxQP::setVerbose
void setVerbose(bool isVerbose=false)
Definition: solver-proxqp.cpp:273
tsid::solvers::SolverProxQP::m_muIn
double m_muIn
Definition: solvers/solver-proxqp.hpp:95
tsid::solvers::SolverProxQP::Vector
math::Vector Vector
Definition: solvers/solver-proxqp.hpp:47
tsid::solvers::HQPData
pinocchio::container::aligned_vector< ConstraintLevel > HQPData
Definition: solvers/fwd.hpp:99
tsid::solvers::SolverProxQP::m_epsAbs
double m_epsAbs
Definition: solvers/solver-proxqp.hpp:97
tsid::toString
std::string toString(const T &v)
Definition: math/utils.hpp:39
tsid::solvers::HQPOutput::iterations
int iterations
indexes of active inequalities
Definition: solver-HQP-output.hpp:40
n
Vec3f n
solver-proxqp.hpp
tsid::solvers::HQPOutput::status
HQPStatus status
Definition: solver-HQP-output.hpp:36
rho
int rho
EIGEN_MALLOC_NOT_ALLOWED
#define EIGEN_MALLOC_NOT_ALLOWED
Definition: math/fwd.hpp:28


tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Thu Apr 3 2025 02:47:16