Using IRK GNSF integrators

Hi guys,

I am using acados in Python anb I would like to exploit structure in my model with implicit integrators. In particular, I have quite some states that are simple integrators of the control inputs. If I got that right, I could use GNSF to exploit this structure, but I was unable to find an example that guides me. My issue is also that I need to use MX as I have splines in my model.

If I got that right I should use something like

acados_ocp.solver_options.integrator_type = 'GNSF'
# acados_ocp.solver_options.collocation_type = "GAUSS_RADAU_IIA"
acados_ocp.solver_options.collocation_type = "GAUSS_LEGENDRE"
acados_ocp.solver_options.sim_method_num_stages = 2
acados_ocp.solver_options.sim_method_num_steps = 1
acados_ocp.solver_options.sim_method_newton_iter = 5
acados_ocp.solver_options.sim_method_jac_reuse = True

but then I get a message that automatic detection is not supported for MX, so I suppose I have to pass it myself. My question is how can I do that.

Many thanks in advance!

Ciao,
Mario

Ciao Mario,

Indeed the structure detection does not work with MX.
Symbolic manipulations with MX are very limited in CasADi.

We worked on a clear interface for manual definition of a GNSF model, see acados PR 1725.
In particular, this example shows how to define a model with GNSF structure manually: acados/examples/acados_python/pendulum_on_cart/sim/extensive_example_sim.py at main · acados/acados · GitHub
I hope this enables you to use GNSF-IRK successfully :slight_smile:

I think for MX, there could be a workflow to perform preliminary structure detection without the spline and use ca.substitute.

Best,
Jonathan

Thanks Jonathan,

that was very helpful!
Now the code starts compiling, but at some point I get the following error

cc -shared boat_dae_constraints/boat_dae_constr_h_fun_jac_uxt_zt.o boat_dae_constraints/boat_dae_constr_h_fun.o boat_dae_cost/boat_dae_cost_y_0_fun.o boat_dae_cost/boat_dae_cost_y_0_fun_jac_ut_xt.o boat_dae_cost/boat_dae_cost_y_0_hess.o boat_dae_cost/boat_dae_cost_y_fun.o boat_dae_cost/boat_dae_cost_y_fun_jac_ut_xt.o boat_dae_cost/boat_dae_cost_y_hess.o boat_dae_cost/boat_dae_cost_y_e_fun.o boat_dae_cost/boat_dae_cost_y_e_fun_jac_ut_xt.o boat_dae_cost/boat_dae_cost_y_e_hess.o acados_solver_boat_dae.o boat_dae_model/boat_dae_gnsf_phi_fun.o boat_dae_model/boat_dae_gnsf_phi_fun_jac_y.o boat_dae_model/boat_dae_gnsf_phi_jac_y_uhat.o boat_dae_model/boat_dae_gnsf_f_lo_fun_jac_x1k1uz.o boat_dae_model/boat_dae_gnsf_get_matrices_fun.o -o libacados_ocp_solver_boat_dae.dylib -L/Users/zmario/src/acados/lib -lacados -lhpipm -lblasfeo -lm  \
	-L -l
ld: warning: search path '-l' not found
acados was compiled with OpenMP.

error: ocp_nlp_opts_set: wrong field: anderson_activation_threshold

I am a bit surprised, because I don’t know even what that is…
My options are


# set prediction horizon
acados_ocp.solver_options.N_horizon = N
acados_ocp.solver_options.tf = T

acados_ocp.solver_options.qp_solver = 'PARTIAL_CONDENSING_HPIPM' 
acados_ocp.solver_options.hessian_approx = 'GAUSS_NEWTON'
acados_ocp.solver_options.integrator_type = 'GNSF'
acados_ocp.solver_options.collocation_type = "GAUSS_LEGENDRE"
acados_ocp.solver_options.sim_method_num_stages = 2
acados_ocp.solver_options.sim_method_num_steps = 1
acados_ocp.solver_options.sim_method_newton_iter = 5
acados_ocp.solver_options.sim_method_jac_reuse = True

Hi Mario,

You need to recompile acados after pulling a new version.
I think you have some old binaries around that cause the error.
Can you double check this?

I think the warning can be ignored.

Best,
Jonathan

Right, I got distracted on that… good catch, thank you!