mpc_python_learn/mpc_pybullet_demo/mpc_demo_nosim.py

219 lines
6.6 KiB
Python
Raw Normal View History

2020-01-13 20:25:26 +08:00
#! /usr/bin/env python
import numpy as np
import matplotlib.pyplot as plt
from matplotlib import animation
from utils import compute_path_from_wp
from cvxpy_mpc import optimize
import sys
import time
2020-01-14 21:37:28 +08:00
# Robot Starting position
2020-07-01 22:59:13 +08:00
SIM_START_X=0.
2020-07-01 00:21:27 +08:00
SIM_START_Y=0.5
2020-07-01 22:59:13 +08:00
SIM_START_V=0.
SIM_START_H=0.
L=0.3
2020-01-13 22:33:29 +08:00
2020-07-01 00:21:27 +08:00
from mpc_config import Params
P=Params()
2020-01-13 22:33:29 +08:00
# Classes
2020-01-13 20:25:26 +08:00
class MPC():
def __init__(self):
# State for the robot mathematical model [x,y,heading]
2020-07-01 22:59:13 +08:00
self.state = [SIM_START_X, SIM_START_Y, SIM_START_V, SIM_START_H]
2020-07-01 00:21:27 +08:00
self.opt_u = np.zeros((P.M,P.T))
2020-07-01 22:59:13 +08:00
self.opt_u[0,:] = 0.5 #m/ss
2020-01-13 20:25:26 +08:00
self.opt_u[1,:] = np.radians(0) #rad/s
# Interpolated Path to follow given waypoints
2020-07-01 00:21:27 +08:00
#self.path = compute_path_from_wp([0,10,12,2,4,14],[0,0,2,10,12,12])
2020-07-06 23:54:22 +08:00
self.path = compute_path_from_wp([0,3,4,6,10,12,13,13,6,1,0],
[0,0,2,4,3,3,-1,-2,-6,-2,-2],P.path_tick)
2020-01-13 20:25:26 +08:00
2020-01-13 22:33:29 +08:00
# Sim help vars
self.sim_time=0
self.x_history=[]
self.y_history=[]
self.v_history=[]
2020-07-01 22:59:13 +08:00
self.h_history=[]
self.a_history=[]
self.d_history=[]
2020-05-05 00:36:23 +08:00
self.predicted=None
2020-01-13 22:33:29 +08:00
2020-01-13 20:25:26 +08:00
#Initialise plot
plt.style.use("ggplot")
self.fig = plt.figure()
plt.ion()
plt.show()
2020-05-05 00:36:23 +08:00
def predict_motion(self):
'''
'''
predicted=np.zeros(self.opt_u.shape)
x=self.state[0]
y=self.state[1]
2020-07-01 22:59:13 +08:00
v=self.state[2]
th=self.state[3]
for idx,a,delta in zip(range(len(self.opt_u[0,:])),self.opt_u[0,:],self.opt_u[1,:]):
2020-07-01 00:21:27 +08:00
x = x+v*np.cos(th)*P.dt
y = y+v*np.sin(th)*P.dt
2020-07-01 22:59:13 +08:00
v = v+a*P.dt
th = th + v*np.tan(delta)/L*P.dt
2020-05-05 00:36:23 +08:00
predicted[0,idx]=x
predicted[1,idx]=y
self.predicted = predicted
2020-01-13 20:25:26 +08:00
def run(self):
'''
'''
self.plot_sim()
input("Press Enter to continue...")
2020-01-13 20:25:26 +08:00
while 1:
if self.state is not None:
if np.sqrt((self.state[0]-self.path[0,-1])**2+(self.state[1]-self.path[1,-1])**2)<0.1:
2020-03-04 20:32:29 +08:00
print("Success! Goal Reached")
input("Press Enter to continue...")
2020-03-04 20:32:29 +08:00
return
2020-01-13 20:25:26 +08:00
#optimization loop
start=time.time()
self.opt_u = optimize(self.state,
self.opt_u,
self.path)
2020-03-04 20:32:29 +08:00
# print("CVXPY Optimization Time: {:.4f}s".format(time.time()-start))
2020-01-13 20:25:26 +08:00
self.update_sim(self.opt_u[0,1],self.opt_u[1,1])
2020-05-05 00:36:23 +08:00
self.predict_motion()
2020-01-13 20:25:26 +08:00
self.plot_sim()
2020-07-01 22:59:13 +08:00
def update_sim(self,acc,steer):
2020-01-13 20:25:26 +08:00
'''
Updates state.
:param lin_v: float
:param ang_v: float
'''
2020-07-01 22:59:13 +08:00
self.state[0] = self.state[0] +self.state[2]*np.cos(self.state[3])*P.dt
self.state[1] = self.state[1] +self.state[2]*np.sin(self.state[3])*P.dt
self.state[2] = self.state[2] +acc*P.dt
self.state[3] = self.state[3] + self.state[2]*np.tan(steer)/L*P.dt
2020-01-13 20:25:26 +08:00
def plot_sim(self):
2020-01-13 22:33:29 +08:00
2020-07-01 00:21:27 +08:00
self.sim_time = self.sim_time+P.dt
2020-01-13 22:33:29 +08:00
self.x_history.append(self.state[0])
self.y_history.append(self.state[1])
2020-07-01 22:59:13 +08:00
self.v_history.append(self.state[2])
self.h_history.append(self.state[3])
self.a_history.append(self.opt_u[0,1])
self.d_history.append(self.opt_u[1,1])
2020-01-13 22:33:29 +08:00
2020-01-13 20:25:26 +08:00
plt.clf()
2020-01-13 22:33:29 +08:00
grid = plt.GridSpec(2, 3)
2020-01-13 20:25:26 +08:00
2020-01-14 21:37:28 +08:00
plt.subplot(grid[0:2, 0:2])
plt.title("MPC Simulation \n" + "Simulation elapsed time {}s".format(self.sim_time))
2020-01-13 22:33:29 +08:00
2020-03-04 20:32:29 +08:00
plt.plot(self.path[0,:],self.path[1,:], c='tab:orange',
marker=".",
label="reference track")
plt.plot(self.x_history, self.y_history, c='tab:blue',
marker=".",
alpha=0.5,
label="vehicle trajectory")
2020-05-05 00:36:23 +08:00
if self.predicted is not None:
plt.plot(self.predicted[0,:], self.predicted[1,:], c='tab:green',
marker="+",
2020-05-05 00:36:23 +08:00
alpha=0.5,
label="mpc opt trajectory")
2020-03-04 20:32:29 +08:00
# plt.plot(self.x_history[-1], self.y_history[-1], c='tab:blue',
# marker=".",
# markersize=12,
# label="vehicle position")
# plt.arrow(self.x_history[-1],
# self.y_history[-1],
# np.cos(self.h_history[-1]),
# np.sin(self.h_history[-1]),
# color='tab:blue',
# width=0.2,
# head_length=0.5,
# label="heading")
plot_car(self.x_history[-1], self.y_history[-1], self.h_history[-1])
2020-01-13 22:33:29 +08:00
plt.ylabel('map y')
2020-03-04 20:32:29 +08:00
plt.yticks(np.arange(min(self.path[1,:])-1., max(self.path[1,:]+1.)+1, 1.0))
2020-01-13 22:33:29 +08:00
plt.xlabel('map x')
2020-03-04 20:32:29 +08:00
plt.xticks(np.arange(min(self.path[0,:])-1., max(self.path[0,:]+1.)+1, 1.0))
2020-07-01 00:21:27 +08:00
plt.axis("equal")
2020-03-04 20:32:29 +08:00
#plt.legend()
2020-01-13 22:33:29 +08:00
plt.subplot(grid[0, 2])
2020-01-14 21:37:28 +08:00
#plt.title("Linear Velocity {} m/s".format(self.v_history[-1]))
2020-07-01 22:59:13 +08:00
plt.plot(self.a_history,c='tab:orange')
2020-03-04 20:32:29 +08:00
locs, _ = plt.xticks()
2020-07-01 00:21:27 +08:00
plt.xticks(locs[1:], locs[1:]*P.dt)
2020-07-01 22:59:13 +08:00
plt.ylabel('a(t) [m/ss]')
2020-03-04 20:32:29 +08:00
plt.xlabel('t [s]')
2020-01-13 22:33:29 +08:00
plt.subplot(grid[1, 2])
2020-01-14 21:37:28 +08:00
#plt.title("Angular Velocity {} m/s".format(self.w_history[-1]))
2020-07-01 22:59:13 +08:00
plt.plot(np.degrees(self.d_history),c='tab:orange')
2020-07-06 23:54:22 +08:00
plt.ylabel('gamma(t) [deg]')
2020-03-04 20:32:29 +08:00
locs, _ = plt.xticks()
2020-07-01 00:21:27 +08:00
plt.xticks(locs[1:], locs[1:]*P.dt)
2020-03-04 20:32:29 +08:00
plt.xlabel('t [s]')
2020-01-13 22:33:29 +08:00
plt.tight_layout()
2020-01-13 20:25:26 +08:00
plt.draw()
plt.pause(0.1)
2020-03-04 20:32:29 +08:00
def plot_car(x, y, yaw):
LENGTH = 0.5 # [m]
WIDTH = 0.25 # [m]
2020-07-01 22:59:13 +08:00
OFFSET = LENGTH # [m]
2020-03-04 20:32:29 +08:00
outline = np.array([[-OFFSET, (LENGTH - OFFSET), (LENGTH - OFFSET), -OFFSET, -OFFSET],
[WIDTH / 2, WIDTH / 2, - WIDTH / 2, -WIDTH / 2, WIDTH / 2]])
Rotm = np.array([[np.cos(yaw), np.sin(yaw)],
[-np.sin(yaw), np.cos(yaw)]])
outline = (outline.T.dot(Rotm)).T
outline[0, :] += x
outline[1, :] += y
plt.plot(np.array(outline[0, :]).flatten(), np.array(outline[1, :]).flatten(), 'tab:blue')
2020-01-13 20:25:26 +08:00
def do_sim():
sim=MPC()
try:
sim.run()
except Exception as e:
sys.exit(e)
if __name__ == '__main__':
do_sim()