HPIPM Solver Failure

Hi guys, I met a weird problem with HPIPM solver failure. The error is:

SQP_RTI: QP solver returned error status 3 QP iteration 30.
Solver failed with status: 4
return status 4.0 in closed loop iteration 1732.
1733
1734
1735
1736
Traceback (most recent call last):
  File "/lhome/zikhuan/MB_MC/motion-control-sim/main.py", line 53, in <module>
    sim.current_pose_v = np.array([0, 0, sim.current_pose_v[2], u_prev])
ValueError: setting an array element with a sequence. The requested array has an inhomogeneous shape after 1 dimensions. The detected shape was (4,) + inhomogeneous part.

The related snippet codes are followings:

sim.current_pose_v[2] = (current_ref_traj['ref_yaw'][0] - sim.current_pose_sim[2] + np.pi) % (2 * np.pi) - np.pi
sim.current_pose_v = np.array([0, 0, sim.current_pose_v[2], u_prev])

I focus on the line sim.current_pose_v = np.array([0, 0, sim.current_pose_v[2], u_prev]) with trying the debugger to find each term out.

current_ref_traj['ref_yaw'][0] = np.float64(1.4617725313547052)

sim.current_pose_sim[2] = np.float64(-1.75365108)

sim.current_pose_sim = array([474.63264591, 189.64698091,  -1.75365108,  35. ])

(current_ref_traj['ref_yaw'][0] - sim.current_pose_sim[2] + np.pi) % (2 * np.pi) - np.pi = np.float64(-3.0677616946074515)

(current_ref_traj['ref_yaw'][0].item() - sim.current_pose_sim[2].item() + np.pi) % (2 * np.pi) - np.pi = -3.0677616946074515

Therefore, the sim.current_pose_v is supposed to be the consequence above. However, I found the result of sim.current_pose_v = array([-3.06776169, -3.06776169, -3.06776169]) in the DEBUG CONSOLE, which has 3 same entries.

My assumption is the something wrong with the solver. Since the solver failed solving the problem, such that the calculation could not be guaranteed correctly. That’s basic description about my problem. Anyone has the same experience, I would like to know:)

Thanks in advance.

Best,
Brian

Hi Brian,

the reason why HPIPM failed with status 3 is that the QP in RTI is likely to be infeasible and then the values acados return might have nans. Therefore, you should ensure that your QPs are always feasible. There are several ways how you could overcome the issue:

  1. Use slack variables to ensure that the underlying QP is always feasible. Here is an example how to introduce slack variables in your problem formulation: acados/examples/acados_python/linear_mass_model/linear_mass_test_problem.py at main · acados/acados · GitHub
  2. We implemented a new solver that tries to circumevent the problem of infeasible QPs. This solver is an SQP solver, but if you set nlp_solver_max_iter to 1, it should behave similarly as SQP_RTI. The solver is called SQP_WITH_FEASIBLE_QP. You call it with the following option:
    ocp.solver_options.nlp_solver_type = 'SQP_WITH_FEASIBLE_QP', this configuration will always solve one QP, if your QP is feasible and not badly scaled. If HPIPM fails, then it solves 3 QPs in total to avoid the infeasibility.
    You could also set the following options:
ocp.solver_options.search_direction_mode = 'BYRD_OMOJOKUN'
ocp.solver_options.allow_direction_mode_switch_to_nominal = False

This will always solve two QPs, and it is supposed to ensure that HPIPM will not fail. Note that this feature is very new and we are still actively developing it, but we are happy about some user experience.

Best,
David

1 Like

Hi David,

thanks a lot for your concrete response! For the status 3 error, I have changed the maximal iteration number of the solver, like if I decrease a little bit, it could be run successfully. Do you think does it make sense or not? Generally speaking, could Is say the QP could be a bit problematic with feasibility?

I will dig into the feasibility of the QPs and also will try your new solver, it is nice to hear that!
I will give my feedback to it and also the further questions if I have. Thanks again for your patience!

Cheers,
Brian

Hi Brian,

do you mean, you decreased the maximum number of QP iterations and then you were succesful?

If that is the case, it still means that the QP is probably infeasible, but HPIPM did not arrive to the point where it would reach the failure. In that case HPIPM will terminate with status MAX_ITER, and as far as I know SQP_RTI does not take this as an error. I would still say that this is problematic because you can run into situations where HPIPM will run into status 3 within the maximum number of iterations you allowed. Therefore, my suggestion is to use either slacks or the new solver to have something more reliable.

I hope this helps.
Best,
David

Hi David,

it is true when I met these problems with status 3 then I tuned the ocp.solver_options.qp_solver_iter_max. As long as the number is not too small (basically I would do it between 30 and 50, depending on different optimization problems), finally it could be manageable, but the quality of results could be hard to guarantee. Yeah, that is the another topic. But I will try what you suggest. Thanks again for your response!

BTW: do you have any examples of setting up LQR by using ACADOS or not?

Cheers,
Brian

Hi Brian,

for setting up an LQR, you can use the LINEAR_LS cost formulation.

Best,
David

1 Like