mpc_python_learn/MPC_cvxpy.ipynb

1176 lines
213 KiB
Plaintext

{
"cells": [
{
"cell_type": "code",
"execution_count": 1,
"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 not 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-\\bar{x}) + B(u-\\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": [
"### Kinematics Model"
]
},
{
"cell_type": "code",
"execution_count": 2,
"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": 3,
"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": 4,
"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": 5,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CPU times: user 4.51 ms, sys: 390 µs, total: 4.9 ms\n",
"Wall time: 4.39 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": 6,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 432x288 with 4 Axes>"
]
},
"metadata": {
"needs_background": "light"
},
"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": 7,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CPU times: user 1.31 ms, sys: 5.59 ms, total: 6.91 ms\n",
"Wall time: 2.05 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": 8,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 432x288 with 4 Axes>"
]
},
"metadata": {
"needs_background": "light"
},
"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": 9,
"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,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": 10,
"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": 11,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 432x288 with 4 Axes>"
]
},
"metadata": {
"needs_background": "light"
},
"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": 12,
"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": 13,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 432x288 with 4 Axes>"
]
},
"metadata": {
"needs_background": "light"
},
"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",
"![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",
"$J(x(t),U) = \\sum^{t+T-1}_{j=t} x^T_{j|t}Qx_{j|t} + u^T_{j|t}Ru_{j|t}$\n",
"\n",
"This 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",
"Becouse the goal is tracking a **reference signal** such as a trajectory, the objective function is rewritten as:\n",
"\n",
"$J(x(t),U) = \\sum^{t+T-1}_{j=t} \\delta x^T_{j|t}Q\\delta x_{j|t} + u^T_{j|t}Ru_{j|t}$\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",
"$J(x(t),U) = \\sum^{t+T}_{j=t} C(x_{j|t},{j|t})$\n",
"\n",
"s.t.\n",
"\n",
"$ x_{j+1|t} = f(x_{j|t},{j|t}) t<j<t+T-1 $\n",
"\n",
"Other nonlinear constrains may be applied:\n",
"\n",
"$ g(x_{j|t},{j|t})<0 t<j<t+T-1 $"
]
},
{
"cell_type": "code",
"execution_count": 14,
"metadata": {},
"outputs": [
{
"name": "stderr",
"output_type": "stream",
"text": [
"/home/marcello/.local/lib/python3.5/site-packages/ipykernel_launcher.py:18: RuntimeWarning: invalid value encountered in true_divide\n"
]
},
{
"name": "stdout",
"output_type": "stream",
"text": [
"CPU times: user 329 ms, sys: 173 ms, total: 502 ms\n",
"Wall time: 281 ms\n"
]
}
],
"source": [
"%%time\n",
"\n",
"track = compute_path_from_wp([0,2,2,10],[0,0,2,2])\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] = 0\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-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",
" # Cost function\n",
" #cost += 5*cp.sum_squares( x[3, t]) # psi\n",
" #cost += 100*cp.sum_squares( x[4, t]) # cte\n",
" \n",
" # Tracking\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 5 states\n",
" #delta_x = np.append(track[:,idx],[0,0])\n",
" #cost+= cp.quad_form(delta_x-x[:,t],500*np.eye(N))\n",
" \n",
" # Actuation effort\n",
" cost += cp.quad_form( u[:, t],1*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": 15,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 432x288 with 3 Axes>"
]
},
"metadata": {
"needs_background": "light"
},
"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[1, :]).flatten()\n",
"psi_mpc=np.array(x.value[1, :]).flatten()\n",
"cte_mpc=np.array(x.value[1, :]).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",
"\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",
"#plot theta(t)\n",
"#plt.subplot(2, 2, 4)\n",
"#plt.plot(cte_mpc)\n",
"#plt.ylabel('cte(t)')\n",
"#plt.xlabel('time')\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": 24,
"metadata": {},
"outputs": [
{
"name": "stderr",
"output_type": "stream",
"text": [
"/home/marcello/.local/lib/python3.5/site-packages/ipykernel_launcher.py:18: RuntimeWarning: invalid value encountered in true_divide\n"
]
}
],
"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",
"\n",
"x_sim = np.zeros((N,sim_duration))\n",
"u_sim = np.zeros((M,sim_duration-1))\n",
"\n",
"MAX_SPEED = 2.5\n",
"MIN_SPEED = 0.5\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",
" # 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",
" # Cost function\n",
" #cost += 5*cp.sum_squares( x[3, t]) # psi\n",
" #cost += 100*cp.sum_squares( x[4, t]) # cte\n",
"\n",
" # Tracking\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 5 states\n",
" #delta_x = np.append(track[:,idx],[0,0])\n",
" #cost+= cp.quad_form(delta_x-x[:,t],500*np.eye(N))\n",
"\n",
" # Actuation effort\n",
" cost += cp.quad_form( u[:, t],1*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] == x_sim[:,sim_time]]\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",
" # 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"
]
},
{
"cell_type": "code",
"execution_count": 33,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 1080x720 with 3 Axes>"
]
},
"metadata": {
"needs_background": "light"
},
"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(np.degrees(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) [rad/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.5.2"
}
},
"nbformat": 4,
"nbformat_minor": 2
}