Adding and removing inequality constraints in Python and C++

Hi!

We are currently working with both the Python interface for development and then using the C generated code for C++ ROS implementation with our system. We are still getting familiar with the framework, so we have a few questions about how to use inequality constraints both in Python and C++.

Particularly, we are trying to avoid obstacles, and the number of obstacles sensed changes depending on the position of our vehicle. In an old ACADO code we saw something like this:

for(int i = 0; i < obs_number; i++){
        ocp.subjectTo(sqrt((x-obsx[i])*(x-obsx[i]) + (y-obsy[i])*(y-obsy[i])) >= safety_distance);
        }

We intend to do a similar approach with acados on both Python and C++, but we do not know the correct syntax to do so. So far, we understand how to set initial states and references, and how to get the inputs and future states (based on the race car code) as:

acados_solver = AcadosOcpSolver(ocp, json_file="acados_ocp.json")

acados_solver.set(0, "lbx", x0)
acados_solver.set(0, "ubx", x0)
for j in range(N):
    acados_solver.set(j, "yref", yref)
acados_solver.set(N, "yref", yref_N)
status = acados_solver.solve()
u0 = acados_solver.get(0, "u")
x0 = acados_solver.get(1, "x")

And in a similar way (based on the crazyflie code) on C++:

solver_input acados_in;
solver_output acados_out;
acados_in.x0[0] = x0
acados_in.yref[0] = yref;
acados_in.yref_e[0] = yref;
for (ii = 0; ii < N; ii++)
{
ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, ii, "yref", acados_in.yref);
}
ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "yref", acados_in.yref_e);
acados_status = acados_solve();
ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, 0, "u", (void *)acados_out.u0);

For both cases, is there a way we can integrate the different number of inequality constraints?

Note: We saw we could use a predefined nonlinear constraint with changing parameters for each stage, but that would only allow us to avoid a predetermined number of obstacles, which is not an ideal solution for us.

Thanks!
Alex

Hi Alex,

it is not possible to add and remove constraints in acados after creating the solver.
This is because the allocated memory is dependent on the dimensions of the problem, part of which are the number of constraints at each shooting node.

What you can do is set a maximum number of inequality constraints when creating the solver, where most of them are trivial and they become nontrivial (by setting parameters and/or bounds) when there is an obstacle.

Best,
Jonathan

1 Like

Hi Jonathan,

I understand, thank you for your answer! It helps to learn more about how to use the library.

Best,
Alex