Simulink Sfunction: Error when setting constraints

Hi acados Team :wave:

unfortunately I am having issues with constraints when creating a Simulink sfunction. What I tried to do is to set up a constraint like this:

ocp_model.set('constr_type', 'auto');
ocp_model.set('constr_expr_h',vertcat(0.5*x(1)+0.5*x(2),u))

When creating the ocp_solver this constraint is reformulated into a linear constraint and a bound for u. The reformulation looks correct. (By the way, this is a very cool feature! :star:) Then, when I try to create an sfunction, I encounter an error.

The error can be easily reproduced with the getting_started\minimal_example_ocp.m. Just change the code in line 87 from

ocp_model.set('constr_expr_h', model.expr_h);

to this

ocp_model.set('constr_expr_h', model.sym_x(1)+model.sym_x(2));

and run getting_started\simulink_example.m. In my case I get the following error message:

Error using acados_template_mex.render_acados_templates>render_file (line 246)
rendering acados_solver.in.c failed.
 command: D:\acados\examples\acados_matlab_octave\..\..\bin\t_renderer.exe
 "D:\acados\examples\acados_matlab_octave\..\..\interfaces\acados_template\acados_template\c_templates_tera\*"
 "acados_solver.in.c" "D:\acados\examples\acados_matlab_octave\getting_started\acados_ocp_nlp.json"
 "acados_solver_pendulum.c"
 returned status 1, got result:
Error: Failed to render 'acados_solver.in.c'
Reason: Variable `constraints.D[j][k]` not found in context while rendering 'acados_solver.in.c': the
evaluated version was `constraints.D.0.0`. Maybe the index is out of bounds?

Some additional Info:

  • I am using the acados version as of the 19th of March. Older versions of acados are also effected, I tried this with a version from November of last year.
  • Using set('constr_type','bgh') and directly setting constr_C and constr_D brings up the same error message.

Can you tell from my description if I should formulate the constraint in another way or if this is a bug related to the process of creating an sfunction?

Thanks a lot for your help! :slightly_smiling_face:
Christian

Hey Christian,

thanks for reporting this issue!
Although it was a bit nasty to fix :stuck_out_tongue:

The problem was that single row matrices are vectors in Matlab and thus not written as a matrix in the json file.
I just pushed a fix to the acados master branch: MEX templating: cast single row matrices to cell, fixing bug for ng == 1 · acados/acados@0f69582 · GitHub

Cheers,
Jonathan

Wow, thanks for the super fast fix :slightly_smiling_face:

One question concerning updating the source code: Do I need to clone and install acados from scratch, or is it sufficient to just pull the master branch?

Regards,
Christian

I think pull should be sufficient, if your previous version was from March 19. But you might have to reinstall too…