-
Notifications
You must be signed in to change notification settings - Fork 1
/
Double_Integrator_System.m
66 lines (54 loc) · 1.61 KB
/
Double_Integrator_System.m
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
% This script defines the system model for a double integrator system.
% More info about the system can be found in Section VI of the paper
% 'DiffTune-MPC: Closed-Loop Learning for Model Predictive Control' (https://arxiv.org/pdf/2312.11384)
% Ran Tao, Sheng Cheng
% University of Illinois Urbana-Champaign
function model = Double_Integrator_System()
import casadi.*
%% dims
nx = 2;
nu = 1;
%% symbolic variables
sym_x = SX.sym('x', nx, 1); % states
sym_u = SX.sym('u', nu, 1); % controls
sym_xdot = SX.sym('xdot',size(sym_x)); %state derivatives
%% dynamics
% continuous time
Ac = [0 1;0 -0.05];
% 0.05 is the friction efficient, assumed to be proportional to velocity
% but in reverse direction
Bc = [0;1];
% discrete time
Ts = 0.01; % sampling time
M = expm([Ts*Ac, Ts*Bc; zeros(nu, 2*nx/2+nu)]);
A = M(1:nx,1:nx);
B = M(1:nx,nx+1:end);
expr_f_expl = Ac*sym_x + Bc*sym_u;
expr_f_impl = expr_f_expl - sym_xdot;
expr_phi = A*sym_x + B*sym_u;
u_max = 1; %maximum control input
x_max = 100; %maximum position
v_max = 100; %maximum velocity
%% constraints
expr_h = [sym_u; sym_x];
expr_h_e = [sym_x];
%% nonlnear least squares
expr_y = [sym_u; sym_x];
expr_y_e = [sym_x];
%% populate structure
model.nx = nx;
model.nu = nu;
model.sym_x = sym_x;
model.sym_xdot = sym_xdot;
model.sym_u = sym_u;
model.expr_f_expl = expr_f_expl;
model.expr_f_impl = expr_f_impl;
model.expr_phi = expr_phi;
model.expr_h = expr_h;
model.expr_h_e = expr_h_e;
model.Ts = Ts; % add sample time
model.A = A; % save the discrete-time system matrices
model.B = B; % save the discrete-time system matrices
model.u_max = u_max;
model.x_max = x_max;
model.v_max = v_max;