-
Notifications
You must be signed in to change notification settings - Fork 0
/
sim_3_mpc_obs_avoid_mul.py
150 lines (130 loc) · 4.75 KB
/
sim_3_mpc_obs_avoid_mul.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
#!/usr/bin/env python
# -*- coding: utf-8 -*-
import casadi as ca
import casadi.tools as ca_tools
import numpy as np
import time
from draw import Draw_MPC_Obstacle
def shift_movement(T, t0, x0, u, x_f, f):
f_value = f(x0, u[:, 0])
st = x0 + T * f_value.full()
t = t0 + T
u_end = np.concatenate((u[:, 1:], u[:, -1:]), axis=1)
x_f = np.concatenate((x_f[:, 1:], x_f[:, -1:]), axis=1)
return t, st, u_end, x_f
if __name__ == '__main__':
T = 0.2 # sampling time [s]
N = 100 # prediction horizon
rob_diam = 1.0 # [m]
v_max = 1.6
omega_max = np.pi / 6.0
x = ca.SX.sym('x')
y = ca.SX.sym('y')
theta = ca.SX.sym('theta')
states = ca.vertcat(x, y)
states = ca.vertcat(states, theta)
n_states = states.size()[0]
v = ca.SX.sym('v')
omega = ca.SX.sym('omega')
controls = ca.vertcat(v, omega)
n_controls = controls.size()[0]
## rhs
rhs = ca.vertcat(v * ca.cos(theta), v * ca.sin(theta))
rhs = ca.vertcat(rhs, omega)
## function
f = ca.Function('f', [states, controls], [rhs], ['input_state', 'control_input'], ['rhs'])
## for MPC
U = ca.SX.sym('U', n_controls, N)
X = ca.SX.sym('X', n_states, N + 1)
P = ca.SX.sym('P', n_states + n_states)
### define
Q = np.array([[10.0, 0.0, 0.0], [0.0, 50.0, 0.0], [0.0, 0.0, .1]])
R = np.array([[0.5, 0.0], [0.0, 0.05]])
#### cost function
obj = 0 #### cost
g = [] # equal constrains
g.append(X[:, 0] - P[:3])
for i in range(N):
obj = obj + ca.mtimes([(X[:, i] - P[3:]).T, Q, X[:, i] - P[3:]]) + ca.mtimes([U[:, i].T, R, U[:, i]])
x_next_ = f(X[:, i], U[:, i]) * T + X[:, i]
g.append(X[:, i + 1] - x_next_)
#### constraints
obs_x = 2
obs_y = 2
obs_diam = 0.3
for i in range(N + 1):
g.append(ca.sqrt((X[0, i] - obs_x) ** 2 + (X[1, i] - obs_y) ** 2)) # should be smaller als 0.0
opt_variables = ca.vertcat(ca.reshape(U, -1, 1), ca.reshape(X, -1, 1))
nlp_prob = {'f': obj, 'x': opt_variables, 'p': P, 'g': ca.vertcat(*g)}
opts_setting = {'ipopt.max_iter': 100, 'ipopt.print_level': 0, 'print_time': 0, 'ipopt.acceptable_tol': 1e-8,
'ipopt.acceptable_obj_change_tol': 1e-6}
solver = ca.nlpsol('solver', 'ipopt', nlp_prob, opts_setting)
lbg = []
ubg = []
lbx = []
ubx = []
for _ in range(N + 1):
lbg.append(0.0)
lbg.append(0.0)
lbg.append(0.0)
ubg.append(0.0)
ubg.append(0.0)
ubg.append(0.0)
for _ in range(N + 1):
lbg.append(0.3)
ubg.append(np.inf)
for _ in range(N):
lbx.append(-v_max)
lbx.append(-omega_max)
ubx.append(v_max)
ubx.append(omega_max)
for _ in range(N + 1): # note that this is different with the method using structure
lbx.append(-2.0)
lbx.append(-2.0)
lbx.append(-np.inf)
ubx.append(2.0)
ubx.append(2.0)
ubx.append(np.inf)
# Simulation
t0 = 0.0
x0 = np.array([0.0, 0.0, 0.0]).reshape(-1, 1) # initial state
x0_ = x0.copy()
x_m = np.zeros((n_states, N + 1))
next_states = x_m.copy()
xs = np.array([5, 5, 0.0]).reshape(-1, 1) # final state
u0 = np.array([1, 2] * N).reshape(-1, 2).T # np.ones((N, 2)) # controls
x_c = [] # contains for the history of the state
u_c = []
t_c = [t0] # for the time
xx = []
sim_time = 20.0
## start MPC
mpciter = 0
start_time = time.time()
index_t = []
while (np.linalg.norm(x0 - xs) > 1e-2 and mpciter - sim_time / T < 0.0 and mpciter < 50):
## set parameter
c_p = np.concatenate((x0, xs))
# print('{0}'.format(next_states))
# print('{0}'.format(next_states.T.reshape(-1, 1)[:6]))
init_control = np.concatenate((u0.T.reshape(-1, 1), next_states.T.reshape(-1, 1)))
t_ = time.time()
res = solver(x0=init_control, p=c_p, lbg=lbg, lbx=lbx, ubg=ubg, ubx=ubx)
index_t.append(time.time() - t_)
estimated_opt = res['x'].full() # the feedback is in the series [u0, x0, u1, x1, ...]
u0 = estimated_opt[:200].reshape(N, n_controls).T # (n_controls, N)
x_m = estimated_opt[200:].reshape(N + 1, n_states).T # [n_states, N]
x_c.append(x_m.T)
u_c.append(u0[:, 0])
t_c.append(t0)
t0, x0, u0, next_states = shift_movement(T, t0, x0, u0, x_m, f)
x0 = ca.reshape(x0, -1, 1)
x0 = x0.full()
xx.append(x0)
mpciter = mpciter + 1
print(mpciter)
t_v = np.array(index_t)
print(t_v.mean())
print((time.time() - start_time) / (mpciter))
draw_result = Draw_MPC_Obstacle(rob_diam=0.3, init_state=x0_, target_state=xs, robot_states=xx,
obstacle=np.array([obs_x, obs_y, obs_diam / 2.]), export_fig=True)