-
Notifications
You must be signed in to change notification settings - Fork 0
/
mpc.py
362 lines (274 loc) · 12.4 KB
/
mpc.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
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
from casadi import *
import util
import numpy as np
from dynamics import *
from time import perf_counter
import logging
from dynamics import generate_f
"""This is a vanilla centralized MPC demo without C-ADMM"""
"""Linear quadratic MPC, centralized (with receding horizon implementation)"""
def solve_mpc_centralized(n_agents, x0, xr, T, radius, Q, R, Qf, MAX_ITER, n_trial = None):
SOVA_admm = 'centralized_mpc'
n_states = 6
n_inputs = 3
nx = n_agents * n_states
nu = n_agents * n_inputs
N = n_agents
opti = Opti('conic')
Y_state = opti.variable((T+1)*nx + T*nu)
cost = 0
u_ref = np.array([0, 0, 0] * N).reshape(-1,1)
for t in range(T):
for idx in range(nx):
cost += (Y_state[:(T+1)*nx][t*nx:(t+1)*nx][idx]-xr[idx]) * \
Q[idx,idx]* (Y_state[:(T+1)*nx][t*nx:(t+1)*nx][idx]-xr[idx])
for idu in range(nu):
cost += (Y_state[(T+1)*nx:][t*nu:(t+1)*nu][idu]) * \
R[idu,idu] * (Y_state[(T+1)*nx:][t*nu:(t+1)*nu][idu])
for idf in range(nx):
cost += (Y_state[:(T+1)*nx][T*nx:(T+1)*nx][idf] - xr[idf]) * \
Qf[idf,idf] * (Y_state[:(T+1)*nx][T*nx:(T+1)*nx][idf] - xr[idf])
obj_hist = [np.inf]
x_curr = x0
u_curr = np.zeros((nu,1))
X_trj = np.zeros((0, nx))
U_trj = np.zeros((0, nu))
X_trj = np.r_[X_trj, x0.T]
iters = 0
solve_times = []
t = 0
dt = 0.1
x_dims = [6]*N
n_dims = [3]*N
r_min = 2*radius
Ad,Bd = linear_kinodynamics(dt,n_agents)
A_i = Ad[0:6,0:6]
B_i = Bd[0:6,0:3]
while not np.all(util.distance_to_goal(x_curr.flatten(), xr.flatten(), n_agents, n_states) <= 0.1):
for k in range(T):
X_next = Y_state[:(T+1)*nx][(k+1)*nx:(k+2)*nx]
X_curr = Y_state[:(T+1)*nx][k*nx:(k+1)*nx]
U_curr = Y_state[(T+1)*nx:][k*nu:(k+1)*nu]
opti.subject_to(X_next==Ad @ X_curr + Bd @ U_curr) # close the gaps
#Constrain acceleration (control input):
opti.subject_to(Y_state[(T+1)*nx:][k*nu:(k+1)*nu] <= np.tile(np.array([2, 2, 2]),(N,)).reshape(-1,1))
opti.subject_to(np.tile(np.array([-2, -2, -2]),(N,)).reshape(-1,1) <= Y_state[(T+1)*nx:][k*nu:(k+1)*nu])
#Constrain velocity:
for i in range(n_agents):
opti.subject_to(Y_state[(T+1)*nx:][i*n_states:(i+1)*n_states][3:6] <= np.array([1.5, 1.5, 1.5]))
opti.subject_to(np.array([-1.5, -1.5, -1.5]) <= Y_state[(T+1)*nx:][i*n_states:(i+1)*n_states][3:6])
#Collision avoidance via BVCs
for i in range(n_agents):
agent_i_trj = forward_pass( A_i,
B_i,
T,
x_curr[i*n_states:(i+1)*n_states],
u_curr[i*n_inputs:(i+1)*n_inputs])
p_i_next = X_curr[i*n_states:(i+1)*n_states][:3]
for j in range(n_agents):
if j != i:
agent_j_trj = forward_pass( A_i,
B_i,
T,
x_curr[j*n_states:(j+1)*n_states],
u_curr[j*n_inputs:(j+1)*n_inputs])
a_ij = (agent_i_trj[:,k][:3] -agent_j_trj[:,k][:3])/cs.norm_2(agent_i_trj[:,k][:3] -agent_j_trj[:,k][:3])
b_ij = cs.dot(a_ij, (agent_i_trj[:,k][:3] + agent_j_trj[:,k][:3])/2) + r_min/2
opti.subject_to(cs.dot(a_ij, p_i_next) >= b_ij )
X0 = opti.parameter(x0.shape[0],1)
opti.subject_to(Y_state[0:nx] == X0)
cost_tot = cost
opti.minimize(cost_tot)
opti.solver("osqp")
opti.set_value(X0,x_curr)
if iters > 0:
opti.set_initial(sol_prev.value_variables())
t0 = perf_counter()
try:
sol = opti.solve()
except RuntimeError:
converged=False
break
sol_prev = sol
solve_times.append(perf_counter() - t0)
obj_hist.append(sol.value(cost_tot))
ctrl = sol.value(Y_state)[(T+1)*nx:].reshape((T, nu))[0]
u_curr = ctrl
x_curr = sol.value(Y_state)[:(T+1)*nx].reshape((T+1,nx))[1]
X_trj = np.r_[X_trj, x_curr.reshape(1,-1)]
U_trj = np.r_[U_trj, ctrl.reshape(1,-1)]
opti.subject_to()
iters += 1
t += dt
if iters > MAX_ITER:
converged = False
print(f'Max MPC iters reached; exiting MPC loops.....')
break
if np.all(util.distance_to_goal(x_curr.flatten(), xr.flatten(), n_agents, n_states) <= 0.1):
converged = True
obj_trj = float(util.objective(X_trj.T, U_trj.T, u_ref, xr, Q, R, Qf))
logging.info(
f'{n_trial},'
f'{n_agents},{t},{converged},'
f'{obj_trj},{T},{dt},{radius},{SOVA_admm},{np.mean(solve_times)}, {np.std(solve_times)}, {MAX_ITER},'
f'{util.distance_to_goal(X_trj[-1].flatten(), xr.flatten(), n_agents, n_states)},'
)
print(f'Distance to goal is {util.distance_to_goal(X_trj[-1].flatten(), xr.flatten(), n_agents, n_states)}!')
return X_trj, U_trj, obj_trj, np.mean(solve_times), obj_hist
def solve_mpc_centralized(n_agents, x0, xr, T, radius, Q, R, Qf, convex = False, n_trial = None):
solver_type = 'CentralizedMPC'
n_states = 6
n_inputs = 3
nx = n_agents * 6
nu = n_agents * 3
N = n_agents
opti = Opti()
Y_state = opti.variable((T+1)*nx + T*nu)
x_dims = [n_states]*n_agents
u_ref = np.array([0, 0, 0] * N).reshape(-1,1)
n_dims = [3]*n_agents
cost = 0
for t in range(T-1):
for idx in range(nx):
cost += (Y_state[:(T+1)*nx][t*nx:(t+1)*nx][idx]-xr[idx]) * \
Q[idx,idx]* (Y_state[:(T+1)*nx][t*nx:(t+1)*nx][idx]-xr[idx])
#Pair-wise Euclidean distance between each pair of agents
distances = util.compute_pairwise_distance_nd_Sym(Y_state[:(T+1)*nx][t*nx:(t+1)*nx], x_dims, n_dims)
#Collision avoidance cost
for dist in distances:
cost += fmin(0,(dist - 2*radius))**2 * 200
for t in range(T):
for idu in range(nu):
cost += (Y_state[(T+1)*nx:][t*nu:(t+1)*nu][idu] - u_ref[idu]) * \
R[idu,idu] * (Y_state[(T+1)*nx:][t*nu:(t+1)*nu][idu] - u_ref[idu])
for idf in range(nx):
cost += (Y_state[:(T+1)*nx][T*nx:(T+1)*nx][idf] - xr[idf]) * \
Qf[idf,idf] * (Y_state[:(T+1)*nx][T*nx:(T+1)*nx][idf] - xr[idf])
obj_hist = [np.inf]
x_curr = x0
X_trj = np.zeros((0, nx))
U_trj = np.zeros((0, nu))
X_trj = np.r_[X_trj, x0.T]
iters = 0
solve_times = []
t = 0
dt = 0.1
x_dims = [6]*N
n_dims = [3]*N
f = generate_f(x_dims)
while not np.all(util.distance_to_goal(x_curr.flatten(), xr.flatten(), n_agents, 6) <= 0.1):
for k in range(T):
k1 = f(Y_state[:(T+1)*nx][k*nx:(k+1)*nx], Y_state[(T+1)*nx:][k*nu:(k+1)*nu])
k2 = f(Y_state[:(T+1)*nx][k*nx:(k+1)*nx]+dt/2*k1, Y_state[(T+1)*nx:][k*nu:(k+1)*nu])
k3 = f(Y_state[:(T+1)*nx][k*nx:(k+1)*nx]+dt/2*k2, Y_state[(T+1)*nx:][k*nu:(k+1)*nu])
k4 = f(Y_state[:(T+1)*nx][k*nx:(k+1)*nx]+dt*k3, Y_state[(T+1)*nx:][k*nu:(k+1)*nu])
x_next = Y_state[:(T+1)*nx][k*nx:(k+1)*nx] + dt/6*(k1+2*k2+2*k3+k4)
opti.subject_to(Y_state[:(T+1)*nx][(k+1)*nx:(k+2)*nx]==x_next) # close the gaps
opti.subject_to(Y_state[(T+1)*nx:][k*nu:(k+1)*nu] <= np.tile(np.array([np.pi/6, np.pi/6, 20]),(N,)).reshape(-1,1))
opti.subject_to(np.tile(np.array([-np.pi/6, -np.pi/6, 0]),(N,)).reshape(-1,1) <= Y_state[(T+1)*nx:][k*nu:(k+1)*nu])
X0 = opti.parameter(x0.shape[0],1)
opti.subject_to(Y_state[0:nx] == X0)
cost_tot = cost
opti.minimize(cost_tot)
opti.solver("ipopt")
opti.set_value(X0,x_curr)
if iters > 0:
opti.set_initial(sol_prev.value_variables())
t0 = perf_counter()
try:
sol = opti.solve()
except RuntimeError:
converged=False
break
times = perf_counter() - t0
sol_prev = sol
solve_times.append(times)
cost_curr = sol.value(cost_tot)
obj_hist.append(cost_curr)
ctrl = sol.value(Y_state)[(T+1)*nx:].reshape((T, nu))[0]
x_curr = sol.value(Y_state)[:(T+1)*nx].reshape((T+1,nx))[1] #Same as above
X_trj = np.r_[X_trj, x_curr.reshape(1,-1)]
U_trj = np.r_[U_trj, ctrl.reshape(1,-1)]
opti.subject_to()
iters += 1
t += dt
if iters > 60:
converged = False
print(f'Max MPC iters reached; exiting MPC loops.....')
break
if np.all(util.distance_to_goal(x_curr.flatten(), xr.flatten(), n_agents, n_states) <= 0.1):
converged = True
cost_trj = util.evaluate_cost_trajectory(X_trj,U_trj,radius,x_dims,n_dims,xr,u_ref,Q,R,Qf)
logging.info(
f'{solver_type},{n_trial},{np.mean(solve_times)},{np.std(solve_times)},'
f'{n_agents},{iters},{cost_trj },'
)
return X_trj, U_trj, obj_hist
"""Nonlinear MPC, centralized"""
def solve_mpc_single_nonlinear(n_agents, x0, xr, T, Q, R, Qf):
"""This function computes the optimal control input over a single finite horizon T (no receding horizon implemented!)"""
n_states = 12
n_inputs = 4
N = n_agents
assert N == 1
opti = Opti()
X_state = opti.variable((T+1)*n_states) #Discrete state variable, concatenated along a horizon T+1
U_state = opti.variable(T*n_inputs) #Discrete state variable, concatenated along a horizon T
u_ref = np.array([0, 0, 0, 9.8/2]) #Reference input vector
cost = 0
#Running cost : x^T@Q@x + u^T@R@u
for t in range(T):
for i in range(Q.shape[0]):
cost += (X_state[t*n_states:(t+1)*n_states][i] - xr[i])* \
Q[i,i]*(X_state[t*n_states:(t+1)*n_states][i]-xr[i])
for j in range(R.shape[0]):
cost += (U_state[t*n_inputs:(t+1)*n_inputs][j] - u_ref[j]) * \
R[j,j] * (U_state[t*n_inputs:(t+1)*n_inputs][j] - u_ref[j])
#Terminal cost:
for i in range(Qf.shape[0]):
cost += (X_state[T*n_states:(T+1)*n_states][i] - xr[i]) * \
Qf[i,i] * (X_state[T*n_states:(T+1)*n_states][i]- xr[i])
# print(cost.is_scalar())
# obj_hist = [np.inf]
x_curr = x0
u_curr = np.zeros((n_inputs,1))
# X_trj = np.zeros((0, n_states))
# U_trj = np.zeros((0, n_inputs))
# X_trj = np.r_[X_trj, x0.T]
iters = 0
solve_times = []
t = 0
dt = 0.1
for k in range(T):
X_next = X_state[(k+1)*n_states:(k+2)*n_states]
X_curr = X_state[k*n_states:(k+1)*n_states]
U_curr = U_state[k*n_inputs:(k+1)*n_inputs]
# f = generate_f_12DOF(X_curr, U_curr)
k1 = generate_f_12DOF(X_curr,U_curr)
k2 = generate_f_12DOF(X_curr+dt/2*k1, U_curr)
k3 = generate_f_12DOF(X_curr+dt/2*k2, U_curr)
k4 = generate_f_12DOF(X_curr+dt*k3, U_curr)
x_update = X_curr + dt/6*(k1+2*k2+2*k3+k4)
opti.subject_to(X_next==x_update) # close the gap
opti.subject_to(U_curr <= np.array([2, 2, 2, 2.5*9.8])) #mass of the drone is 0.5 kg
opti.subject_to(np.array([-2, -2, -2, -2.5*9.8]) <= U_curr)
X0 = opti.parameter(x0.shape[0],1)
opti.subject_to(X_state[0:n_states] == X0)
opti.minimize(cost)
opti.solver("ipopt")
opti.set_value(X0,x_curr)
t0 = perf_counter()
try:
sol = opti.solve()
iter_time = perf_counter() - t0
except RuntimeError:
print("Runtime error encountered in single drone MPC !!! ")
iter_time = None
obj_val = None
return x_curr, u_curr, iter_time, obj_val
solve_times.append(perf_counter() - t0)
obj_val = sol.value(cost)
ctrl = sol.value(U_state).reshape((T, n_inputs))[0]
u_curr = ctrl
x_curr = sol.value(X_state).reshape((T+1,n_states))[1]
return x_curr, u_curr, iter_time, obj_val