QPOASES failing with soft constraints

Hello,

I’m having an issue where “PARTIAL_CONDENSING_HPIPM” and “FULL_CONDENSING_HPIPM” work nicely, but “FULL_CONDENSING_QPOASES” fails specifically in the presence of soft constraints. I’ve reduced the OCP to something very simple - linear dynamics, one state and one input variable, no nonlinear constraints, linear LS cost.

I’ve uploaded this example here:

Specifically, when constraints are softened (soft_constraints = True) and the number of time steps is large enough (N >= 12), FULL_CONDENSING_QPOASES does not converge and eventually (usually on the first or second iteration) throws Error 37 ‘RET_INIT_FAILED_INFEASIBILITY’. Everything works fine with hard constraints, so the OCP shouldn’t be infeasible.

Any idea what the problem might be? Thanks for your help!
Logan

Hi Logan,

I just had a look into your example.
Increasing the maximum number of QP iterations seems to solve the issue:

Cheers,
Jonathan

Interestingly, qpOASES can return SUCCESS within 50 iterations on the first 4 problems, while taking 51 iterations when allowed more.
If anyone has some insight on this, I would be interested.

With qp_solver_iter_max=50, I got:

0

iter	qp_stat	qp_iter
0	0	0
1	0	0


1
solve time, 0.006324446999769862

iter	qp_stat	qp_iter
0	0	0
1	2	50


2
solve time, 0.0039940739998201025

iter	qp_stat	qp_iter
0	0	0
1	2	50


3
solve time, 0.003979571999934706

iter	qp_stat	qp_iter
0	0	0
1	2	50


4
solve time, 0.004307506999793986

iter	qp_stat	qp_iter
0	0	0
1	2	50


5
solve time, 0.0014888799996697344
Failed on instance  5  with status  4

while with qp_solver_iter_max=100, I get:

0

iter	qp_stat	qp_iter
0	0	0
1	0	0


1
solve time, 0.02731398499986426

iter	qp_stat	qp_iter
0	0	0
1	0	51


2
solve time, 0.0010279650000484253

iter	qp_stat	qp_iter
0	0	0
1	0	51


3
solve time, 0.004083296999851882

iter	qp_stat	qp_iter
0	0	0
1	0	51


4
solve time, 0.004239356999960364

iter	qp_stat	qp_iter
0	0	0
1	0	51


5
solve time, 0.0041367829999217065

iter	qp_stat	qp_iter
0	0	0
1	0	51

Hi Jonathan,

Thanks so much - increasing the number of QP iterations fixes this on my original OCP as well.

Cheers,
Logan

1 Like