mpc_python_learn/notebook/MPC_cvxpy.ipynb

1340 lines
254 KiB
Plaintext

{
"cells": [
{
"cell_type": "code",
"execution_count": 33,
"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": 34,
"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": 35,
"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": 36,
"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": 37,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CPU times: user 7.06 ms, sys: 0 ns, total: 7.06 ms\n",
"Wall time: 6.23 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": 38,
"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": 39,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CPU times: user 2.19 ms, sys: 343 µs, total: 2.54 ms\n",
"Wall time: 1.6 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": 40,
"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": 41,
"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",
" \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": 42,
"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": 43,
"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": 44,
"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": 45,
"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": 89,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CPU times: user 383 ms, sys: 12.2 ms, total: 395 ms\n",
"Wall time: 388 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",
"# 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": "markdown",
"metadata": {},
"source": [
"Print Results:"
]
},
{
"cell_type": "code",
"execution_count": 90,
"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": 48,
"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": 97,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CVXPY Optimization Time: Avrg: 0.1656s Max: 0.2457s Min: 0.1539s\n"
]
}
],
"source": [
"\n",
"track = compute_path_from_wp([0,10],\n",
" [0,0])\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": 98,
"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
}