-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathmpc.py
292 lines (266 loc) · 11.5 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
"""
Created on Fri Mar 15 01:10:46 2019
Nonlinear Model Predictive Control
# CasADi -- A symbolic framework for dynamic optimization.
# Copyright (C) 2010-2014 Joel Andersson, Joris Gillis, Moritz Diehl,
# K.U. Leuven. All rights reserved.
# Copyright (C) 2011-2014 Greg Horn
# CasADi is free software; you can redistribute it and/or
# modify it under the terms of the GNU Lesser General Public
# License as published by the Free Software Foundation; either
# version 3 of the License, or (at your option) any later version.
#
# CasADi is distributed in the hope that it will be useful,
# but WITHOUT ANY WARRANTY; without even the implied warranty of
# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
# Lesser General Public License for more details.
#
# You should have received a copy of the GNU Lesser General Public
# License along with CasADi; if not, write to the Free Software
# Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
source: https://web.casadi.org/
@author: rapha
"""
import numpy as np
from sys import path
import vtkplotter as vtk
#path.append(r"C:\Users\rapha\Documents\Projects\casadi-windows-py36-v3.4.5-64bit")
from casadi import *
import copy
import math
import matplotlib.pyplot as plt
DEFAULT_A = np.array([0,0]).reshape((1,2))
class NonlinearMPC():
def __init__(self, N, dT, lr, vp, A=None, C=None):
self.N = N # prediction horizon in seconds
self.dT = dT # timestep
self.H = int(N/dT) # prrdiction horizon steps
print(self.H, "times steps")
self.u_1 = np.zeros((self.H+1)) # acceleration control
self.u_2 = np.zeros((self.H+1)) # steering velocity control
self.warm_x = np.zeros((5,self.H+1))
self.lr = lr
self.vp = vp
if (A is not None):
self.warm_lam = np.zeros((A.shape[0], self.H+1))
if (C is not None):
self.warm_lam2 = np.zeros((C.shape[0], self.H+1))
def MPC(self, states, path, agent, A=None, b=None, C=None, d=None):
"""
Inputs:
A: polyhedron normals defining velocity object
b: polyhedron offsets defining velocity object
C: polyhedron normals defining static obstacles
d: polyhedron offsets defining static obstacles
"""
opti = Opti() # Optimization problem
# system states and controls
X = opti.variable(5, self.H+1) # state trajectory
x = X[0,:]
y = X[1,:]
theta = X[2,:]
v = X[3,:]
phi = X[4,:]
U = opti.variable(2,self.H+1) # control trajectory (acceleration and steering velocity)
a = U[0,:]
steer_angle = U[1,:]
#if we have velocity obstacles
if (A is not None):
lam = opti.variable(A.shape[0], self.H+1) #dual variables for obstacle opt
slack = opti.variable(self.H+1) #dual variables for obstacle opt
if (C is not None):
lam2 = opti.variable(C.shape[0], self.H+1) #dual variables for obstacle opt
mu2 = opti.variable(C.shape[0], self.H+1)#dual variable for full-bodied agent
slack2 = opti.variable(self.H+1)
"""Define Cost function"""
def cost(i):
total = 0
#path tracking
#distance from path
total += .1 * ((x[i]-path[0][i])**2+(y[i]-path[1][i])**2)
#distance from end
total += 10 * ((x[i]-path[0][-1])**2+(y[i]-path[1][-1])**2)
#shallow steering
total += .1 *steer_angle[i]*steer_angle[i]
#acceleration
total += .1 * a[i] * a[i]
#jerk
if (i > 0):
total += (a[i] - a[i-1])**2
#velocity obstacles (slack)
if (A is not None):
total += 300 * slack[i]
#static obstacles
if (C is not None):
total += 300 * slack2[i]
return total
V = 0
for i in range(self.H+1):
if i < len(path[0]):
V += cost(i)
else:
V += cost(-1)
opti.minimize(V)
"""System Dynamics"""
f = lambda x,u: vertcat(x[3,:]*casadi.cos(x[2,:]),
x[3,:]*casadi.sin(x[2,:]),
x[3,:]*casadi.tan(x[4,:])/self.lr,
u[0,:],
u[1,:])
"""System Constraints"""
opti.bounded(-math.pi, X[2,:], math.pi)
opti.bounded(-50, X[3,:], 50)
opti.bounded(-math.pi/3, X[4,:], math.pi/3)
opti.subject_to(opti.bounded(-5.0, a, 5.0))
opti.subject_to(opti.bounded(-math.radians(50.0), steer_angle, math.radians(50.0)))
for k in range(self.H): # loop over control intervals
k1 = f(X[:,k], U[:,k])
x_next = X[:,k] + self.dT*k1
opti.subject_to(X[:,k+1]==x_next)
opti.subject_to(x[k] - x[k+1] < 1) # limit velocity
"""add the velocity obstacle constraint"""
if (A is not None):
for k in range(self.H+1): # loop over lambdas
# (Ap - b)'lambda > 0
vel_x = v[k] * (casadi.cos(theta[k])) + x[k]
vel_y = v[k] * (casadi.sin(theta[k])) + y[k]
Av = A[:,0] * vel_x + A[:,1] * vel_y
opti.subject_to((Av-b).T @ lam[:,k] > -slack[k])
opti.subject_to(lam[:,k] >= 0)
opti.subject_to(slack[k] >= 0)
norm = lam[:,k].T @ A @ A.T @ lam[:,k]
opti.subject_to(norm == 1)
"""Add static obstacle constraint"""
Rot = lambda theta : casadi.blockcat([
[casadi.cos(theta), -casadi.sin(theta)],
[casadi.sin(theta), casadi.cos(theta)],
])
G = agent.G
g = agent.g
if (C is not None):
for k in range(self.H+1): # loop over lambdas
#eq (18) from https://arxiv.org/pdf/1711.03449.pdf
opti.subject_to((C @ X[:2,k]-d).T @ lam2[:,k]
> 1 - slack2[k])
#we rotate G
# opti.subject_to(G.T + Rot(theta[k]).T @ C.T @ lam2[:,k] == 0)
norm = lam2[:,k].T @ C @ C.T @ lam2[:,k]
opti.subject_to(norm == 1)
opti.subject_to(lam2[:,k] >= 0)
opti.subject_to(mu2[:,k] >= 0)
opti.subject_to(slack2[k] >= 0)
"""Initial Conditions"""
opti.subject_to(x[0]==states[0])
opti.subject_to(y[0]==states[1])
opti.subject_to(theta[0]==states[2])
opti.subject_to(v[0]==states[3])
opti.subject_to(phi[0]==states[4])
"""Warm Start"""
for n in range(self.H+1):
opti.set_initial(U[0,n], self.u_1[n])
opti.set_initial(U[1,n], self.u_2[n])
opti.set_initial(X[:,n], self.warm_x[:,n])
if (A is not None):
opti.set_initial(lam[:,n], self.warm_lam[:,n])
if (C is not None):
opti.set_initial(lam2[:,n], self.warm_lam2[:,n])
# solve NLP
p_opts = {"expand":True}
s_opts = {"max_iter": 1000,
"hessian_approximation":"exact",
"mumps_pivtol":1e-6,
"alpha_for_y":"min",
"recalc_y":"yes",
"mumps_mem_percent":6000,
"tol":1e-5,
"print_level":0,
"min_hessian_perturbation":1e-12,
"jacobian_regularization_value":1e-7
}
opti.solver("ipopt", p_opts, s_opts)
try:
sol = opti.solve()
print("acc: ", sol.value(U[0,0]))
print("steering: ", sol.value(U[1,0]))
control = np.array([sol.value(U[0,:]), sol.value(U[1,:])])
print("control shape: " , control.shape)
"""Populate Warm Start"""
for i in range(self.H):
self.u_1[i] = copy.deepcopy(sol.value(U[0,i+1]))
self.u_2[i] = copy.deepcopy(sol.value(U[1,i+1]))
self.warm_x[:,i] = copy.deepcopy(sol.value(X[:,i+1]))
if (A is not None):
self.warm_lam[:,i] = copy.deepcopy(sol.value(lam[:,i+1]))
if (C is not None):
self.warm_lam2[:,i] = copy.deepcopy(sol.value(lam2[:,i+1]))
self.u_1[-1] = 0
self.u_2[-1] = 0
self.warm_x[:,-1] = np.zeros((5))
"""Begin Debugging Section"""
x = sol.value(x)
y = sol.value(X[1,:])
theta = sol.value(X[2,:])
v = sol.value(X[3,:])
phi = sol.value(X[4,:])
theta = sol.value(theta)
if (A is not None):
slack = sol.value(slack)
print("Slack cost is: ", slack)
if (C is not None):
slack2 = sol.value(slack2)
print("Slack cost is: ", slack2)
"""Visualizing Planned Velocities"""
viz = []
if (True and A is not None):
# for i in range(len(v)):
i=0
pos = [x[i], y[i]]
velxy = v[i] * np.array([np.cos(theta[i]), np.sin(theta[i])])
velxy += pos
# self.vp += [vtk.shapes.Sphere(list(velxy)+[0], c="green", r=.1)]
vels = np.random.normal(loc=velxy.reshape(2,1), scale=4, size=(2,2000))
show = np.all(np.greater(b, A@vels), axis=0)
# self.vp += [vtk.shapes.Sphere(list(v)+[0], c="purple", r=.05)
# for v,s in zip(vels.T, show.T) if s]
# self.vp.show(interactive=1)
# for i in range(len(v)):
# pos = [x[i], y[i]]
# velxy = v[i] * np.array([np.cos(phi[i]), np.sin(phi[i])])
# velxy += pos
# #viz += [vtk.shapes.Sphere(list(velxy)+[0], c="green", r=.1)]
#
# vel_x = v[i] * (casadi.cos(theta[i])) + x[i]
# vel_y = v[i] * (casadi.sin(theta[i])) + y[i]
# Av = A[:,0] * vel_x + A[:,1] * vel_y
# print("Av-b for ", i, " is: ", Av-b)
# print("Av-b.T @ lam is : ", (Av-b).T @ lam[:,i])
# print("-Slack is: ", -slack[i])
return control, viz
except:
"""Begin Debugging Section"""
states = opti.debug.value(X)
x = opti.debug.value(x)
y = opti.debug.value(X[1,:])
theta = opti.debug.value(X[2,:])
v = opti.debug.value(X[3,:])
phi = opti.debug.value(X[4,:])
theta = opti.debug.value(theta)
if (A is not None):
slack = opti.debug.value(slack)
print("Slack cost is: ", slack)
if (C is not None):
slack2 = opti.debug.value(slack2)
print("Slack2 cost is: ", slack2)
xys = states[:2,:].T
viz = [vtk.shapes.Circle(pos=list(p)+[0],r=.1, c="darkred") for p in xys]
print("NMPC failed", sys.exc_info())
self.vp.show(interactive=0)
# in case it fails use previous computed controls and shift it
control = np.array([self.u_1[:], self.u_2[:]])
print("control shape: ", control.shape)
for i in range(self.H):
self.u_1[i] = self.u_1[i+1]
self.u_2[i] = self.u_2[i+1]
self.u_1[-1] = 0
self.u_2[-1] = 0
return control, viz