-
Notifications
You must be signed in to change notification settings - Fork 11
/
Copy pathdynamics.py
298 lines (254 loc) · 11.1 KB
/
dynamics.py
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
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
from __future__ import print_function
import torch
import numpy as np
from config import DynamicsConfig
import matplotlib.pyplot as plt
import math
PI = 3.1415926
class VehicleDynamics(DynamicsConfig):
def __init__(self):
self._state = torch.zeros([self.BATCH_SIZE, self.DYNAMICS_DIM])
self.init_state = torch.zeros([self.BATCH_SIZE, self.DYNAMICS_DIM])
self._reset_index = np.zeros([self.BATCH_SIZE, 1])
self.initialize_state()
super(VehicleDynamics, self).__init__()
def initialize_state(self):
"""
random initialization of state.
Returns
-------
"""
self.init_state[:, 0] = torch.normal(0.0, 0.6, [self.BATCH_SIZE,])
self.init_state[:, 1] = torch.normal(0.0, 0.4, [self.BATCH_SIZE,])
self.init_state[:, 2] = torch.normal(0.0, 0.15, [self.BATCH_SIZE,])
self.init_state[:, 3] = torch.normal(0.0, 0.1, [self.BATCH_SIZE,])
self.init_state[:, 4] = torch.linspace(0.0, np.pi, self.BATCH_SIZE)
init_ref = self.reference_trajectory(self.init_state[:, 4])
init_ref_all = torch.cat((init_ref, torch.zeros([self.BATCH_SIZE,1])),1)
self._state = self.init_state
init_state = self.init_state + init_ref_all
return init_state
def relative_state(self, state):
x_ref = self.reference_trajectory(state[:, -1])
state_r = state.detach().clone()[:, 0:4] - x_ref # relative state # todo:修改所有相对坐标更新
return state_r
def _state_function(self, state, control):
"""
State function of vehicle with Pacejka tire model, i.e. \dot(x)=f(x,u)
Parameters
----------
state: tensor shape: [BATCH_SIZE, STATE_DIMENSION]
current state
control: tensor shape: [BATCH_SIZE, ACTION_DIMENSION]
input
Returns
-------
deri_state.T: tensor shape: [BATCH_SIZE, ]
f(x,u)
F_y1: tensor shape: [BATCH_SIZE, ]
front axle lateral force
F_y2: tensor shape: [BATCH_SIZE, ]
rear axle lateral force
alpha_1: tensor shape: [BATCH_SIZE, ]
front wheel slip angle
alpha_2: tensor shape: [BATCH_SIZE, ]
rear wheel slip angle
"""
# state variable
y = state[:, 0] # lateral position
u_lateral = state[:, 1] # lateral speed
beta = u_lateral / self.u # yaw angle
psi = state[:, 2] # heading angle
omega_r = state[:, 3] # yaw rate
x = state[:, 4] # longitudinal position
# inputs
delta = control[:, 0] # front wheel steering angle
delta.requires_grad_(True)
# slip angle of front and rear wheels
alpha_1 = -delta + beta + self.a * omega_r / self.u
alpha_2 = beta - self.b * omega_r / self.u
# cornering force of front and rear angle, Pacejka tire model
F_y1 = -self.D * torch.sin(self.C * torch.atan(self.B * alpha_1)) * self.F_z1
F_y2 = -self.D * torch.sin(self.C * torch.atan(self.B * alpha_2)) * self.F_z2
# derivative of state
deri_y = self.u * torch.sin(psi) + u_lateral * torch.cos(psi)
deri_u_lat = (torch.mul(F_y1, torch.cos(delta)) + F_y2) / (self.m) - self.u * omega_r
deri_psi = omega_r
deri_omega_r = (torch.mul(self.a * F_y1, torch.cos(delta)) - self.b * F_y2) / self.I_zz
deri_x = self.u * torch.cos(psi) - u_lateral * torch.sin(psi)
deri_state = torch.cat((deri_y[np.newaxis, :],
deri_u_lat[np.newaxis, :],
deri_psi[np.newaxis, :],
deri_omega_r[np.newaxis, :],
deri_x[np.newaxis, :]), 0)
return deri_state.T, F_y1, F_y2, alpha_1, alpha_2
def _state_function_linear(self, state, control):
"""
State function of vehicle with linear tire model and linear approximation, i.e. \dot(x) = Ax + Bu
Parameters
----------
state: tensor shape: [BATCH_SIZE, STATE_DIMENSION]
current state
control: tensor shape: [BATCH_SIZE, ACTION_DIMENSION]
input
Returns
-------
deri_state.T: tensor shape: [BATCH_SIZE, ]
f(x,u)
F_y1: tensor shape: [BATCH_SIZE, ]
front axle lateral force
F_y2: tensor shape: [BATCH_SIZE, ]
rear axle lateral force
alpha_1: tensor shape: [BATCH_SIZE, ]
front wheel slip angle
alpha_2: tensor shape: [BATCH_SIZE, ]
rear wheel slip angle
"""
# state variable
y = state[:, 0] # lateral position
u_lateral = state[:, 1] # lateral speed
beta = u_lateral / self.u # yaw angle
psi = state[:, 2] # heading angle
omega_r = state[:, 3] # yaw rate
x = state[:, 4] # longitudinal position
# inputs
delta = control[:, 0] # front wheel steering angle
delta.requires_grad_(True)
# slip angle of front and rear wheels, with small angle approximation
alpha_1 = -delta + beta + self.a * omega_r / self.u
alpha_2 = beta - self.b * omega_r / self.u
# cornering force of front and rear angle, linear tire model
F_y1 = - self.k1 * alpha_1
F_y2 = - self.k2 * alpha_2
# derivative of state
# deri_y = self.u * psi + u_lateral
deri_y = self.u * torch.sin(psi) + u_lateral * torch.cos(psi)
deri_u_lat = (torch.mul(F_y1, torch.cos(delta)) + F_y2) / (self.m) - self.u * omega_r
deri_psi = omega_r
deri_omega_r = (torch.mul(self.a * F_y1, torch.cos(delta)) - self.b * F_y2) / self.I_zz
deri_x = self.u * torch.cos(psi) - u_lateral * torch.sin(psi)
deri_state = torch.cat((deri_y[np.newaxis, :],
deri_u_lat[np.newaxis, :],
deri_psi[np.newaxis, :],
deri_omega_r[np.newaxis, :],
deri_x[np.newaxis, :]), 0)
return deri_state.T, F_y1, F_y2, alpha_1, alpha_2
def reference_trajectory(self, state):
"""
Parameters
----------
state shape: [BATCH_SIZE,] longitudinal location x
Returns
-------
state_ref.T: shape: [BATCH_SIZE, 4] reference trajectory
"""
if self.reference_traj == 'SIN':
k = self.k_curve
a = self.a_curve
y_ref = a * torch.sin(k * state)
psi_ref = torch.atan(a * k * torch.cos(k * state))
elif self.reference_traj == 'DLC':
width = 3.5
line1 = 50
straight = 50
cycle = 3 * straight + 2 * line1
x = state % cycle
lane_position = torch.zeros([len(state), ])
lane_angle = torch.zeros([len(state), ])
for i in range(len(state)):
if x[i] <= 50:
lane_position[i] = 0
lane_angle[i] = 0
elif 50 < x[i] and x[i] <= 90:
lane_position[i] = 3.5 / 40 * x[i] - 4.375
lane_angle[i] = np.arctan(3.5 / 40)
elif 90 < x[i] and x[i] <= 140:
lane_position[i] = 3.5
lane_angle[i] = 0
elif x[i] > 180:
lane_position[i] = 0
lane_angle[i] = 0
elif 140 < x[i] and x[i] <= 180:
lane_position[i] = -3.5 / 40 * x[i] + 15.75
lane_angle[i] = -np.arctan(3.5 / 40)
else:
lane_position[i] = 0.
lane_angle[i] = 0.
y_ref = lane_position
psi_ref = lane_angle
zeros = torch.zeros([len(state), ])
state_ref = torch.cat((y_ref[np.newaxis, :],
zeros[np.newaxis, :],
psi_ref[np.newaxis, :],
zeros[np.newaxis, :]), 0)
return state_ref.T
def step(self, state, control):
"""
step ahead with discrete state function, i.e. x'=f(x,u)
Parameters
----------
state: tensor shape: [BATCH_SIZE, STATE_DIMENSION]
current state
control: tensor shape: [BATCH_SIZE, ACTION_DIMENSION]
current control signal
Returns
-------
state_next: tensor shape: [BATCH_SIZE, ]
x'
f_xu: tensor shape: [BATCH_SIZE, ]
f(x,u)
utility: tensor shape: [BATCH_SIZE, ]
utility, i.e. l(x,u)
F_y1: tensor shape: [BATCH_SIZE, ]
front axle lateral force
F_y2: tensor shape: [BATCH_SIZE, ]
rear axle lateral force
alpha_1: tensor shape: [BATCH_SIZE, ]
front wheel slip angle
alpha_2: tensor shape: [BATCH_SIZE, ]
rear wheel slip angle
"""
if self.nonlinearity:
deri_state, F_y1, F_y2, alpha_1, alpha_2 = self._state_function(state, control)
else:
deri_state, F_y1, F_y2, alpha_1, alpha_2 = self._state_function_linear(state, control)
state_next = state + self.Ts * deri_state
utility = self.utility(state, control)
f_xu = deri_state[:, 0:4]
return state_next, f_xu, utility, F_y1, F_y2, alpha_1, alpha_2
def step_relative(self, state, u):
"""
Parameters
----------
state_r
u_r
Returns
-------
"""
x_ref = self.reference_trajectory(state[:, -1])
state_r = state.detach().clone() # relative state
state_r[:, 0:4] = state_r[:, 0:4] - x_ref
state_next, deri_state, utility, F_y1, F_y2, alpha_1, alpha_2 = self.step(state, u)
state_r_next_bias, _, _, _, _, _, _ = self.step(state_r, u) # update by relative value
state_r_next = state_r_next_bias.detach().clone()
state_r_next_bias[:, [0, 2]] = state_next[:, [0, 2]] # y psi with reference update by absolute value
x_ref_next = self.reference_trajectory(state_next[:, -1])
state_r_next[:, 0:4] = state_r_next_bias[:, 0:4] - x_ref_next
utility = self.utility(state_r_next, u)
return state_next.clone().detach(), state_r_next.clone().detach()
@staticmethod
def utility(state, control):
"""
Parameters
----------
state: tensor shape: [BATCH_SIZE, STATE_DIMENSION]
current state
control: tensor shape: [BATCH_SIZE, ACTION_DIMENSION]
current control signal
Returns
-------
utility: tensor shape: [BATCH_SIZE, ]
utility, i.e. l(x,u)
"""
utility = 0.05 * (10 * torch.pow(state[:, 0], 2) + 5 * torch.pow(state[:, 2], 2) + 5 * torch.pow(control[:, 0], 2))
return utility