|
7 | 7 | """ |
8 | 8 |
|
9 | 9 | import matplotlib.pyplot as plt |
| 10 | +import numpy as np |
| 11 | +import scipy.linalg as la |
| 12 | +import math |
10 | 13 |
|
11 | 14 | show_animation = True |
12 | 15 |
|
| 16 | +MAX_TIME = 100.0 |
| 17 | +DT = 0.1 |
| 18 | + |
13 | 19 |
|
14 | 20 | def LQRplanning(sx, sy, gx, gy): |
15 | 21 |
|
16 | | - rx, ry = [], [] |
| 22 | + rx, ry = [sx], [sy] |
| 23 | + |
| 24 | + x = np.matrix([gx - sx, gy - sy]).T # State vector |
| 25 | + |
| 26 | + # Linear system model |
| 27 | + A, B = get_system_model() |
| 28 | + |
| 29 | + time = 0.0 |
| 30 | + |
| 31 | + while time <= MAX_TIME: |
| 32 | + time += DT |
| 33 | + |
| 34 | + u = LQR_control(A, B, x) |
| 35 | + |
| 36 | + x = A * x + B * u |
| 37 | + |
| 38 | + rx.append(x[0, 0]) |
| 39 | + ry.append(x[1, 0]) |
| 40 | + |
| 41 | + plt.plot(rx, ry) |
| 42 | + plt.plot(rx[-1], ry[-1], "xr") |
| 43 | + plt.pause(1.0) |
| 44 | + |
| 45 | + d = math.sqrt((gx - x[0, 0])**2 + (gy - x[1, 0])**2) |
| 46 | + print(d) |
| 47 | + if d <= 0.1: |
| 48 | + print("Goal!!") |
| 49 | + break |
17 | 50 |
|
18 | 51 | return rx, ry |
19 | 52 |
|
20 | 53 |
|
| 54 | +def solve_DARE(A, B, Q, R): |
| 55 | + """ |
| 56 | + solve a discrete time_Algebraic Riccati equation (DARE) |
| 57 | + """ |
| 58 | + X = Q |
| 59 | + maxiter = 150 |
| 60 | + eps = 0.01 |
| 61 | + |
| 62 | + for i in range(maxiter): |
| 63 | + Xn = A.T * X * A - A.T * X * B * \ |
| 64 | + la.inv(R + B.T * X * B) * B.T * X * A + Q |
| 65 | + if (abs(Xn - X)).max() < eps: |
| 66 | + X = Xn |
| 67 | + break |
| 68 | + X = Xn |
| 69 | + |
| 70 | + return Xn |
| 71 | + |
| 72 | + |
| 73 | +def dlqr(A, B, Q, R): |
| 74 | + """Solve the discrete time lqr controller. |
| 75 | + x[k+1] = A x[k] + B u[k] |
| 76 | + cost = sum x[k].T*Q*x[k] + u[k].T*R*u[k] |
| 77 | + # ref Bertsekas, p.151 |
| 78 | + """ |
| 79 | + |
| 80 | + # first, try to solve the ricatti equation |
| 81 | + X = solve_DARE(A, B, Q, R) |
| 82 | + |
| 83 | + # compute the LQR gain |
| 84 | + K = np.matrix(la.inv(B.T * X * B + R) * (B.T * X * A)) |
| 85 | + |
| 86 | + eigVals, eigVecs = la.eig(A - B * K) |
| 87 | + |
| 88 | + return K, X, eigVals |
| 89 | + |
| 90 | + |
| 91 | +def get_system_model(): |
| 92 | + A = np.eye(2) * DT |
| 93 | + A[0, 1] = 1.0 |
| 94 | + B = np.matrix([0.0, 1.0]).T |
| 95 | + |
| 96 | + return A, B |
| 97 | + |
| 98 | + |
| 99 | +def LQR_control(A, B, x): |
| 100 | + |
| 101 | + Kopt, X, ev = dlqr(A, B, np.eye(2), np.eye(1)) |
| 102 | + |
| 103 | + u = -Kopt * x |
| 104 | + |
| 105 | + return u |
| 106 | + |
| 107 | + |
21 | 108 | def main(): |
22 | 109 | print(__file__ + " start!!") |
23 | 110 |
|
24 | | - sx = 0.0 |
25 | | - sy = 0.0 |
26 | | - gx = 10.0 |
27 | | - gy = 5.0 |
| 111 | + sx = -10.0 |
| 112 | + sy = -5.0 |
| 113 | + gx = 0.0 |
| 114 | + gy = 0.0 |
28 | 115 |
|
29 | 116 | rx, ry = LQRplanning(sx, sy, gx, gy) |
30 | 117 |
|
|
0 commit comments