Runtime errors with MSVC (not with MinGW)

Hi all,

Recenlty, I’ve been switching between the MinGW and MSVC compilers (Windows, Matlab interface), and I noticed different runtime behaviour between the two. With MinGW, I get a solution for my simple model, as expected. However, when I (only) change the compiler to MSVC, I run into a QP solver failure (ACADOS_QP_FAILURE). Playing around with the qp solver settings (I’m using hpipm) sometimes makes the error dissapear, so I’m guessing that HPIPM and MSVC don’t play nice together. @giaf is this something you recognize?

Below, I pasted a minimal example of the Matlab code that yields errors with MSVC, but not with MinGW.

Thank you for any insights that might solve this issue.

function minimal_example()
clear all
N_ocp = 10;            % control horizon (steps)
Ts = 0.01;            % timestep/sampling time
T_ocp = Ts*N_ocp;     % control horizon (time)

%%%%%%%%%%%%%%%%%%%%%%%
%%%%%% OCP MODEL %%%%%%
%%%%%%%%%%%%%%%%%%%%%%%

ocp_model = acados_ocp_model();
ocp_model.set('name', 'example');
ocp_model.set('T',T_ocp);

%%%%%% state %%%%%
X = casadi.SX.sym('X');
V = casadi.SX.sym('V');
F = casadi.SX.sym('F');
sym_x = vertcat(X, V, F);
ocp_model.set('sym_x', sym_x);
ocp_model.set('sym_xdot', casadi.SX.sym('xdot', 3, 1));

%%%%%% inputs %%%%%
dF = casadi.SX.sym('dF');
sym_u = [dF];
ocp_model.set('sym_u', sym_u);

%%%%%% model %%%%%
m = 1;
A = [0, 1, 0;
     0, 0, 1/m;
     0, 0, 0];
B = [0; 
     0; 
     1];
ocp_model.set('dyn_expr_f', A * sym_x + B * sym_u);
ocp_model.set('dyn_type', 'explicit');

%%%%%% constraints %%%%%
dF_u = 1; dF_l = -dF_u;
ocp_model.set('constr_Jbu', 1);
ocp_model.set('constr_lbu', dF_l);
ocp_model.set('constr_ubu', dF_u);

%%%%%% cost %%%%%
W_X = 1e1; W_V = 1e-6; W_F = 1e2; W_dF = 1e-6;

ocp_model.set('cost_type', 'linear_ls');
ocp_model.set('cost_type_e', 'linear_ls');

ocp_model.set('cost_Vx', [1, 0, 0;
                          0, 1, 0;
                          0, 0, 1;
                          0, 0, 0]);
ocp_model.set('cost_Vu', [0; 
                          0;
                          0;
                          1]);
ocp_model.set('cost_Vx_e', [1, 0, 0;
                            0, 1, 0;
                            0, 0, 1]);

ocp_model.set('cost_W', [W_X,    0,    0,    0;
                           0,  W_V,    0,    0;
                           0,    0,  W_F,    0;
                           0,    0,    0, W_dF]);
ocp_model.set('cost_W_e', [W_X,    0,    0;
                             0,  W_V,    0;
                             0,    0,  W_F]);

%%% trajectory %%%
ocp_model.set('constr_x0', [0;0;0]);
ocp_model.set('cost_y_ref', [1;0;0;0]);
ocp_model.set('cost_y_ref_e', [1;0;0]);

%%%%%%%%%%%%%%%%%%%%%%%%%
%%%%%% OCP OPTIONS %%%%%%
%%%%%%%%%%%%%%%%%%%%%%%%%

% ocp options
ocp_opts = acados_ocp_opts();
ocp_opts.set('qp_solver','partial_condensing_hpipm'); % --> options that don't play nice with MSVC compiler
ocp_opts.set('qp_solver_cond_N', 5); % --> options that don't play nice with MSVC compiler
% ocp_opts.set('qp_solver_iter_max', 10); % --> options that don't play nice with MSVC compiler
ocp_opts.set('regularize_method', 'no_regularize');
ocp_opts.set('sim_method', 'erk');

%%%%%%%%%%%%%%%%%%%%%%%%
%%%%%% OCP SOLVER %%%%%%
%%%%%%%%%%%%%%%%%%%%%%%%

% create ocp solver
ocp = acados_ocp(ocp_model, ocp_opts);

% solve OCP
ocp.solve();
x_traj = ocp.get('x');

% print stats
ocp.print('stat');
status = ocp.get('status');
fprintf('OCP finished with code %.f: %s\n\n', status, status_code(status+1));

%%%%%%%%%%%%%%%%%%
%%%%%% PLOT %%%%%%
%%%%%%%%%%%%%%%%%%

figure
states = {'X', 'V', 'F'};
ylabels = {{'Position [m]'}, {'Velocity [m/s]'}, {'Force [N]'}};
for i=1:length(states)
    subplot(length(states), 1, i);
    hold on
    plot((0:N_ocp)*Ts, x_traj(i,:));
    grid on;
    xlim([0 T_ocp]);
    ylabel(ylabels{i})
    legend(states{i},'Location','southeast');
end

end % function

function msg = status_code(code) 
    msgs = [ ...
        "ACADOS_SUCCESS", ...       % success
        "ACADOS_FAILURE", ...       % failure
        "ACADOS_MAXITER", ...       % maximum number of iterations reached
        "ACADOS_MINSTEP", ...       % minimum step size in QP solver reached
        "ACADOS_QP_FAILURE", ...    % qp solver failed
        "ACADOS_READY"
    ];
    msg = msgs(code);
end % function

Hi Jonathan, Gianluca,

You effectively solved this issue with one of your most recent commits. I don’t know which one exactly, but thanks for solving it in any case!

There was just one remaining issue I had to manually solve. With MSVC2017 (not with MSVC2019), the compilation fails due to a redeclaration of ocp_nlp_eval_residuals in acados/interfaces/acados_c/ocp_nlp_interface.h. That header seems to define this function twice, with and without the ACADOS_SYMBOL_EXPORT. Commenting the one without doesn’t seem to give issues. Is this an accidental duplicate?

Thanks,
Caspar

Hi Caspar,

I am glad it works with the most recent version!
I actually also had this issue with MSVC 2019, it is now fixed:

It was an accidental duplicate / merge artifact.

Cheers,
Jonathan