I am using the ocp_qp_interface and wondering how to properly warm start the solver.
I have the ocp_qp_out, ocp_qp_in and qp_solver_ prepared and in every MPC cycle I just update the target, initial state, update the linearization of the A and B matrix and then solve the problem:
int acados_return = ocp_qp_solve(qp_solver_, qp_in_, qp_out_)
Is there a way in the next control cycle, to reuse the old prediction (maybe shifted by one)?
I also need to play around with this more, but in general you should just set the option warm_start via opts_set and the right QP solver options should be set internally, see e.g. acados/acados/dense_qp/dense_qp_qpoases.c at master · acados/acados · GitHub
It is not universal across QP solvers what warm or hot starting means though, so it depends on what you are using, is that qpOASES still for you?
I think warm start should take the current initial guess from qp_out and hot start should reuse some (parts) of a factorization from the previous call.
So in general (after the first call of ocp_qp_solve) when assuming qp_solver_ and qp_in_ are always reused, it is not necessary to manually set any value to “u” or “x”? Or in other words, how to set the initial guess correctly?
We are currently using, qpOASES, HPIPM, OSQP and DAQP, comparing which one works the best for our problem.
I had another brief look into the interface of some of the QP solvers.
For the active set solvers DAQP and qpOASES, warm starts mainly require the guess of the working set which is taken from solver memory and cannot be altered (through the acados interface).
Also for qpOASES, data from qp_out is not used but whatever was solved before.
On the other hand for HPIPM, independent of condensing, the primal variables are put to zero and the duals are initialized with the previous solution, see here for the full condensing case acados/acados/dense_qp/dense_qp_hpipm.c at f0f474cbe0de01f24b99243226ed74942e876d8e · acados/acados · GitHub
I think it does internally use the guesses given in qp_out.
Zeroing the primal variables is motivated by the fact that the acados NLP solvers
formulate QP subproblems which are in delta formulation of the primals and absolute formulation for the dual variables.
Maybe in your particular setup, it could make sense to reuse the primal variables.
It would be interesting to play around with such things more.
However they also require a bit of knowledge about the underlying solvers.
Playing with the initialization of HPIPM would be as easy as commenting the part where the primal variables are zeroed out.
I encourage you to try that and would be interested to read about the findings.
If you find a strategy which works significantly better for you, we can sure add an option to realize it.
Thanks again Jonathan for the helpful information!
Regarding the active set solvers, that sounds good to me. Maybe at some point it would make sense to collect this information somewhere.
Regarding HPIPM, I will definitely take look. Our problem, even we linearize it at every control cycle, does not change a lot. If I have results, I will come back.