mpc_python_learn/notebook/MPC_cvxpy.ipynb

1442 lines
246 KiB
Plaintext

{
"cells": [
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": []
},
{
"cell_type": "code",
"execution_count": 2,
"metadata": {},
"outputs": [],
"source": [
"import numpy as np\n",
"from scipy.integrate import odeint\n",
"from scipy.interpolate import interp1d\n",
"import cvxpy as cp\n",
"\n",
"import matplotlib.pyplot as plt\n",
"plt.style.use(\"ggplot\")\n",
"\n",
"import time"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"### kinematics model equations\n",
"\n",
"The variables of the model are:\n",
"\n",
"* $x$ coordinate of the robot\n",
"* $y$ coordinate of the robot\n",
"* $\\theta$ heading of the robot\n",
"* $\\psi$ heading error = $\\psi = \\theta_{ref} - \\theta$\n",
"* $cte$ crosstrack error = lateral distance of the robot from the path \n",
"\n",
"The inputs of the model are:\n",
"\n",
"* $v$ linear velocity of the robot\n",
"* $w$ angular velocity of the robot\n",
"\n",
"These are the differential equations f(x,u) of the model:\n",
"\n",
"* $\\dot{x} = v\\cos{\\theta}$ \n",
"* $\\dot{y} = v\\sin{\\theta}$\n",
"* $\\dot{\\theta} = w$\n",
"* $\\dot{\\psi} = -w$\n",
"* $\\dot{cte} = v\\sin{-\\psi}$\n",
"\n",
"The **Continuous** State Space Model is\n",
"\n",
"$ {\\dot{x}} = Ax + Bu $\n",
"\n",
"with:\n",
"\n",
"$ A =\n",
"\\quad\n",
"\\begin{bmatrix}\n",
"\\frac{\\partial f(x,u)}{\\partial x} & \\frac{\\partial f(x,u)}{\\partial y} & \\frac{\\partial f(x,u)}{\\partial \\theta} & \\frac{\\partial f(x,u)}{\\partial \\psi} & \\frac{\\partial f(x,u)}{\\partial cte} \\\\\n",
"\\end{bmatrix}\n",
"\\quad\n",
"=\n",
"\\quad\n",
"\\begin{bmatrix}\n",
"0 & 0 & -vsin(\\theta) & 0 & 0 \\\\\n",
"0 & 0 & vcos(\\theta) & 0 & 0 \\\\\n",
"0 & 0 & 0 & 0 & 0 \\\\\n",
"0 & 0 & 0 & 0 & 0 \\\\\n",
"0 & 0 & 0 & -vcos(-\\psi) & 0 \n",
"\\end{bmatrix}\n",
"\\quad $\n",
"\n",
"\n",
"$ B = \\quad\n",
"\\begin{bmatrix}\n",
"\\frac{\\partial f(x,u)}{\\partial v} & \\frac{\\partial f(x,u)}{\\partial w} \\\\\n",
"\\end{bmatrix}\n",
"\\quad\n",
"=\n",
"\\quad\n",
"\\begin{bmatrix}\n",
"\\cos{\\theta_t} & 0 \\\\\n",
"\\sin{\\theta_t} & 0 \\\\\n",
"0 & 1 \\\\\n",
"0 & -1 \\\\\n",
"-\\sin{(-\\psi_t)} & 0 \n",
"\\end{bmatrix}\n",
"\\quad $\n",
"\n",
"discretize with forward Euler Integration for time step dt:\n",
"\n",
"* ${x_{t+1}} = x_{t} + v_t\\cos{\\theta}*dt$\n",
"* ${y_{t+1}} = y_{t} + v_t\\sin{\\theta}*dt$\n",
"* ${\\theta_{t+1}} = \\theta_{t} + w_t*dt$\n",
"* ${\\psi_{t+1}} = \\psi_{t} - w_t*dt$\n",
"* ${cte_{t+1}} = cte_{t} + v_t\\sin{-\\psi}*dt$\n",
"\n",
"The **Discrete** State Space Model is then:\n",
"\n",
"${x_{t+1}} = Ax_t + Bu_t $\n",
"\n",
"with:\n",
"\n",
"$\n",
"A = \\quad\n",
"\\begin{bmatrix}\n",
"1 & 0 & -v\\sin{\\theta}dt & 0 & 0 \\\\\n",
"0 & 1 & v\\cos{\\theta}dt & 0 & 0 \\\\\n",
"0 & 0 & 1 & 0 & 0 \\\\\n",
"0 & 0 & 0 & 1 & 0 \\\\\n",
"0 & 0 & 0 & -vcos{(-\\psi)}dt & 1 \n",
"\\end{bmatrix}\n",
"\\quad\n",
"$\n",
"\n",
"$\n",
"B = \\quad\n",
"\\begin{bmatrix}\n",
"\\cos{\\theta_t}dt & 0 \\\\\n",
"\\sin{\\theta_t}dt & 0 \\\\\n",
"0 & dt \\\\\n",
"0 & -dt \\\\\n",
"-\\sin{-\\psi_t}dt & 0 \n",
"\\end{bmatrix}\n",
"\\quad\n",
"$\n",
"\n",
"This State Space Model is **non-linear** (A,B are time changing), to linearize it the **Taylor's series expansion** is used around $\\bar{x}$ and $\\bar{u}$:\n",
"\n",
"$ \\dot{x} = f(x,u) \\approx f(\\bar{x},\\bar{u}) + A(x-\\bar{x}) + B(u-\\bar{u})$\n",
"\n",
"So:\n",
"\n",
"$ x_{t+1} = x_t + (f(\\bar{x},\\bar{u}) + A(x_t-\\bar{x}) + B(u_t-\\bar{u}) )dt $\n",
"\n",
"$ x_{t+1} = (I+dtA)x_t + dtBu_t +dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\bar{u}))$\n",
"\n",
"The Discrete linearized kinematics model is\n",
"\n",
"$ x_{t+1} = A'x_t + B' u_t + C' $\n",
"\n",
"with:\n",
"\n",
"$ A' = I+dtA $\n",
"\n",
"$ B' = dtB $\n",
"\n",
"$ C' = dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\bar{u}) $"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"------------------\n",
"NB: psi and cte are expressed w.r.t. the track as reference frame.\n",
"In the reference frame of the veicle the equtions would be:\n",
"* psi_dot = w\n",
"* cte_dot = sin(psi)\n",
"-----------------"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"-----------------\n",
"[About Taylor Series Expansion](https://courses.engr.illinois.edu/ece486/fa2017/documents/lecture_notes/state_space_p2.pdf):\n",
"\n",
"In order to linearize general nonlinear systems, we will use the Taylor Series expansion of functions.\n",
"\n",
"Typically it is possible to assume that the system is operating about some nominal\n",
"state solution $\\bar{x}$ (possibly requires a nominal input $\\bar{u}$) called **equilibrium point**.\n",
"\n",
"Recall that the Taylor Series expansion of f(x) around the\n",
"point $\\bar{x}$ is given by:\n",
"\n",
"$f(x)=f(\\bar{x}) + \\frac{df(x)}{dx}|_{x=\\bar{x}}(x-\\bar{x})$ + higher order terms...\n",
"\n",
"For x sufficiently close to $\\bar{x}$, these higher order terms will be very close to zero, and so we can drop them.\n",
"\n",
"The extension to functions of multiple states and inputs is very similar to the above procedure.Suppose the evolution of state x\n",
"is given by:\n",
"\n",
"$\\dot{x} = f(x1, x2, . . . , xn, u1, u2, . . . , um) = Ax+Bu$\n",
"\n",
"Where:\n",
"\n",
"$ A =\n",
"\\quad\n",
"\\begin{bmatrix}\n",
"\\frac{\\partial f(x,u)}{\\partial x1} & ... & \\frac{\\partial f(x,u)}{\\partial xn} \\\\\n",
"\\end{bmatrix}\n",
"\\quad\n",
"$ and $ B = \\quad\n",
"\\begin{bmatrix}\n",
"\\frac{\\partial f(x,u)}{\\partial u1} & ... & \\frac{\\partial f(x,u)}{\\partial um} \\\\\n",
"\\end{bmatrix}\n",
"\\quad $\n",
"\n",
"Then:\n",
"\n",
"$f(x,u)=f(\\bar{x},\\bar{u}) + \\frac{df(x,u)}{dx}|_{x=\\bar{x}}(x-\\bar{x}) + \\frac{df(x,u)}{du}|_{u=\\bar{u}}(u-\\bar{u}) = f(\\bar{x},\\bar{u}) + A_{x=\\bar{x}}(x-\\bar{x}) + B_{u=\\bar{u}}(u-\\bar{u})$\n",
"\n",
"-----------------"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"### Kinematics Model"
]
},
{
"cell_type": "code",
"execution_count": 3,
"metadata": {},
"outputs": [],
"source": [
"# Control problem statement.\n",
"\n",
"N = 5 #number of state variables\n",
"M = 2 #number of control variables\n",
"T = 20 #Prediction Horizon\n",
"dt = 0.25 #discretization step\n",
"\n",
"x = cp.Variable((N, T+1))\n",
"u = cp.Variable((M, T))"
]
},
{
"cell_type": "code",
"execution_count": 4,
"metadata": {},
"outputs": [],
"source": [
"def get_linear_model(x_bar,u_bar):\n",
" \"\"\"\n",
" \"\"\"\n",
" \n",
" x = x_bar[0]\n",
" y = x_bar[1]\n",
" theta = x_bar[2]\n",
" psi = x_bar[3]\n",
" cte = x_bar[4]\n",
" \n",
" v = u_bar[0]\n",
" w = u_bar[1]\n",
" \n",
" A = np.zeros((N,N))\n",
" A[0,2]=-v*np.sin(theta)\n",
" A[1,2]=v*np.cos(theta)\n",
" A[4,3]=-v*np.cos(-psi)\n",
" A_lin=np.eye(N)+dt*A\n",
" \n",
" B = np.zeros((N,M))\n",
" B[0,0]=np.cos(theta)\n",
" B[1,0]=np.sin(theta)\n",
" B[2,1]=1\n",
" B[3,1]=-1\n",
" B[4,0]=-np.sin(-psi)\n",
" B_lin=dt*B\n",
" \n",
" f_xu=np.array([v*np.cos(theta),v*np.sin(theta),w,-w,v*np.sin(-psi)]).reshape(N,1)\n",
" C_lin = dt*(f_xu - np.dot(A,x_bar.reshape(N,1)) - np.dot(B,u_bar.reshape(M,1)))\n",
" \n",
" return A_lin,B_lin,C_lin"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Motion Prediction: using scipy intergration"
]
},
{
"cell_type": "code",
"execution_count": 5,
"metadata": {},
"outputs": [],
"source": [
"# Define process model\n",
"def kinematics_model(x,t,u):\n",
" \"\"\"\n",
" \"\"\"\n",
"\n",
" dxdt = u[0]*np.cos(x[2])\n",
" dydt = u[0]*np.sin(x[2])\n",
" dthetadt = u[1]\n",
" dpsidt = -u[1]\n",
" dctedt = u[0]*np.sin(-x[3])\n",
"\n",
" dqdt = [dxdt,\n",
" dydt,\n",
" dthetadt,\n",
" dpsidt,\n",
" dctedt]\n",
"\n",
" return dqdt\n",
"\n",
"def predict(x0,u):\n",
" \"\"\"\n",
" \"\"\"\n",
" \n",
" x_bar = np.zeros((N,T+1))\n",
" \n",
" x_bar[:,0] = x0\n",
" \n",
" # solve ODE\n",
" for t in range(1,T+1):\n",
"\n",
" tspan = [0,dt]\n",
" x_next = odeint(kinematics_model,\n",
" x0,\n",
" tspan,\n",
" args=(u[:,t-1],))\n",
"\n",
" x0 = x_next[1]\n",
" x_bar[:,t]=x_next[1]\n",
" \n",
" return x_bar"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Validate the model, here the status w.r.t a straight line with constant heading 0"
]
},
{
"cell_type": "code",
"execution_count": 6,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CPU times: user 2.58 ms, sys: 3.15 ms, total: 5.73 ms\n",
"Wall time: 5.54 ms\n"
]
}
],
"source": [
"%%time\n",
"\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:] = 1 #m/s\n",
"u_bar[1,:] = np.radians(-10) #rad/s\n",
"\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = 1\n",
"x0[2] = np.radians(0)\n",
"x0[3] = 0\n",
"x0[4] = 1\n",
"\n",
"x_bar=predict(x0,u_bar)"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Check the model prediction"
]
},
{
"cell_type": "code",
"execution_count": 7,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 432x288 with 4 Axes>"
]
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"#plot trajectory\n",
"plt.subplot(2, 2, 1)\n",
"plt.plot(x_bar[0,:],x_bar[1,:])\n",
"plt.plot(np.linspace(0,10,T+1),np.zeros(T+1),\"b-\")\n",
"plt.axis('equal')\n",
"plt.ylabel('y')\n",
"plt.xlabel('x')\n",
"\n",
"plt.subplot(2, 2, 2)\n",
"plt.plot(np.degrees(x_bar[2,:]))\n",
"plt.ylabel('theta(t) [deg]')\n",
"#plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 3)\n",
"plt.plot(np.degrees(x_bar[3,:]))\n",
"plt.ylabel('psi(t) [deg]')\n",
"#plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 4)\n",
"plt.plot(x_bar[4,:])\n",
"plt.ylabel('cte(t)')\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"the results seems valid:\n",
"* the cte is correct\n",
"* theta error is correct"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Motion Prediction: using the state space model"
]
},
{
"cell_type": "code",
"execution_count": 8,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CPU times: user 3.07 ms, sys: 1.38 ms, total: 4.44 ms\n",
"Wall time: 2.86 ms\n"
]
}
],
"source": [
"%%time\n",
"\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:] = 1 #m/s\n",
"u_bar[1,:] = np.radians(-10) #rad/s\n",
"\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = 1\n",
"x0[2] = np.radians(0)\n",
"x0[3] = 0\n",
"x0[4] = 1\n",
"\n",
"x_bar=np.zeros((N,T+1))\n",
"x_bar[:,0]=x0\n",
"\n",
"for t in range (1,T+1):\n",
" xt=x_bar[:,t-1].reshape(5,1)\n",
" ut=u_bar[:,t-1].reshape(2,1)\n",
" \n",
" A,B,C=get_linear_model(xt,ut)\n",
" \n",
" xt_plus_one = np.dot(A,xt)+np.dot(B,ut)+C\n",
" \n",
" x_bar[:,t]= np.squeeze(xt_plus_one)"
]
},
{
"cell_type": "code",
"execution_count": 9,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 432x288 with 4 Axes>"
]
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"#plot trajectory\n",
"plt.subplot(2, 2, 1)\n",
"plt.plot(x_bar[0,:],x_bar[1,:])\n",
"plt.plot(np.linspace(0,10,T+1),np.zeros(T+1),\"b-\")\n",
"plt.axis('equal')\n",
"plt.ylabel('y')\n",
"plt.xlabel('x')\n",
"\n",
"plt.subplot(2, 2, 2)\n",
"plt.plot(x_bar[2,:])\n",
"plt.ylabel('theta(t)')\n",
"#plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 3)\n",
"plt.plot(x_bar[3,:])\n",
"plt.ylabel('psi(t)')\n",
"#plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 4)\n",
"plt.plot(x_bar[4,:])\n",
"plt.ylabel('cte(t)')\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"The results are the same as expected"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"------------------\n",
"\n",
"the kinematics model predictits psi and cte for constant heading references. So, for non-constant paths appropriate functions have to be developed.\n",
"\n",
"-----------------"
]
},
{
"cell_type": "code",
"execution_count": 10,
"metadata": {},
"outputs": [],
"source": [
"def calc_err(state,path):\n",
" \"\"\"\n",
" Finds psi and cte w.r.t. the closest waypoint.\n",
"\n",
" :param state: array_like, state of the vehicle [x_pos, y_pos, theta]\n",
" :param path: array_like, reference path ((x1, x2, ...), (y1, y2, ...), (th1 ,th2, ...)]\n",
" :returns: (float,float)\n",
" \"\"\"\n",
"\n",
" dx = state[0]-path[0,:]\n",
" dy = state[1]-path[1,:]\n",
" dist = np.sqrt(dx**2 + dy**2)\n",
" nn_idx = np.argmin(dist)\n",
"\n",
" try:\n",
" v = [path[0,nn_idx+1] - path[0,nn_idx],\n",
" path[1,nn_idx+1] - path[1,nn_idx]] \n",
" v /= np.linalg.norm(v)\n",
"\n",
" d = [path[0,nn_idx] - state[0],\n",
" path[1,nn_idx] - state[1]]\n",
"\n",
" if np.dot(d,v) > 0:\n",
" target_idx = nn_idx\n",
" else:\n",
" target_idx = nn_idx+1\n",
"\n",
" except IndexError as e:\n",
" target_idx = nn_idx\n",
"\n",
"# front_axle_vect = [np.cos(state[2] - np.pi / 2),\n",
"# np.sin(state[2] - np.pi / 2)]\n",
" path_ref_vect = [np.cos(path[2,target_idx] + np.pi / 2),\n",
" np.sin(path[2,target_idx] + np.pi / 2)]\n",
" \n",
" #heading error w.r.t path frame\n",
" psi = path[2,target_idx] - state[2]\n",
" #psi = -path[2,target_idx] + state[2]\n",
" \n",
" # the cross-track error is given by the scalar projection of the car->wp vector onto the faxle versor\n",
" #cte = np.dot([dx[target_idx], dy[target_idx]],front_axle_vect)\n",
" cte = np.dot([dx[target_idx], dy[target_idx]],path_ref_vect)\n",
"\n",
" return target_idx,psi,cte\n",
"\n",
"def compute_path_from_wp(start_xp, start_yp, step = 0.1):\n",
" \"\"\"\n",
" Interpolation range is computed to assure one point every fixed distance step [m].\n",
" \n",
" :param start_xp: array_like, list of starting x coordinates\n",
" :param start_yp: array_like, list of starting y coordinates\n",
" :param step: float, interpolation distance [m] between consecutive waypoints\n",
" :returns: array_like, of shape (3,N)\n",
" \"\"\"\n",
"\n",
" final_xp=[]\n",
" final_yp=[]\n",
" delta = step #[m]\n",
"\n",
" for idx in range(len(start_xp)-1):\n",
" section_len = np.sum(np.sqrt(np.power(np.diff(start_xp[idx:idx+2]),2)+np.power(np.diff(start_yp[idx:idx+2]),2)))\n",
"\n",
" interp_range = np.linspace(0,1,int(section_len/delta))\n",
" \n",
" fx=interp1d(np.linspace(0,1,2),start_xp[idx:idx+2],kind=1)\n",
" fy=interp1d(np.linspace(0,1,2),start_yp[idx:idx+2],kind=1)\n",
" \n",
" final_xp=np.append(final_xp,fx(interp_range))\n",
" final_yp=np.append(final_yp,fy(interp_range))\n",
" \n",
" dx = np.append(0, np.diff(final_xp))\n",
" dy = np.append(0, np.diff(final_yp))\n",
" theta = np.arctan2(dy, dx)\n",
"\n",
" return np.vstack((final_xp,final_yp,theta))"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"test it"
]
},
{
"cell_type": "code",
"execution_count": 11,
"metadata": {},
"outputs": [],
"source": [
"track = compute_path_from_wp([0,5],[0,0])\n",
"\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:] = 1 #m/s\n",
"u_bar[1,:] = np.radians(-10) #rad/s\n",
"\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = 1\n",
"x0[2] = np.radians(0)\n",
"_,psi,cte = calc_err(x0,track)\n",
"x0[3]=psi\n",
"x0[4]=cte\n",
"\n",
"x_bar=np.zeros((N,T+1))\n",
"x_bar[:,0]=x0\n",
"\n",
"for t in range (1,T+1):\n",
" xt=x_bar[:,t-1].reshape(5,1)\n",
" ut=u_bar[:,t-1].reshape(2,1)\n",
" \n",
" A,B,C=get_linear_model(xt,ut)\n",
" \n",
" xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n",
" \n",
" _,psi,cte = calc_err(xt_plus_one,track)\n",
" xt_plus_one[3]=psi\n",
" xt_plus_one[4]=cte\n",
" \n",
" x_bar[:,t]= xt_plus_one"
]
},
{
"cell_type": "code",
"execution_count": 12,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 432x288 with 4 Axes>"
]
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"#plot trajectory\n",
"plt.subplot(2, 2, 1)\n",
"plt.plot(x_bar[0,:],x_bar[1,:])\n",
"plt.plot(track[0,:],track[1,:],\"b-\")\n",
"plt.axis('equal')\n",
"plt.ylabel('y')\n",
"plt.xlabel('x')\n",
"\n",
"plt.subplot(2, 2, 2)\n",
"plt.plot(x_bar[2,:])\n",
"plt.ylabel('theta(t)')\n",
"#plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 3)\n",
"plt.plot(x_bar[3,:])\n",
"plt.ylabel('psi(t)')\n",
"#plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 4)\n",
"plt.plot(x_bar[4,:])\n",
"plt.ylabel('cte(t)')\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "code",
"execution_count": 13,
"metadata": {},
"outputs": [],
"source": [
"track = compute_path_from_wp([0,2,4,5,10],[0,0,3,1,1])\n",
"\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:] = 1 #m/s\n",
"u_bar[1,:] = np.radians(10) #rad/s\n",
"\n",
"x0 = np.zeros(N)\n",
"x0[0] = 2\n",
"x0[1] = 2\n",
"x0[2] = np.radians(0)\n",
"_,psi,cte = calc_err(x0,track)\n",
"x0[3]=psi\n",
"x0[4]=cte\n",
"\n",
"x_bar=np.zeros((N,T+1))\n",
"x_bar[:,0]=x0\n",
"\n",
"for t in range (1,T+1):\n",
" xt=x_bar[:,t-1].reshape(5,1)\n",
" ut=u_bar[:,t-1].reshape(2,1)\n",
" \n",
" A,B,C=get_linear_model(xt,ut)\n",
" \n",
" xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n",
" \n",
" _,psi,cte = calc_err(xt_plus_one,track)\n",
" xt_plus_one[3]=psi\n",
" xt_plus_one[4]=cte\n",
" \n",
" x_bar[:,t]= xt_plus_one"
]
},
{
"cell_type": "code",
"execution_count": 14,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 432x288 with 4 Axes>"
]
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"#plot trajectory\n",
"plt.subplot(2, 2, 1)\n",
"plt.plot(x_bar[0,:],x_bar[1,:])\n",
"plt.plot(track[0,:],track[1,:],\"b-\")\n",
"plt.axis('equal')\n",
"plt.ylabel('y')\n",
"plt.xlabel('x')\n",
"\n",
"plt.subplot(2, 2, 2)\n",
"plt.plot(x_bar[2,:])\n",
"plt.ylabel('theta(t)')\n",
"#plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 3)\n",
"plt.plot(x_bar[3,:])\n",
"plt.ylabel('psi(t)')\n",
"#plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 4)\n",
"plt.plot(x_bar[4,:])\n",
"plt.ylabel('cte(t)')\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"### MPC Problem formulation\n",
"\n",
"**Model Predictive Control** refers to the control approach of **numerically** solving a optimization problem at each time step. \n",
"\n",
"The controller generates a control signal over a fixed lenght T (Horizon) at each time step."
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"![mpc](img/mpc_block_diagram.png)\n",
"\n",
"![mpc](img/mpc_t.png)"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"#### Linear MPC Formulation\n",
"\n",
"Linear MPC makes use of the **LTI** (Linear time invariant) discrete state space model, wich represents a motion model used for Prediction.\n",
"\n",
"$x_{t+1} = Ax_t + Bu_t$\n",
"\n",
"The LTI formulation means that **future states** are linearly related to the current state and actuator signal. Hence, the MPC seeks to find a **control policy** U over a finite lenght horizon.\n",
"\n",
"$U={u_{t|t}, u_{t+1|t}, ...,u_{t+T|t}}$\n",
"\n",
"The objective function used minimize (drive the state to 0) is:\n",
"\n",
"$\n",
"\\begin{equation}\n",
"\\begin{aligned}\n",
"\\min_{} \\quad & \\sum^{t+T-1}_{j=t} x^T_{j|t}Qx_{j|t} + u^T_{j|t}Ru_{j|t}\\\\\n",
"\\textrm{s.t.} \\quad & x(0) = x0\\\\\n",
" & x_{j+1|t} = Ax_{j|t}+Bu_{j|t}) \\quad \\textrm{for} \\quad t<j<t+T-1 \\\\\n",
"\\end{aligned}\n",
"\\end{equation}\n",
"$\n",
"\n",
"Other linear constrains may be applied,for instance on the control variable:\n",
"\n",
"$ U_{MIN} < u_{j|t} < U_{MAX} \\quad \\textrm{for} \\quad t<j<t+T-1 $\n",
"\n",
"The objective fuction accounts for quadratic error on deviation from 0 of the state and the control inputs sequences. Q and R are the **weight matrices** and are used to tune the response.\n",
"\n",
"Because the goal is tracking a **reference signal** such as a trajectory, the objective function is rewritten as:\n",
"\n",
"$\n",
"\\begin{equation}\n",
"\\begin{aligned}\n",
"\\min_{} \\quad & \\sum^{t+T-1}_{j=t} \\delta x^T_{j|t}Q\\delta x_{j|t} + u^T_{j|t}Ru_{j|t}\n",
"\\end{aligned}\n",
"\\end{equation}\n",
"$\n",
"\n",
"where the error w.r.t desired state is accounted for:\n",
"\n",
"$ \\delta x = x_{j,t,ref} - x_{j,t} $\n",
"\n",
"#### Non-Linear MPC Formulation\n",
"\n",
"In general cases, the objective function is any non-differentiable non-linear function of states and inputs over a finite horizon T. In this case the constrains include nonlinear dynamics of motion.\n",
"\n",
"$\n",
"\\begin{equation}\n",
"\\begin{aligned}\n",
"\\min_{} \\quad & \\sum^{t+T}_{j=t} C(x_{j|t},{j|t})\\\\\n",
"\\textrm{s.t.} \\quad & x(0) = x0\\\\\n",
" & x_{j+1|t} = f(x_{j|t},u_{j|t}) \\quad \\textrm{for} \\quad t<j<t+T-1 \\\\\n",
"\\end{aligned}\n",
"\\end{equation}\n",
"$\n",
"\n",
"Other nonlinear constrains may be applied:\n",
"\n",
"$ g(x_{j|t},{j|t})<0 \\quad \\textrm{for} \\quad t<j<t+T-1 $"
]
},
{
"cell_type": "code",
"execution_count": 15,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CPU times: user 270 ms, sys: 109 µs, total: 270 ms\n",
"Wall time: 274 ms\n"
]
}
],
"source": [
"%%time\n",
"\n",
"track = compute_path_from_wp([0,10],[0,0])\n",
"\n",
"MAX_SPEED = 2.5\n",
"MIN_SPEED = 0.5\n",
"MAX_STEER_SPEED = 1.57/2\n",
"\n",
"#starting guess\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:]=0.5*(MAX_SPEED+MIN_SPEED)\n",
"u_bar[1,:]=0.01\n",
"\n",
"# Starting Condition\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = 1\n",
"x0[2] = np.radians(-0)\n",
"_,psi,cte = calc_err(x0,track)\n",
"x0[3]=psi\n",
"x0[4]=cte\n",
"\n",
"# Linearized Model Prediction\n",
"x_bar=np.zeros((N,T+1))\n",
"x_bar[:,0]=x0\n",
"\n",
"for t in range (1,T+1):\n",
" xt=x_bar[:,t].reshape(5,1)\n",
" ut=u_bar[:,t-1].reshape(2,1)\n",
" \n",
" A,B,C=get_linear_model(xt,ut)\n",
" \n",
" xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n",
" \n",
" _,psi,cte = calc_err(xt_plus_one,track)\n",
" xt_plus_one[3]=psi\n",
" xt_plus_one[4]=cte\n",
" x_bar[:,t]= xt_plus_one\n",
"\n",
"\n",
"#CVXPY Linear MPC problem statement\n",
"cost = 0\n",
"constr = []\n",
"\n",
"for t in range(T):\n",
" \n",
" # Cost function\n",
" cost += 10*cp.sum_squares( x[3, t]) # psi\n",
" cost += 10*cp.sum_squares( x[4, t]) # cte\n",
" \n",
" # Actuation effort\n",
" cost += cp.quad_form( u[:, t],10*np.eye(M))\n",
" \n",
" # Actuation rate of change\n",
" if t < (T - 1):\n",
" cost += cp.quad_form(u[:, t + 1] - u[:, t], 5*np.eye(M))\n",
" \n",
" #constrains\n",
" A,B,C=get_linear_model(x_bar[:,t],u_bar[:,t])\n",
" constr += [x[:,t+1] == A*x[:,t] + B*u[:,t] + C.flatten()]\n",
" \n",
"# sums problem objectives and concatenates constraints.\n",
"constr += [x[:,0] == x0]\n",
"constr += [u[0, :] <= MAX_SPEED]\n",
"constr += [u[0, :] >= MIN_SPEED]\n",
"constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED]\n",
"\n",
"\n",
"prob = cp.Problem(cp.Minimize(cost), constr)\n",
"solution = prob.solve(solver=cp.ECOS, verbose=False)"
]
},
{
"cell_type": "code",
"execution_count": 16,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CPU times: user 411 ms, sys: 2.64 ms, total: 413 ms\n",
"Wall time: 404 ms\n"
]
}
],
"source": [
"%%time\n",
"\n",
"track = compute_path_from_wp([0,10],[0,0])\n",
"\n",
"MAX_SPEED = 2.5\n",
"MIN_SPEED = 0.5\n",
"MAX_STEER_SPEED = 1.57/2\n",
"\n",
"#starting guess\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:]=0.5*(MAX_SPEED+MIN_SPEED)\n",
"u_bar[1,:]=0.01\n",
"\n",
"# Starting Condition\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = 1\n",
"x0[2] = np.radians(-0)\n",
"_,psi,cte = calc_err(x0,track)\n",
"x0[3]=psi\n",
"x0[4]=cte\n",
"\n",
"# Linearized Model Aprrox. Prediction\n",
"# x_bar=np.zeros((N,T+1))\n",
"# x_bar[:,0]=x0\n",
"\n",
"# for t in range (1,T+1):\n",
"# xt=x_bar[:,t].reshape(5,1)\n",
"# ut=u_bar[:,t-1].reshape(2,1)\n",
" \n",
"# A,B,C=get_linear_model(xt,ut)\n",
" \n",
"# xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n",
" \n",
"# _,psi,cte = calc_err(xt_plus_one,track)\n",
"# xt_plus_one[3]=psi\n",
"# xt_plus_one[4]=cte\n",
"# x_bar[:,t]= xt_plus_one\n",
"\n",
"\n",
"#CVXPY Linear MPC problem statement\n",
"cost = 0\n",
"constr = []\n",
"\n",
"for t in range(T):\n",
" \n",
" # Cost function\n",
" cost += 10*cp.sum_squares( x[3, t]) # psi\n",
" cost += 10*cp.sum_squares( x[4, t]) # cte\n",
" \n",
" # Actuation effort\n",
" cost += cp.quad_form( u[:, t],10*np.eye(M))\n",
" \n",
" # Actuation rate of change\n",
" if t < (T - 1):\n",
" cost += cp.quad_form(u[:, t + 1] - u[:, t], 5*np.eye(M))\n",
" \n",
" #constrains -> approx linear model at xo\n",
" A,B,C=get_linear_model(x0,u_bar[:,t])\n",
" constr += [x[:,t+1] == A*x[:,t] + B*u[:,t] + C.flatten()]\n",
" \n",
"# sums problem objectives and concatenates constraints.\n",
"constr += [x[:,0] == x0]\n",
"constr += [u[0, :] <= MAX_SPEED]\n",
"constr += [u[0, :] >= MIN_SPEED]\n",
"constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED]\n",
"\n",
"\n",
"prob = cp.Problem(cp.Minimize(cost), constr)\n",
"solution = prob.solve(solver=cp.ECOS, verbose=False)"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Print Results:"
]
},
{
"cell_type": "code",
"execution_count": 17,
"metadata": {},
"outputs": [
{
"name": "stderr",
"output_type": "stream",
"text": [
"No handles with labels found to put in legend.\n"
]
},
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 1080x720 with 4 Axes>"
]
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"x_mpc=np.array(x.value[0, :]).flatten()\n",
"y_mpc=np.array(x.value[1, :]).flatten()\n",
"theta_mpc=np.array(x.value[2, :]).flatten()\n",
"psi_mpc=np.array(x.value[3, :]).flatten()\n",
"cte_mpc=np.array(x.value[4, :]).flatten()\n",
"v_mpc=np.array(u.value[0, :]).flatten()\n",
"w_mpc=np.array(u.value[1, :]).flatten()\n",
"\n",
"#simulate robot state trajectory for optimized U\n",
"x_traj=predict(x0, np.vstack((v_mpc,w_mpc)))\n",
"plt.figure(figsize=(15,10))\n",
"#plot trajectory\n",
"plt.subplot(2, 2, 1)\n",
"plt.plot(track[0,:],track[1,:],\"b*\")\n",
"plt.plot(x_traj[0,:],x_traj[1,:])\n",
"plt.axis(\"equal\")\n",
"plt.ylabel('y')\n",
"plt.xlabel('x')\n",
"\n",
"#plot v(t)\n",
"plt.subplot(2, 2, 2)\n",
"plt.plot(v_mpc)\n",
"plt.ylabel('v(t)')\n",
"#plt.xlabel('time')\n",
"\n",
"#plot w(t)\n",
"plt.subplot(2, 2, 3)\n",
"plt.plot(w_mpc)\n",
"plt.ylabel('w(t)')\n",
"#plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 4)\n",
"plt.plot(cte_mpc)\n",
"plt.ylabel('cte(t)')\n",
"plt.legend(loc='best')\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"full track demo"
]
},
{
"cell_type": "code",
"execution_count": 18,
"metadata": {},
"outputs": [],
"source": [
"\n",
"# track = compute_path_from_wp([0,5,7.5,10,12,13,13,10],\n",
"# [0,0,2.5,2.5,0,0,5,10])\n",
"\n",
"# sim_duration =100 \n",
"# opt_time=[]\n",
"\n",
"# x_sim = np.zeros((N,sim_duration))\n",
"# u_sim = np.zeros((M,sim_duration-1))\n",
"\n",
"# MAX_SPEED = 1.25\n",
"# MIN_SPEED = 0.75\n",
"# MAX_STEER_SPEED = 1.57/2\n",
"\n",
"# # Starting Condition\n",
"# x0 = np.zeros(N)\n",
"# x0[0] = 0\n",
"# x0[1] = -0.5\n",
"# x0[2] = np.radians(-0)\n",
"# _,psi,cte = calc_err(x0,track)\n",
"# x0[3]=psi\n",
"# x0[4]=cte\n",
"\n",
"# x_sim[:,0]=x0\n",
" \n",
"# #starting guess\n",
"# u_bar = np.zeros((M,T))\n",
"# u_bar[0,:]=0.5*(MAX_SPEED+MIN_SPEED)\n",
"# u_bar[1,:]=0.01\n",
"\n",
"# for sim_time in range(sim_duration-1):\n",
" \n",
"# iter_start=time.time()\n",
" \n",
"# # Prediction\n",
"# x_bar=np.zeros((N,T+1))\n",
"# x_bar[:,0]=x_sim[:,sim_time]\n",
"\n",
"# for t in range (1,T+1):\n",
"# xt=x_bar[:,t-1].reshape(5,1)\n",
"# ut=u_bar[:,t-1].reshape(2,1)\n",
"\n",
"# A,B,C=get_linear_model(xt,ut)\n",
"\n",
"# xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n",
"\n",
"# _,psi,cte = calc_err(xt_plus_one,track)\n",
"# xt_plus_one[3]=psi\n",
"# xt_plus_one[4]=cte\n",
"\n",
"# x_bar[:,t]= xt_plus_one\n",
"\n",
"\n",
"# #CVXPY Linear MPC problem statement\n",
"# cost = 0\n",
"# constr = []\n",
"\n",
"# for t in range(T):\n",
"\n",
"# # Tracking\n",
"# if t > 0:\n",
"# idx,_,_ = calc_err(x_bar[:,t],track)\n",
"# delta_x = track[:,idx]-x[0:3,t]\n",
"# cost+= cp.quad_form(delta_x,10*np.eye(3))\n",
" \n",
"# # Tracking last time step\n",
"# if t == T:\n",
"# idx,_,_ = calc_err(x_bar[:,t],track)\n",
"# delta_x = track[:,idx]-x[0:3,t]\n",
"# cost+= cp.quad_form(delta_x,100*np.eye(3))\n",
"\n",
"# # Actuation rate of change\n",
"# if t < (T - 1):\n",
"# cost += cp.quad_form(u[:, t + 1] - u[:, t], 25*np.eye(M))\n",
" \n",
"# # Actuation effort\n",
"# cost += cp.quad_form( u[:, t],1*np.eye(M))\n",
" \n",
"# # Constrains\n",
"# A,B,C=get_linear_model(x_bar[:,t],u_bar[:,t])\n",
"# constr += [x[:,t+1] == A*x[:,t] + B*u[:,t] + C.flatten()]\n",
"\n",
"# # sums problem objectives and concatenates constraints.\n",
"# constr += [x[:,0] == x_sim[:,sim_time]] # starting condition\n",
"# constr += [u[0, :] <= MAX_SPEED]\n",
"# constr += [u[0, :] >= MIN_SPEED]\n",
"# constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED]\n",
" \n",
"# # Solve\n",
"# prob = cp.Problem(cp.Minimize(cost), constr)\n",
"# solution = prob.solve(solver=cp.ECOS, verbose=False)\n",
" \n",
"# #retrieved optimized U and assign to u_bar to linearize in next step\n",
"# u_bar=np.vstack((np.array(u.value[0, :]).flatten(),\n",
"# (np.array(u.value[1, :]).flatten())))\n",
" \n",
"# u_sim[:,sim_time] = u_bar[:,0]\n",
" \n",
"# # Measure elpased time to get results from cvxpy\n",
"# opt_time.append(time.time()-iter_start)\n",
" \n",
"# # move simulation to t+1\n",
"# tspan = [0,dt]\n",
"# x_sim[:,sim_time+1] = odeint(kinematics_model,\n",
"# x_sim[:,sim_time],\n",
"# tspan,\n",
"# args=(u_bar[:,0],))[1]\n",
" \n",
"# print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n",
"# np.max(opt_time),\n",
"# np.min(opt_time))) "
]
},
{
"cell_type": "code",
"execution_count": 19,
"metadata": {},
"outputs": [
{
"name": "stderr",
"output_type": "stream",
"text": [
"/home/marcello/.local/lib/python3.6/site-packages/ipykernel_launcher.py:18: RuntimeWarning: invalid value encountered in true_divide\n"
]
},
{
"name": "stdout",
"output_type": "stream",
"text": [
"CVXPY Optimization Time: Avrg: 0.1777s Max: 0.2998s Min: 0.1523s\n"
]
}
],
"source": [
"\n",
"track = compute_path_from_wp([0,3,4,6],\n",
" [0,0,2,1])\n",
"\n",
"sim_duration =50\n",
"opt_time=[]\n",
"\n",
"x_sim = np.zeros((N,sim_duration))\n",
"u_sim = np.zeros((M,sim_duration-1))\n",
"\n",
"MAX_SPEED = 1.25\n",
"MIN_SPEED = 0.75\n",
"MAX_STEER_SPEED = 1.57/2\n",
"\n",
"# Starting Condition\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = -0.5\n",
"x0[2] = np.radians(-0)\n",
"_,psi,cte = calc_err(x0,track)\n",
"x0[3]=psi\n",
"x0[4]=cte\n",
"\n",
"x_sim[:,0]=x0\n",
" \n",
"#starting guess\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:]=0.5*(MAX_SPEED+MIN_SPEED)\n",
"u_bar[1,:]=0.01\n",
"\n",
"for sim_time in range(sim_duration-1):\n",
" \n",
" iter_start=time.time()\n",
" \n",
" # Prediction\n",
" x_bar=np.zeros((N,T+1))\n",
" x_bar[:,0]=x_sim[:,sim_time]\n",
"\n",
" for t in range (1,T+1):\n",
" xt=x_bar[:,t-1].reshape(5,1)\n",
" ut=u_bar[:,t-1].reshape(2,1)\n",
"\n",
" A,B,C=get_linear_model(xt,ut)\n",
"\n",
" xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n",
"\n",
" _,psi,cte = calc_err(xt_plus_one,track)\n",
" xt_plus_one[3]=psi\n",
" xt_plus_one[4]=cte\n",
"\n",
" x_bar[:,t]= xt_plus_one\n",
"\n",
"\n",
" #CVXPY Linear MPC problem statement\n",
" cost = 0\n",
" constr = []\n",
"\n",
" for t in range(T):\n",
"\n",
" # Tracking\n",
" cost += 50*cp.sum_squares( x[3, t]) # psi\n",
" cost += 10*cp.sum_squares( x[4, t]) # cte\n",
"\n",
" # Actuation rate of change\n",
" if t < (T - 1):\n",
" cost += cp.quad_form(u[:, t + 1] - u[:, t], 25*np.eye(M))\n",
" \n",
" # Actuation effort\n",
" cost += cp.quad_form( u[:, t],1*np.eye(M))\n",
" \n",
" # Constrains\n",
" A,B,C=get_linear_model(x_bar[:,t],u_bar[:,t])\n",
" constr += [x[:,t+1] == A*x[:,t] + B*u[:,t] + C.flatten()]\n",
"\n",
" # sums problem objectives and concatenates constraints.\n",
" constr += [x[:,0] == x_sim[:,sim_time]] # starting condition\n",
" constr += [u[0, :] <= MAX_SPEED]\n",
" constr += [u[0, :] >= MIN_SPEED]\n",
" constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED]\n",
" \n",
" # Solve\n",
" prob = cp.Problem(cp.Minimize(cost), constr)\n",
" solution = prob.solve(solver=cp.OSQP, verbose=False)\n",
" \n",
" #retrieved optimized U and assign to u_bar to linearize in next step\n",
" u_bar=np.vstack((np.array(u.value[0, :]).flatten(),\n",
" (np.array(u.value[1, :]).flatten())))\n",
" \n",
" u_sim[:,sim_time] = u_bar[:,0]\n",
" \n",
" # Measure elpased time to get results from cvxpy\n",
" opt_time.append(time.time()-iter_start)\n",
" \n",
" # move simulation to t+1\n",
" tspan = [0,dt]\n",
" x_sim[:,sim_time+1] = odeint(kinematics_model,\n",
" x_sim[:,sim_time],\n",
" tspan,\n",
" args=(u_bar[:,1],))[1]\n",
" \n",
"print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n",
" np.max(opt_time),\n",
" np.min(opt_time))) "
]
},
{
"cell_type": "code",
"execution_count": 20,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 1080x720 with 3 Axes>"
]
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"#plot trajectory\n",
"grid = plt.GridSpec(2, 3)\n",
"\n",
"plt.figure(figsize=(15,10))\n",
"\n",
"plt.subplot(grid[0:2, 0:2])\n",
"plt.plot(track[0,:],track[1,:],\"b+\")\n",
"plt.plot(x_sim[0,:],x_sim[1,:])\n",
"plt.axis(\"equal\")\n",
"plt.ylabel('y')\n",
"plt.xlabel('x')\n",
"\n",
"plt.subplot(grid[0, 2])\n",
"plt.plot(u_sim[0,:])\n",
"plt.ylabel('v(t) [m/s]')\n",
"\n",
"plt.subplot(grid[1, 2])\n",
"plt.plot(np.degrees(u_sim[1,:]))\n",
"plt.ylabel('w(t) [deg/s]')\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": []
}
],
"metadata": {
"kernelspec": {
"display_name": "Python 3",
"language": "python",
"name": "python3"
},
"language_info": {
"codemirror_mode": {
"name": "ipython",
"version": 3
},
"file_extension": ".py",
"mimetype": "text/x-python",
"name": "python",
"nbconvert_exporter": "python",
"pygments_lexer": "ipython3",
"version": "3.6.9"
}
},
"nbformat": 4,
"nbformat_minor": 4
}