Quirks in qpOASES
qpOASES (paper, code, manual) is a solver for quadratic programs (QPs) that is designed to be particularly efficient for solving model predictive control problems, which typically involve solving a sequence of QPs with very similar parameters. I've had success using it for my research on control for mobile manipulation for a while now. In this post, however, I'll describe three issues I've run into with qpOASES that have caused me some confusion.
1 Not a number
The first issue was the result of a bug in my own code, and I offer it as a
cautionary tale. It turns out that the qpOASES solver happily accepts matrices
with NaN
(not a number) values, and produces a solution vector saturated at
one of the provided bounds and an optimal objective value of NaN
. There is no
error or other indication that the input is malformed in this way, so I'd
recommend checking for a NaN
objective value manually and raising an error so
you know that your code has a bug to fix. In my case, I had an unintentional
division by zero, and the result was some very unexpected control commands.
2 Working set recalculations
The next issue has to do with the number of working set recalculations (WSRs)
performed by the solver, which is specified via the argument int_t& nWSR
.
Notice we're actually passing a reference int_t&
, which is what tripped
me up. The solver modifies this value to be the number of WSRs it actually
performed. This behaviour is documented in the user manual, but I've still
ended up confused when the solver initially succeeds but on subsequent solves
begins to fail with the message
ERROR: Maximum number of working set recalculations performed
This occurred because I was reusing the same nWSR
variable for multiple
calls to the solver, expecting it to be treated as constant. When a QP is
easy for the solver, such as after a hotstart, the required number of WSRs may
be very few or even zero. If one call to the solver sets nWSR = 0
, then a
subsequent call will fail if it needs any WSRs at all. To avoid the problem, I
just make a new int_t
for each call to the solver.
3 Equality constraints
The final issue has to do with the solver itself. For some reason it will refuse to solve certain equality-constrained problems with its default settings, as discussed in this GitHub issue. For example, I had a QP with an equality constraint , where , that I knew to be feasible. However, qpOASES produced the error
ERROR: Division by zero
->ERROR: Abnormal termination due to TQ factorisation
->ERROR: Determination of step direction failed
->ERROR: Abnormal termination due to TQ factorisation
->ERROR: Initialisation failed! QP could not be solved!
As I commented in the GitHub issue linked above, the solution is to set the solver to "reliable" mode:
qpOASES::Options options;
options.setToReliable();
// qp is my QProblem object
qp.setOptions(options);
For some reason, qpOASES is not able to handle all feasible problems with the default options, but at least the reliable options appear to live up their name.
Conclusion
While the issues I've described have caused me a couple of headaches, qpOASES has served me well: it is fast, free, and generally easy to use. Unfortunately, qpOASES no longer appears to be maintained, and there are many GitHub issues that have gone unresolved for a long while. I suspect it is time to at least consider switching to an alternative like OSQP.