Hi,
I’m using the python interface for NMPC with HPIPM and SQP_RTI.
Apart from initializing the first state at the initial state of my system and setting the state constraints to the current state in the loop (following some of the examples) I am not setting any initial guess for the solution.
The solver is in general able to find a solution, but I would like to know if for steps after the first the solver is internally using some initial guess based on the solution of the previous step of if I should set it myself.
Thanks in advance,
Tommaso
Hi Tommaso,
if you do not initialize the solver explicitly in between calls, the initialization is what is in the memory of the solver.
You can explicitly initialize the solver using the setter with the fields ['x', 'u', 'pi', 'lam', 't']
.
I see, it should be added more to the examples.
Also the setter lacks documentation, which I will add soon.
However, the docs for the getter should be helpful as well:
https://docs.acados.org/interfaces/#acados_template.acados_ocp_solver.AcadosOcpSolver.get
Best,
Jonathan
Hi,
so the solver is effectively warm-started with the previous solution if I do not specify otherwise, right?
Since we are here, if I can ask another question,
my problem involves a nonlinear least square cost with nonlinear inequality constraint (not complex, but still nonlinear), and while normally the constraints are satisfed I have found that setting this constraint slightly in contrast with the target (but this happens also for constraints very near to the target), after some iterations the solver stops, but more importantly, looking at the solution trajectory at each step, there are stages in which the constraints are violated.
I understand that being this a nonlinear problem I may not find a feasible solution (which indeed exists), but shouldn’t each intermediate solution at least satisfy the constraints?
As an additional note, the solver gives error status 4 (qp solver failure) and hpipm gives error 3, but I could not find the meaning of the errors in hpipm code, do you know where to find it?
Best,
Tommaso
Hi,
For the meaning of error codes, let me refer to this Acados error status 2 on python interface - #2 by FreyJo
If the solver exits with nonzero status, non of the constraints are guaranteed to be satisfied.
Moreover, for SQP_RTI, the solver does not run until convergence and constraint satisfaction cannot be guarenteed in general.
I dont really know what you mean here.
The intermediate solutions are just the iterates of the SQP.
So, the iterates do not have to satisfy the constraints (also not the ones for the dynamics).
Best,
Jonathan
I’m sorry, I should have asked the question more clearly.
I thought that the single step performed in the SQP_RTI still has to satisfy the constraints. Doesn’t it solve a constrained QP and perform one step towards the (eventual) solution?
What I meant by slightly in constrast is this: (again sorry for not being clear)
I have a uniclycle that I want to track a constant reference at y=0, starting from a position at y=1, but setting a constraint y>0.1.
I would expect the system to converge to slightly above 0.1 and then keep going parallel to the reference. Instead the solver eventually exits for a qp failure and before exiting does not satisfy the constraint.
Note that if I set the constraint to be always satisfied SQP does not converge even at the first iteration. However removing the constraint (and initializing SQP with a meaningful guess) everything converges properly.
I can also add that in different conditions SQP_RTI is able to satisfy the same constraint and the unicycle runs “on the edge” of the constraint, but this is obtained altering the cost function, with the contraint not “in contrast” with the reference.
Do you have any pointers on where should I look?
Thanks,
Tommaso
EDIT: Having a closer look I found that this behaviour seems to be related to using parameters in the constraint: If I set a plain constraint y>0.1 everithing seems to work.
In general I use a parametric contraint to compute the lateral displacement y_lat (which is the quantity I really want to constraint) depending on the desired angle by
y_lat = -sin(psi_des)*(x-x_des)+cos(psi_des)*(y-y_des)
and setting the parameters at each stage with the appropriate set command.
With the scenario I described psi_des = 0 and y_des = 0 so that it should be the same as
y_lat = y
Here I found that even though with the proper parameters the expression is the same, the solver behaves differently.
Is this expected in any way? should I open a new topic to discuss this issue (if it is one) more in detail?
@tom hey Tommaso, have you figured out how to solve the status 4 errors? would really appreciate the help.
Hi, as I recall in the end I solved many of my problems by just using qpOASES instead of HPIPM as QP solver.
For some reason I never managed to make HPIPM converge with SQP even when qpOASES worked just fine and everything was working as expected. Even initializing HPIPM with the solution from qpOASES would not work, so I assume it was a bug in acados or some HPIPM-related condition that I was setting in the wrong way.
Unfortunately I have not been using acados for some time so I cannot speak for more current developments.
Sorry if this does not help, I wish you to be able to fix your problems.
Ok, I will give it a shot, thanks for the reply man