Hi,
I am currently working on some benchmarking and I am having a problem with one OCP in particular which should definitely work with acados. I am looking at the nonlinear hanging chain as it is shown in
Kirches, C., et al. “Efficient direct multiple shooting for nonlinear model predictive control on long horizons.” Journal of Process Control 22.3 (2012): 540-550.
I know that there is an example for the nonlinear chain in the acados installation folder which is based on
Kouzoupis, Dimitris, et al. “Recent advances in quadratic programming algorithms for nonlinear model predictive control.” Vietnam Journal of Mathematics 46.4 (2018): 863-882.
Those two problems are only slightly different. Besides differing parameters, Kirches 2012 also does not consider the wall constraint or the initial disturbance, thus it should be easier to solve.
When I try to implement it, however, acados only iterates once (even though it is allowed to iterate 4 times) and always returns an optimal input of zero over all three input channels, which effectively results in the free response of the dynamic system. The extremely short timing, which I get via ocp_acados.get(‘time_qp_sol’) further suggests that acados is not even “trying” to actually solve the problem.
I am pretty confident in the implemented ODE of the dynamical system, since it works with other solvers. I am therefore convinced that I messed up some settings and I was wondering if any of you can spot a mistake that I have not been able to find for days.
keyfacts: 21 states, 3 inputs, 0.1s sampling time, 80 steps horizon, 4 max iterations
% Calculate prediction horizon in seconds
ocp_N = double(optim.N);
ocp_T = ocp_N * model.dT;
%% Define cost function
% The cost function on ACADOS is defined in terms of a virtual output y. In
% our case, we stack the states and inputs together to form y.
nx = model.nx;
nu = model.nu;
ny = nx + nu; % Dimension of the virtual output
Vx = [ eye(nx); zeros(nu,nx) ]; % Mapping from states to virtual output
Vu = [ zeros(nx,nu); eye(nu) ]; % Mapping from inputs to virtual output
% lower and upper bounds on the input
u_ub = optim.b(1:nu);
u_lb = - optim.b(nu+1:2*nu);
% set up reference to be tracked
y_ref = [model.xdes; model.udes];
% Weighting matrix for the virtual output
W = blkdiag(optim.Q, optim.R);
% set up terminal penalty
Vx_e = Vx;
W_e = blkdiag(optim.P, zeros(size(optim.R)));
y_ref_e = y_ref;
%% Build ACADOS OCP model
ocp_model = acados_ocp_model();
ocp_model.set('name', model.name);
ocp_model.set('T', ocp_T);
% Set dimension of the decision variables
ocp_model.set('dim_nx', nx);
ocp_model.set('dim_nu', nu);
ocp_model.set('dim_ny', ny);
ocp_model.set('dim_ny_e', 0);
ocp_model.set('dim_nz', 0); % No algebraic variables
% Set symbolic variables
sym_x = casadi.SX.sym('x', nx);
sym_u = casadi.SX.sym('u', nu);
ocp_model.set('sym_x', sym_x);
ocp_model.set('sym_u', sym_u);
% Define dynamic properties of the model
ocp_model.set('dyn_type', 'explicit'); % Use explicit continuous-time ODE as model
ocp_model.set('dyn_expr_f', model.ode(sym_x, sym_u));
% Set up cost function
ocp_model.set('cost_type', 'linear_ls'); % Linear least-squares cost function
ocp_model.set('cost_Vu', Vu);
ocp_model.set('cost_Vx', Vx);
ocp_model.set('cost_Vz', zeros(ny,0)); % No algebraic variables, so setting to 0
ocp_model.set('cost_W', W);
ocp_model.set('cost_y_ref', y_ref); % in this case we are considering a reference
% Set up input constraints
ocp_model.set('constr_C', zeros(nu, nx)); % No constraints on the states
ocp_model.set('constr_D', eye(nu));
ocp_model.set('constr_lg', u_lb); % Lower and upper limit on the control
ocp_model.set('constr_ug', u_ub);
% Use additional terminal cost.
ocp_model.set('cost_type_e', 'linear_ls');
ocp_model.set('cost_Vx_e', Vx_e); % for terminal cost
ocp_model.set('cost_W_e', W_e); % for terminal cost
ocp_model.set('cost_y_ref_e', y_ref_e); % for terminal cost
% Temporarily set initial conditions, without this the model contruction fails. Will be overwritten
% before the simulation anyway.
ocp_model.set('constr_x0', model.x0);
%% Configure ACADOS OCP solver
ocp_opts = acados_ocp_opts();
ocp_opts.set('param_scheme_N', ocp_N);
% Set up the internal simulator.
ocp_opts.set('sim_method', 'erk'); % Use explicit Runge-Kutta ODE solver
ocp_opts.set('sim_method_num_stages', 4); % Use 4th order ODE solver
ocp_opts.set('sim_method_num_steps', 2);
% Set up the NLP solver. If the solver is only allowed to perform a single iteration, switch to
% real-time iteration mode.
if optim.iter_max == 1
ocp_opts.set('nlp_solver', 'sqp_rti');
else
ocp_opts.set('nlp_solver', 'sqp');
end
ocp_opts.set('nlp_solver_max_iter', optim.iter_max); % Maximum number of iterations
% Set up the QP solver
ocp_opts.set('qp_solver', 'full_condensing_hpipm');
%% Generate OCP
ocp = acados_ocp(ocp_model, ocp_opts);
Any help, advice or idea would be much appreciated.
Best,
Artur