Skip to content

Commit 01563d8

Browse files
authored
Update Kloeser2020.mo
1 parent 199758f commit 01563d8

File tree

1 file changed

+12
-2
lines changed

1 file changed

+12
-2
lines changed

Kloeser2020.mo

Lines changed: 12 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,9 +15,12 @@ model Kloeser2020 "Bicycle model of a model racwe car, from Kloeser2020 paper"
1515
parameter Real kappa = 1 "Road curvature [1/m] (constant)";
1616

1717
// --- Inputs ---
18-
input Real D(min = -1, max = 1) "Duty cycle of electric motor";
19-
input Real delta(min = -1, max = 1) "Steering angle";
18+
input Real D_der(min = -20.0, max = 20.0) "Rate of duty cycle";
19+
input Real delta_der(min = -4.0, max = 4.0) "Rate of steering angle";
2020

21+
Real D(min = -1, max = 1) "Duty cycle of electric motor";
22+
Real delta(min = -0.8, max = 0.8) "Steering angle";
23+
2124
// --- Outputs ---
2225
output Real acc_long "Longitudinal acceleration";
2326
output Real acc_lat "Lateral acceleration";
@@ -28,6 +31,8 @@ model Kloeser2020 "Bicycle model of a model racwe car, from Kloeser2020 paper"
2831
Real alpha "Heading";
2932
Real v "Speed";
3033

34+
Real D_der;
35+
3136
// Auxiliaries
3237
Real beta;
3338
Real Fx_d;
@@ -51,6 +56,9 @@ equation
5156
der(alpha) = dalpha;
5257
der(v) = dv;
5358

59+
der(D) = D_der;
60+
der(delta) = delta_der;
61+
5462
// Outputs
5563
acc_long = Fx_d/m;
5664
acc_lat = v*v/lr*sin(beta) + Fx_d*sin(beta)/m;
@@ -60,5 +68,7 @@ initial equation
6068
n = 0;
6169
alpha = 0;
6270
v = 0;
71+
D = 0;
72+
delta = 0;
6373

6474
end Kloeser2020;

0 commit comments

Comments
 (0)