mpc_python_learn/.ipynb_checkpoints/MPC_cvxpy-checkpoint.ipynb

1169 lines
212 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 3 states (x,y,theta) reference\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": "iVBORw0KGgoAAAANSUhEUgAAAagAAAEYCAYAAAAJeGK1AAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAADl0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uIDMuMC4zLCBodHRwOi8vbWF0cGxvdGxpYi5vcmcvnQurowAAIABJREFUeJzt3Xd4VFX6wPHvuSn0HkroLQEBFQQUbKj4U7CAWI6KCCouYln7Ku7q2ta6uyq6qCCoIIoeG6JiBxsKCigCUqQKCRB6J5Dc8/vjDhBCQtrM3JuZ9/M882Tm3jv3vhxm8uaeqqy1CCGEEEHj+B2AEEIIURBJUEIIIQJJEpQQQohAkgQlhBAikCRBCSGECCRJUEIIIQJJEpQQQohAkgQlhBAikCRBCSGECKREvwPwkUyhIcJJ+R1AhMj3RIRTib4n8ZygyMzMPPA8JSWFDRs2+BhN8EiZFCx/uTRs2NDHaCIv7/ckL/l8FEzKpWCl+Z5IFZ8QQohAkgQlhBARZK3FbszCzp2JXb/W73DKlbiu4hNCiHCye3ax97eZuAvmQsZKbMZKyPwT9uz2DqhTD+f+Z1GVKvsbaDkRUwlKa50AzAQyjDHn+R2PECK+uE/ew+ZVy70XVatBo+ao7mdA42aQXAH78nDsmy+hrr7F30DLiZhKUMAtwAKgut+BCCHii92yCVYtp/L5l7KnxzlQvSZKHdppzV2Xif3oLeyxXVHHnehTpOVHzLRBaa0bA+cCo/2ORQgRf+zieQBU7HE2qkatw5ITgDr3UmjWGve1Editm6MdYrkTS3dQzwB3AdUKO0BrPQQYAmCMISUl5cC+xMTEQ14LKZPCSLmIAi2aC5Uqk9g8DTYXnHxUYiLO4NtxH74Vd+xzOH+9r8BEJjwxkaC01ucBWcaYWVrr0wo7zhgzChgVemnzjlWQsQuHkzIpWLyNgxLFYxfNg7T2qISEIx6nUhujLr4KO2EU9tvPUD16RSnC8idWqvhOAvporVcAbwJnaK3H+xuSECJe2C0bYV0Gqk2HYh2vTjsH2nXCmjHYdQUPhBYxkqCMMfcYYxobY5oDlwFTjDEDfA5LCBEn7CKv/Um1ObpYxyvHwbnqZkhMwh3zFDY3N5LhlVsxkaCEEMJXi+dBpSrQpEWx36Jq1UENuAGWL8Z+8nYEgyu/YqINKi9jzNfA1z6HIYSII3bRPEhvj3KO3P6Un9P1ZNw5M7Afvolt3xnVIi1CEZZPcgclhBBlcKD9Kb147U/5qf7XQY3auOP+h3XdMEdXvkmCEkKIMihp+1N+qnJV1EWDYPVy7M/fhTO0ck8SlBBClMWiuaH2p+alPoXqego0bo794HVsTk74YivnJEEJIUQZlLb9KS/lODgXXAnr12KnfRnG6Mo3SVBCCFFKdvNGyMosdfvTIY7pAq2P8jpMZGeX/XwxQBKUEEKU0v7591Tb0rU/5aWUwuk3ELZuwk79qMzniwWSoIQQorQWzYXKVaBx87CcTqW3hw6dsZ+8i921IyznLM9ibhyUEPFIa90EGAfUBywwyhgzPN8xChgOnAPsAq4yxsyOdqyxxC6a682/V4b2p/ycfgNwH74N+9lEVL/4nhBH7qCEiA05wB3GmHZAN+BGrXW7fMf0BtJCjyHAC9ENMbbYTRsga02pu5cXRjVthep6CvbLD+J+SQ5JUELEAGPMmv13Q8aY7XgLdzbKd1hfYJwxxhpjpgM1tdapUQ41ZhxofyrmBLElofpeATn7sB+bsJ+7PJEqPiFijNa6OdAJmJFvVyNgVZ7Xq0Pb1uR7f6HrpuUV7+tibVv5B3uqVCPl2C6HLLERlnJJSWHbmeeze8rH1Lr0ahLqx+eSLpKghIghWuuqwLvArcaYbaU5x5HWTcsr3tcLy/1tJqS1Y2O+xQnDVS72zAtg6idsHDsC55rbynw+v5Vm3TSp4hMiRmitk/CS0+vGmPcKOCQDaJLndePQNlFCB9ufwl+9t5+qVQd1+rnY6V9jM1ZG7DpBJglKiBgQ6qE3BlhgjHmqkMMmAQO11kpr3Q3YaoxZU8ix4gjs4rkAqPTwdpDIT/W+CCpWwn3/tYheJ6ikik+I2HAScCUwV2v9a2jb34GmAMaYF4HJeF3Ml+B1M7/ahzhjw6J5ULlq2MY/FUZVrY46+0LsxPHYP35HpeXvmBnbJEEJEQOMMd8DqohjLHBjdCKKbXbR3ND8e5GvhFJn9sV+PRn3nVdwhj2JUkf8b44pUsUnhBAlYDeth/VrI9r+lJeqUAHVpz8sWwSzf4zKNYNCEpQQQpTAwfFPx0TtmurEntCwKe574+JqOY6YqOIrzjQvQggRFgvneu1PjZpF7ZIqIQHnwkG4/3sY+93nqNPPidq1/RQrd1DFmeYlMObNSyQ9vQG9eqUwf34i559fh169Ujj//IOv8z73a9+cOQQmloL2+XXtnj0TycqKla+OKCm7eF7U2p8OcUwXSO+A/XACds+u6F7bJ8pa63cMYae1/gD4nzHmiyMcZjMzMw+8iOagw1NOqcuyZd7Na3r6PhYvTjqwL+9rv/cddZRlwQJV5PvapGezccUO6lXYQK3kraQ13cb2rGyqJO6kcf3dbNlgSXRycLDUqmPZsCGBJTtbsLT6KWWO048yWrIkiQEDdvLYY9442NAAxFhtuT7ke5JXPA7UtVs24f7tKtQl1+CcdUGBx0SyXOzyxbiP3ok671KcvldE5BqRUprvScwlqNA0L98CHYoYSR/1BNWoUSrl9fdYosqheeVVtK66nNZVl5NWdTktq/xJ/YrrSUneRKKTW6LzfbymJ9f/8kSEoo2eChUse/YoKK//sUWTBJWHnTUN98UncP7+H1SL9AKPiXS5uCOfxP72M84jI1E1a0fsOuFWmgQVE21Q+xU1zcuR5hiLxrxiycmwd29RR1kO/h/mfR7dfdUSd9C11i90qz2bE+rMpn31RSQ7BxtnV+9uwLIdzVi4vRVZ2SkHHpv21mRHThV25FRhZ05ldudWIMcmkmMTca2DwsVR3pXC82/wp4wqVrRccIHLE0/kAsmI+GD/+N37Ijdp6VsMqt+V2F+mYz+cgLoytkcNxEyCKsY0L0ecYywafw1On+5w6ql12bHDwfuFV9jdqy3keST3WTrX/I3eDabQvc5s2lVfTIJyyc5NYs7W9oxe3p9F21uxZEcLlu5sxq7cyoXEfmSWBFx76Jay/xuiVUaehARLdjYkJ+8mMXEbEJ8TecYju2QBtGiDSvTvV6eql4o6rTd2ysfYM/ugUpsU/aZyKiYSVDGnefFd9+71yc7O+5f5wb/KmzXLYe3aBHJyFHXretVl69cnkJhoadAgN2L7mldYTv/Wkzm71uc0rLCG7Nxk5u/pwIjl1/Djxs6sTjyKbFvxkPflZieQAFGNM/8+v669Y4dDly6WZs12k5UVvkXqRPDZPbth1TJU74v9DgV1rsZO+xL3vXEk3PgPv8OJmJhIUBQyzYsxZrKPMR2msOa+5GT44Yf10Ytj22bsj1Ox07+B1ctBOXDUsagTNJU6dadrpcp0BR45cFdZqkmxY5Z3ty1lEneWLwbXRbU+yu9IUNVqoHpd5E2BtHi+t1R8DIqJBFWcaV6CYPr0dVx4YR1WrEhkfxVfixY5vPfexqhc325cj/3sXez3X8K+vdAiHXXZX1BdT0ZVrxWVGIQor+ySBaAUtGzrdyhAnimQzBicv/87rMvOB0VMJKjyoqAqvuXLk+jWrT7LlkVuUmm7djX203ex078GFKr76aiz+qFSG0fsmkLEGrvkd2jUDFW5it+hAKEpkC6+Gjv6v9gpH6PO7ON3SGEnCSqKCqvii1RPf7tqOXby29hZ0yApCXXaOaizLkDVrhuZC4oyCfVCrQlsMcbs8DsecZDNzYWli1DdT/c7lEOo40/FzvjGq+rreAIqpb7fIYWVJKgYZLdtxr7zKvbHqVCxEqrXhagz+6Kq1/Q7NJGP1roDcB1wLtCMUN2v1noF8Akw0hgz178IBQAZKyB7NwSg/SkvpRTOFdfj3n8j7vjncW55IKZmO5f5WqJo+vR1VKrkcrDLsqVyZZcZM9aF5fw2Nxd3yke4996A/ek7VO+LcZ4Yg3PhIElOAaS1fhN4A1gDDABS8AZVpeB1+skAXg8dJ3xk/1gAgGodvBnUVJ26qH4DYf4v2Bnf+B1OWMkdVBQV1Aa1a5cKSxuUXboQ9/UXYNVyaNcR5/LrUA0alS1gEWnjjTEfFbB9M/BD6PGY1vq86IYlDrN0AdROQdUJZvW4Or039qdvsG+9hG3fCVWtht8hhYXcQUVRJNqg7PZtuGOfw338Lti+Dee6u3BufVCSUzmQNzlprU8o6Bit9fGFJDERJdZa7B/zA3n3tJ9yEnAG/hV278aaMX6HEzaSoKJo+vR1NG++j7xVfC1a7CtVFZ+1FnfGN7j3XY/9cQrqrH44D49AdTk5puqg40hhExt/GtUoxOE2ZsGWTYFrf8pPNWqK6n0xdvrX2Hmz/A4nLKJSxae1fhoYa4z5tciDY1i4upnbndux41/AzvweWrbBGfhXVKOm4Q9YRJzWev+8Vyo0I0reD0grvKVkhI/skuC2P+WnzrkEO/N73PEv4DzwHKpiJb9DKpNotUElAJ9prdcDr+HNl7c6StcOjHBU8dl5s3HHPgvbt6IuGIDqdREqIfYG6MWRHA7eUudPRi7wSHTDEYdZ8jtUqgzl4I9AlZSEM+gm3CeGYT94HXXptX6HVCZRSVDGmJu11rcBvYErgHu11jPwVsF9L17GfJRlJgmbnY199xXs1MmQ2gTnpvtQzVpFPGYRcS3wPgzfAKfm2W6B9caY3cU5idb6ZeA8IMsY06GA/acBHwDLQ5veM8Y8VJqA7e5d2NdGsO+ya6B6ndKcolyxSxZAyzblZqYG1bod6rRzsF99iO16CqplG79DKrWo9eIzxuQCHwEfaa3b43WvfRV4PtSN9n5jTEa04vFDaav47PLFuGOehnUZqDP7oPpdiUquEPmARcQZY1aGnpZ1/fBXgf/h/dFXmO+MMWXvEZixAjv/FzbdcTWq6ymoPv1jtlOO3bkDMv9EdTnZ71BKRF04EPvrDNxx/8O59ylUYlLRbwqgqHWS0FpX11oP1lpPxVtQcAZwCnAUsANvUGJMK2kVn83NxZ00weuhtzcb5/aHcS69VpJTjNBaP6W1blDEMQ201kXO0G+M+RbYFLbgjkC1bofz2CiqXDwI+9vP3iDRcf/DborehMdRs2whWBuICWJLQlWqjDPgBshYiZ38jt/hlFq0Okm8A5yNl5heBCYaY7Lz7L8d2BqNWPxUkio+uy4Td8xTsHwx6oQeqP7XoSpXjXrMIqIWAT9prRfgVfEtArYD1YB04DSgDfCvMF2vu9Z6DpAJ3GmMmV/QQUda2POgFBIH3Uilcy9h5ztj2f3ZROz0r6ncqx9VLhqIUyM2Jh/ekbGCnQkJpHTpXuwOB9FY/LRYevZm628z2DPZUOOM3iQ1b+13RCUWrSq+6cBNxpi1Be00xrha69iaRKoAxanis9Ziv/3MG8uQmIQa8jecrqf4E7CIKGPMyFDbUV+89tkL8Obi2wz8hvfH3IfGmHD05JsNNDPG7NBanwNMBNIKiavQhT3zSklJYXOOCxdciXPK2dgPJ7Dro7fZ9cUknGvvRB3bNQxh+yt37ixo0pKNO3bCjp3Fek80Fj8tLnvBQPhlBpueeQjnnn/72qEqtOR7iSgbqZlKg89mZmYeeBGND1WLFqns3Xv4GKXkZMvy5WuwG9d7s0HMnenNBnHVLaha/jVCB+mLFiT5yyX0xSvT4DOt9XC83q0/leEczYGPCuokUcCxK4Auxpii/oMP+Z7kVdDnw65Z5bWXrl6Bc/095TpJ2Zx9uDdfjurRG+fSwcV+X9C+N3bm97gjn0RdNAin10W+xVGa74kM1I2iQgfq/pCB+9n7uPffCIt+Q132F2/SRx+Tk4g6C0zUWv+htX5Aa50ezpOH2rJU6PnxeN/9sC9EplKb4Nz2EDRujvviY9jffg73JaJn5VLYtxeVVr7anw7T+SQ4rjv2gzewa8vX6B5JUFHUvXt9VqxI4uAfEYqULfNZf9ud2HdegbbH4Dw4Aqfn+ShH/mviiTHmVqAxcAPQFJihtZ4Vap8tktZ6AvAj0EZrvTrUIWmo1npo6JCLgXmhNqhngcuMMRGpPlFVqnpJqlFz3Bcew86dGYnLRNz+AbpBn0GiKEopnP5DIbkC7tjnsK7rd0jFJlV8IdGu4utccw63pr1Ej7rTydxTn8Z3DEZ17BbR65dU0KoqgiISVXz5aa0bAa8APY0xfg7AKVEV3yFv3LkD96n7IHMlzg1/Rx3dJVIxRkTuiEchcyUJj4ws0fuC+r1xf5iCfeUZ1GVDcHpGf/7h0nxPZDbzKKqcsIs+jaZySeNJdK8zm43ZNXls4U1MWHMJ8zvGfCdGUQStdRWgH3A5Xg++b4BBfsZUFqpKVZzbH8J96p+4zz+Kc8M/UEd39jusYrHWwpLfUceU3za0/FT307E/f4d9byz2mC6oukcc4RAIMVOPpLXupbVepLVeorUeVpL3rlvn0LNnIvPnJ3L++XU4//yUA8979Uo55HVJnvc9vyY39ttK5viP+fHKJ/ipx9k8dewDpFbM4uEFt3Li15MYu3YgU3/YHqliEeWE1vptYB1e9+6P8HrcnWOMGe9vZGWjqlTDuf0haNgU9/lHy88kpusyYMe2cl+9l5dSCufKG8BxcF8bQXmoPYuJKj6tdQKwGPg/YDXwM3C5Meb3I7ztQNXFPfdUZ/z4KrRuvY/Fi70R1+npB5/nf533edv0PWxeuZ1GldbQpeVqErasp3mVVRxXdxHNkpZTMcEb7rViZ2O+3XACEzN7M3PzseS9061QwZZ5PahICGpVhd8i1IvvLuBNY8yfZYsu7EpdxXfISXZuD1X3rcK57UFUepEdDX3lfv8FduxzOA89j0ptXKL3Bv17437zKXb886iBN+GcclbUrhvPVXzHA0uMMcvgwEqlfYEjJShatkwlO1vRqeZc+jdeREJ2Lqc0z8VRLok5OZzdKodKCdlUTthNpcTdVO64m6qJu6iRtI3aPbZQK2krNZK24bTOk+QbwIbsWizcnsY32y5m4fY0ZmzqxKrdhU8Fk51d6C4RJ4wxT/odQyR5d1IP4z52F+7IJ3HuewZVs7bfYRVuye9QtRrE4BRO6pSzvKq+t1/BHtMVFeBB1bGSoBoBq/K8Xg0ctgBc/hHyixbtY9iwBFrPncqQZgVPYbbPTWBXbiV251ZiZ04lduVWYsu+Gszb2oZNe2uyeV9NNmTXJmN3Kqt31ydjd0N25lbB6zW8/4+F/Hep+/dZqlaFqVP3BWPkeT6BGREfMFIupaOqVMMZejfuY3fivvQfnNsfDuxM/PaP36HVUTG5tppyHJwBN+A++FeseRn1lzv8DqlQsZKgiiX/CPmkpA0kJdXg2cVX89Kyy9mbk4hrHXJsAjk2gVybSI4tTRHZfD/zP8/72qVhww0EsUYg6FUVfimkik8Ug2rcHHXFDdhXnsF+MB51YfD6gNjMPyFrDeqM8/0OJWJUg0be4oYfvok96QxUu05+h1SgWOkkkQE0yfO6cWhbkTZscOjXX3HUCXXYV6E6lVKqUK1uRXJURRKSE2jWLIcKFSwJCdCgQS4NGuSW6nmFCpZmzXJwHEhMhI4d99KmzT6qVIlIeQgRWM6JZ3jVTJ+8i51T6okzIsbO+gGUQnXu7ncoEaV6Xwz1UnFffxG7b6/f4RQoVu6gfgbStNYt8BLTZUD/4rxx9OjNAKSkJMvdghBRoi4fgl25BPflp3HufTpQXZ7trGle9V7N2J7JRSUl41wxFPfp+7GfvIPqU6xfmVEVE3dQock0bwI+AxZ4mwqeqVkI4T+VlIwzdBhYcEc+id23z++QALypgDJWojqf6HcoUaHadUIdfyr2k3ewa4O3HF+s3EFhjJkMTPY7DiFE8ai6DXCuuRV3xCNYMxp1xfV+h+RV7wHquPhIUABKD8bOnYX7xos4tz0UqI4hMXEHJYQon1THE1BnX4j9+hPc6V/7HQ525jRo1RZVO356aaoatVD9roQFc7A/fet3OIeQBCWE8JXqdyWkt8e+NgK7ZlXRb4gQuy4TVi9HdT7Jtxj8onqcDS3SsW+N9pa5DwhJUEIIX6mEBJy//A2Sk32dbdvOmubFE0fVe/spJwFnwPWwYzt24mt+h3OAJCghhO9UzdqoSwbD0oXYbz71JQY7axq0SEfVqevL9f2mmrZC9TwP+82n2GWL/A4HkAQlhAgI1f10OOpYb7btzWFfS/GIbNYa+HMZqkv8Ve/lpfr2hxq1cV97HpuT43c4kqCEEMGglMIZcAPk5uJOKNkaTGUVj733CqIqVsa5/C+wejn2yw/8DkcSlBAiOFS9VNT5l8Mv07Gzf4zade2sadA8DZVSP2rXDCp13InQsRt20gRsVsEz2UeLJCghRKCo/+sLjVvgThiJ3bUz4tez69fCyiVxX72Xl9P/OkhMxB3/gq/rRkmCEkIEikpMxBl4E2zdjH0/8j3K9t+pxXv1Xl6qVh1vIt8Fc7A/TPEtjpiZSUKIeKa1fhk4D8gyxhy2GqDWWgHDgXOAXcBVxpjZ0Y2y+FSLNNQZ52GnfIQ9oQcqgivb2lnToFnrQM0HGATq1LOxM77BmjHYo49DVY/+ulFyByVEbHgV6HWE/b2BtNBjCPBCFGIqE3XBAKiV4i1PnhOZufrsxixYvjhu5t4rCeU4OANvhL17sG+O9iUGSVBCxABjzLfApiMc0hcYZ4yxxpjpQE2tdWp0oisdVbESzhVDIfNP7GfvR+QaB3rvxeHsEcWhUpugztHeCrxzZ0b9+pKghIgPBa06Hfj1zNUxXVFdTsZ+9JY303iY2dk/QNOWqHqBztW+Ur0vgtQmXoeJPbujem1pgxJCHEJrPQSvGhBjTKHL2ycmJha6L5xyb7ibjTdfgfPKcGo/PhKVlBye825Yx4alC6l6xXVUCeO/I1rlEk17b76XzX8fSsXP3qXa4Fujdl1JUELEh2KvOm2MGQWMCr20hS3kmZKSErVFPtWgm8gZ8SjrRz2Nc+ngsJzT/fIjAHa17cjuMP47olkuUZOSijqtN7s+fps9R3dFtWxT4lM0bNiwxO+RKj4h4sMkYKDWWmmtuwFbjTFr/A6quFTHbl6vvi8/wM75OSzntDOnQePmqAaBr+kMBNVvINSs403om50dlWtKghIiBmitJwA/Am201qu11oO11kO11kNDh0wGlgFLgJeAG3wKtdTUxVdBkxa4rz5T5rn63O8+h6ULUSf2DE9wcUBVquyNT1uzCvv681EZwCtVfELEAGPM5UXst8CNUQonIlRSMs6Qv+H+63bc0f/FueNhlJNQ4vPYFX9g3xgJ7Tqiep4XgUhjl+pwHOr8y7GT3oAWbVCnnxPR68kdlBCi3FANGqP6XweL52Env13i99vt23BfeByq18S59s5SJbh4p87VcHQXb3HDpQsjeq1yfweltf43cD6wF1gKXG2M2eJvVEKISFHdz/Cm4Jn0Jjb9aFR6+2K9z7q5uKP/A9s249z9BKpa9QhHGpuU4+AMvh33kdtxX3wc576nIzbLRCzcQX0BdDDGHAMsBu7xOR4hRAQppVBXDIW69XFH/xe7Y1ux3mc/mAC//4rqPxTVPC2yQcY4VaUqzvX3wK4duCP/jc3Njch1yn2CMsZ8bozZv7LWdLzus0KIGKYqVsYZchds24L76rNFNtjbX2dgJxvUKWfhnHJWlKKMbapJC9SVN3rVre+Njcg1yn0VXz7XAG8VtvNIAxBjcXBdWUmZFEzKJRhUs1aoiwdh3xqD+997Ud1OQ3XqjqpS9ZDj7LpM3Jef9iaEvXyIT9HGJqfb6bjLFmE/n4jbPB2n68lhPX+5SFBa6y+BgqYa/ocx5oPQMf8AcoDXCzvPkQYgxuTgujKSMilY/nIpzQBEER6qZx/Yuxf7/RfYsc9hx78A7Tuhup6C6ng8KAf3hcfAScC5fljYZqEQByk9GPvnMuzYZ7ENm6IaNQ3fuf1cjCpctNZXAdcBPY0xu4r5NpuZeXC1SPllfDgpk4IVkqCUbwFF1iHfk7yC9Pmw1sLKJd6kpjO/h00bICkZ6tSDdRk4tzyAat8pKrEEqVyixW7eiPvwrVC5Ks7f/4OqXOWwY0rzPSkXd1BHorXuBdwF9ChBchJCxBCllLdke/M07EVXwbKF2J+/x/46A3XRVVFLTvFK1aqDc93d2OlTITF8aaXcJyjgf0AF4AutNcB0Y8zQI79FCBGrlONA63ao1u1A2pyiRrXpgGpz2FqZZVLuE5QxprXfMQghhAi/ct/NXAghRGySBCWEECKQYqIXXynF7T9cRETM9uLzOwARU0r0PYnnOyiV96G1npV/W7w/pExKVC6xSj4f4fl8xP0jVC4lEs8JSgghRIBJghJCCBFIkqAOGlX0IXFHyqRgUi4eKYeCSbkUrMTlEs+dJIQQQgSY3EEJIYQIpHI/k0Q4hObzGw4kAKONMY/7HJLvtNYrgO1ALpBjjOnib0TRp7V+GTgPyDLGdAhtq423pEtzYAWgjTGb/YrRD/J9OUg+IwXTWjcBxgH18YYqjDLGDC9p2cT9HZTWOgEYAfQG2gGXa63b+RtVYJxujOkYj8kp5FWgV75tw4CvjDFpwFeh13FDvi+HeRX5jBQkB7jDGNMO6AbcGPqclKhs4j5BAccDS4wxy4wxe4E3gb4+xyQCwBjzLbAp3+a+wNjQ87HABVENyn/yfclDPiMFM8asMcbMDj3fDiwAGlHCspEE5RXaqjyvV4e2xTsLfK61nhVaiVh46htj1oSer8Wrwogn8n0pWrx/Rg6htW4OdAJmUMKykQQlCnOyMeY4vKqcG7XWp/odUNAYYywyFZA4gnj/jGitqwLvArcaY7bl3VecspEEBRlAkzyvG4e2xTVjTEboZxbwPl7VjoB1WutUgNDPLJ/jiTb5vhQt3j8jAGitk/CS0+vGmPdCm0tUNtKLD34G0rTWLfC+aJcB/f0NyV9a6yqAY4zZHnp+FvCQz2EFxSRgEPB46OcH/oYTdfJ9KVqW6c7wAAAWx0lEQVS8f0bQWitgDLDAGPNUnl0lKhsZqAtorc8BnsHrNvuyMeYRn0Pylda6Jd5dE3h/xLwRj2WitZ4AnAakAOuA+4GJgAGaAivxusnmbySPafJ9OUg+IwXTWp8MfAfMBdzQ5r/jtUMVu2wkQQkhhAgkaYMSQggRSJKghBBCBJIkKCGEEIEkCUoIIUQgSYISQggRSJKghBBCBJIkKCGEEIEkCUoIIUQgyVRH4hBa61Z409mcaYyZrbVuCMwBLjHGfO1rcEKIuCIzSYjDaK3/AtwGdMGb8miuMeZOf6MSQsQbqeIThzHGvAQswZs3KxX4h78RCSHikSQoUZiXgA7Ac8aYbL+DEULEH6niE4cJLTI2B5iKt2Dh0fE2G7MQwn9yByUKMhyYaYy5FvgYeNHneIQQcUgSlDiE1rov0Au4PrTpduA4rfUV/kUlhIhHUsUnhBAikOQOSgghRCBJghJCCBFIkqCEEEIEkiQoIYQQgSQJSgghRCBJghJCCBFIkqCEEEIEkiQoIYQQgSQJSgghRCBJghJCCBFIkqCEEEIEkiQoIYQQgSQJSgghRCBJghJCCBFIkqCEEEIEkiQoIYQQgZTodwA+kpUaRTgpvwMQItbEc4IiMzOzwO0pKSls2LAhytEEn5RLwRo2bOh3CELEJKniE0IIEUhxfQcVK6y1kL0Hdu3wHnv2QPM0VKL89wohyi/5DVYO2W2bcce/AGtWwc4dsGsn5OYcelD7Tjg3349y5CZZCFE+SYIqZ+yaVbjDH4TtW1FHd4EqVb1HZe+hqlTFZvyJ/XACdrJBnXeZ3yELIUSpSIIqR+ziebgjHoGERJy/PYpqnlbwgcedCFmZ2EkTsC3botp1jGqcQggRDlL/U064M77BffqfUL0Wzj3/ptDkBCilUFfeCKlNcEf/F7t5Y/QCFUKIMJEEFXDWWtzJb2NH/xdatsEZ9iSqboMi36cqVMQZOgz2ZuOOehKbk1Pke4QQIkgkQQWYzc3FvjYC+/5rqONPxbn1IVSVqsV+v0ptjBp4EyxZgH1/XAQjFUKI8JM2qICy+/bhvvAYzJ2J6n0x6oIBpeqR5xx/Ku6SBdjPJ2JbtUUdd2IEohVCiPCTO6gAstZixz3nJacrrse5cGCZuourS66BFum4rz6LzSp49gwhhAgaSVABZD98Ezv9a1TfK3BO613m86mkJJzr7gInAfeFJ7B7s8sepBBCRJgkqIBxf5yK/XAC6sSeqHN12M6r6tTDGXw7rF6Onfx22M4rhBCRIgkqQOyiedixz0HbY1BX3oBS4Z0gWx3dGToch53+tTc9khBCBJgkqICwa1fjPv8o1EvFuX4YKjEpItdRnU+CjVnw59KInF8IIcJFElQA2O1bcZ99CBIScP56H6py8buSl5Tq1A0SErAzp0XsGkIIEQ6SoHxm9+31pi/asgnnpnuLNQi3LFSVatD2GOysaVLNJ4QINElQPrKui335GVi6EGfw7aiWbaJyXdX5JFi/Fv5cFpXrCSFEaQRmoK7WuhcwHEgARhtjHs+3/3bgWiAHWA9cY4xZGdqXC8wNHfqnMaZP1AIvJWst1ozBzvwedfFVqM7RG0CrOnXDjn8eO+t7VLNWUbuuEEKURCDuoLTWCcAIoDfQDrhca90u32G/AF2MMccA7wBP5tm32xjTMfQIfHICsB8b7Fcfos7sizqrX1SvrapWh7bHYmdKNZ8QIrgCkaCA44Elxphlxpi9wJtA37wHGGOmGmN2hV5OBxpHOcawcb/+BPvB66hup6MuuTrs3cmLQ3UJVfOtkmo+IUQwBaWKrxGwKs/r1cAJRzh+MPBJntcVtdYz8ar/HjfGTCzoTVrrIcAQAGMMKSkpBZ48MTGx0H1ltWfaV2x940WSu5xEzTse9G1ZdrfnOawf/wIVf/+FascdqagPimS5CCFEfkFJUMWmtR4AdAF65NnczBiTobVuCUzRWs81xhw20McYMwoYFXppN2zYUOA1UlJSKGxfWdjff8F99mFodRQ5V9/Kxi1bwn6NEmnTgV3ffcGesy8q1l1cpMqlvGvYsKHfIQgRk4JSxZcBNMnzunFo2yG01mcC/wD6GGMOTChnjMkI/VwGfA10imSwpWGXL8Z9/jFIbYzz13tRyRX8Dsmr5staA6uW+x2KEEIcJigJ6mcgTWvdQmudDFwGTMp7gNa6EzASLzll5dleS2tdIfQ8BTgJ+D1qkReDXbMK99kHoXpNnFseiOhA3JJQnbqD42BnyaBdIUTwBCJBGWNygJuAz4AF3iYzX2v9kNZ6f6+8fwNVgbe11r9qrfcnsKOAmVrrOcBUvDaowCQou3oF7tP3g5OAc+uDqJq1/Q7pAFWtBrQ5WnrzCSECScXxLyabmVnw2kjhamuxs6bhvjIcKlbGueV+VJMWZT5nuLnffIod/zzOP4cXGZ+0QRUs1AYV/a6YQsS4QNxBxRrr5uK+Nw73xSegcXOce58KZHKC0Nx8Sqr5hBDBIwkqzOzOHbjP/Qv7yTuoU8/GueORQFXr5aeq14Q2HWRuPiFE4EiCCiOb8Sfuo3fAgjmoATfgXHkjKikyy2aEk+p8EqzNgIyVfocihBAHSIIKEzv7R9zH/gZ7duPc+S+cHr38DqnY1HFSzSeECJ5yN1A3SKybC3N+xv1iIvzxO7RIx7n+HlStOn6HViKqei1Ib+/15uvT35epl4QQIj9JUKVg9+zCTvsK+9WH3nx2deqhLrkGdfo5qKRkv8MrFdX5JOwbL0Lmn9Comd/hCCGEJKiSsBuzsFM+wn73OezeBa3a4lw0CDp2QyUk+B1emajjumMnjMTOmoaSBCWECABJUHnYfftgw1qyVy7GXbYENqzDblgHG9bBxizYuR0cB9X5JNT/9UW1SPc75LBRNWpBs9bYhb9Bn/5+hyOEEJKgDrHkd9yn7uPAFK6JSZBSD1Lqo1qmQ90GqC4no2rX9TPKiFFp7bBTJ2P37SsXvQ+FELFNElReTVqgBt9OzdZt2JpYAarXRDnx09FRpbXHfvEBrPgD0vKvFymEENEVP799i0FVrY7T7TSS2x6Nqlk7rpITAK29pGT/mO9zIEIIIQlK5KGqVYfUJtg/AjPXrhAijkmCEodQae1g6UJvjJcQQvioyDYorXUi0Ac4FzgWqAlsAebgLbs+MbRchogFae3g288g408I6AS3Qoj4cMQ7KK31UGAZcB2wFHgEGBr6uRT4C7AsdJyIAUraoYQQAVHUHVRr4HhjzNoC9r0PPKq1TgXuCHtkwh916kGtFG/qpjPO8zsaIUQckwULCxDvC/O5L/0Hu2gezr9fOWRevngvl8LIgoVCREaxx0FprTcZYw5b2EhrnWWMqVfWQLTWvYDhQAIw2hjzeL79FYBxQGdgI3CpMWZFaN89wGAgF7jZGPNZWeOJa2nt4KdvvXkG66X6HY0QIk6VpBffYVMLaK2T8BJKmWitE4ARQG+gHXC51jr/SNHBwGZjTGvgaeCJ0HvbAZcB7YFewPOh84lSUmntAbBLpLu5EMI/xenF9x1ggYpa62/z7W4M/BCGOI4HlhhjloWu+SbQF8j7G7Iv8EDo+TvA/7TWKrT9TWNMNrBca70kdL4fwxBXfEptApWreu1QJ/b0OxohRJwqThXfaLz69a7AmDzbLbAOmBKGOBoBq/K8Xg2cUNgxxpgcrfVWoE5o+/R8720UhpjilnIcaH2UDNgVQviqyARljBkLoLWeboxZGPmQIkdrPQQYAmCMISUlpcDjEhMTC90XL3Z27MqOcc9TK9EhoabX9CjlIoSIpiMmKK11H2PMJIAjJae8x5VSBtAkz+vGoW0FHbM6NHi4Bl5nieK8FwBjzChgVOilLaxHmvRWA9uwOQCbZnyP6nwiIOVSmFAvPiFEmBV1B3WZ1vpR4HXgG2ARsB2oBqQDPYABwK9AWRLUz0Ca1roFXnK5DMi/KNEkYBBe29LFwBRjjNVaTwLe0Fo/BTQE0oCfyhCLAGjWCpKTsX/MP5CghBAimo7Yi88Y0x+4HK9N5zVgPbAn9HMs0ACvu/eAsgQRmirpJuAzYIG3yczXWj+kte4TOmwMUCfUCeJ2YFjovfMBg9eh4lPgRmOMTCRXRioxCVq0wS5Z4HcoQog4VeyBulrrY4E/CM3FZ4zZFcnAokAG6hbBnTgeO/kdnGffQFWsLOVSCBmoK0RklGQc1Id4veieB67TWh8X6uYtYpRKaw/WhaWL/A5FCBGHip2gjDFN8bqaTwSOAd4GNmutP4pQbMJvrdqAcmTiWCGEL0q0HlRoIO0PeB0VpuNNLVTmaY5EMKmKlaFpSxkPJYTwRUnm4nsL6A5kAl/j9ewbaozZHpnQRBCotHbYbz7F7tvndyi+sfv2wdrVKFkfS4ioKnaCAo4DXLyFCucAv0pyin0qrR32y0nw51JIjZ+JY+36tdh5s7HzZsHC30A5OM+M93o3CiGiotgJyhiTFlr76dTQY5jWuhLwrTHm2kgFKHzW+iggtIDhCSf7HEzk2JwcWDwXO3eWl5TWhsZ6p9RHndgT1aEz0lFPiOgqyR0Uxpg1WutFeANiGwOn481ALmKUql4L6jeK6XYoO28W7pujYV0GJCZBmw6oHr29pFS/4SFrYgkhoqckbVCTgJPxZpL4Bq/b+Z3GmD8iFJsICJXWDjv7R6zr+h1KWNn1a3HNGPh1BtRriDN0GHTojKpQwe/QhBCU7A7qPeAWY8zySAUjAiqtHXz/BTmrlkOVGn5HU2Y2Oxv76bvYT9+FhATUhYNQZ/ZBJUn7khBBUpI2qFcjGIcIMJXWHgvsWzAHupzqdzilZq2FX37EfWsMbFqPOv5U1MVXo2rV8Ts0IUQBStQGJeJUSn2oWYe9c2aW2wRl9+3FvjIc+/N30KgZzp2Potp08DssIcQRSIISRVJKoTqeQPYPX+FcsRtVsZLfIZWI3bUDd8SjsHge6oIBqF4XoRIS/A5LCFGEEs0kIeKX6nIy7M3Gzp3pdyglYjdtwH3yHli6EHXtHTjnaklOQpQTkqBE8aQdhVOrDnbm935HUmw240/cx++CjVk4t9yPc0IPv0MSQpSAJChRLMpJoEL302HuLOye4K+0YhfPx33ybnBdnLseRx11rN8hCSFKSBKUKLaKJ50B+/Zi5/zsdyhHZGdNw336n1C9Fs49T8ocekKUU5KgRLEltT0GatTGzpzmdyiFcr/9FHfkk9CsFc6wJ1B1ZLJ9IcorSVCi2JTjoLqcBPNmYXcHr5rPzv4RO/4F6NAZ5/aHUVWq+R2SEKIMfO9mrrWuDbwFNAdWANoYsznfMR2BF4DqeGtQPWKMeSu071WgB7A1dPhVxphfoxF7PFJdTsJ+9SF2zk+obqf5Hc4BdsnvuKP/Cy3Sca67G5Us0xUJUd4F4Q5qGPCVMSYN+Cr0Or9dwEBjTHugF/CM1rpmnv1/M8Z0DD0kOUVSy7ZQM1i9+eya1bjP/QtqpeDcdJ/MpSdEjAhCguoLjA09HwtckP8AY8zi/ZPSGmMygSygbtQiFAccqOabPxu7a6ff4WC3bMId/gAkJODc+gCqWnW/QxJChInvVXxAfWPMmtDztUD9Ix2stT4eSAaW5tn8iNb6n4TuwIwx2YW8dwgwBMAYQ0pKSoHXSExMLHRfPNtfLnt7nsvmLydRddnvVDrNv9VW3N072fzYo9id26n1rxEktWrrWyxCiPCLSoLSWn8JNChg1z/yvjDGWK21PcJ5UoHXgEHGmP1rP9yDl9iSgVHA3cBDBb3fGDMqdAyA3bBhQ4HXSUlJobB98Wx/udja9aF2CtumfsrODl19icXm5OA+9zCsWIJz031srZECPv2fNWzY0JfrChHropKgjDFnFrZPa71Oa50aWgwxFa/6rqDjqgMfA/8wxkzPc+79d1/ZWutXgDvDGLoogHIcVOeTsFM+xu7agapcNarXt9Zixz0Hv/+Cuupm1NGdo3p9IUR0BKENahIwKPR8EPBB/gO01snA+8A4Y8w7+falhn4qvPareRGNVgChuflyc7C/zoj6te0Hr2N/nIrq0x/npEL/9hFClHNBaIN6HDBa68HASkADaK27AEONMdeGtp0K1NFaXxV63/7u5K9rresCCvgVGBrl+ONTi3SoXdcbtHtiz6hd1v1hCvZjgzr5/1DnXRq16wohok9ZW2iTT6yzmZmZBe6QNqiC5S8X9+1XsF9Nwvnva6gqka/ms4vn4z51H6S1w7nlAVRiEP6+OtAGpfyOQ4hYE4QqPlFOedV8udhfpxd9cBnZrEzcFx6FuvVxhg4LTHISQkSOJChRes1bQ516ER+0a3fu8HrsWXD+el9U7taEEP6TBCVKTSnl3UUtmIPdsS0i17A5ObgvPg7r1+HccA+qnnTpFiJeSIISZaK6hqr5fgl/NZ+1FvvGi7DwN9TAm1DpHcJ+DSFEcEmCEmXTtBXUa4j99F3srh1hPbX9YiL2u89R51yCc+IZYT23ECL4JEGJMlFK4Qz6K2zMwh3zNNZ1i35TMdhfpmPfeRU6n4jqe0VYzimEKF8kQYkyU+ntUXow/PYz9qM3y3w+94cpuCOfgOZpOFffhnLkYypEPJK+uiIs1Onnwool2A/fxDZthep4QonPYa3FfvIO9v3X4Khjca6/R5bOECKOyZ+mIiyUUqgB10PTVrgvP41du7pE77duLnbCSOz7r6GO74Fz8z9RlSpHKFohRHkgCUqEjUqugHPDPZCQiPv8Y9g9xVsW3u7bizvySezUyaiz+qEG34ZKTIpwtEKIoJMEJcJK1amHc91dsC4D95XhFDWVlt25A/fpf8Iv01GXDsa55GppcxJCAJKgRASotsegLr4aZv+I/eSdAo+xe7Oxq5bjPnE3LF+M+svfcM7sG+VIhRBBJp0kRESoM/t4nSYmjsfdtgX27MZu2QhbNsHmjbB/zFSlyt7Er22P8TdgIUTgSIISEaGUgoE3YTeuw075CKrXgpq1oW4DVFp773mtOqj0DqiU+n6HK4QIIElQImJUhQo4dz8Bubky+7gQosTkt4aIKKUUSHISQpSCdJIQQggRSJKghBBCBFJcL/nudwAipsiS70KEWTzfQanCHlrrWUfaH68PKZcjlosQIsziOUEJIYQIMElQQgghAkkSVMFG+R1AQEm5FEzKRYgIiOdOEkIIIQJM7qCEEEIEkiQoIYQQgSRz0OShte4FDAcSgNHGmMd9Dsk3WuuXgfOALGNMh9C22sBbQHNgBaCNMZv9itEPWusmwDigPt5YulHGmOFSNkKEn9xBhWitE4ARQG+gHXC51rqdv1H56lWgV75tw4CvjDFpwFeh1/EmB7jDGNMO6AbcGPqcSNkIEWaSoA46HlhijFlmjNkLvAnE7Qp6xphvgU35NvcFxoaejwUuiGpQAWCMWWOMmR16vh1YADRCykaIsJMEdVAjYFWe16tD28RB9Y0xa0LP1+JVc8UtrXVzoBMwAykbIcJOEpQoFWOMJY7nM9RaVwXeBW41xmzLuy/ey0aIcJEEdVAG0CTP68ahbeKgdVrrVIDQzyyf4/GF1joJLzm9box5L7RZykaIMJMEddDPQJrWuoXWOhm4DJjkc0xBMwkYFHo+CPjAx1h8obVWwBhggTHmqTy74r5shAg3mUkiD631OcAzeN3MXzbGPOJzSL7RWk8ATgNSgHXA/cBEwABNgZV4Xanzd6SIaVrrk4HvgLmAG9r8d7x2qLguGyHCTRKUEEKIQJIqPiGEEIEkCUoIIUQgSYISQggRSJKghBBCBJIkKCGEEIEkCUoIIUQgSYISQggRSP8P3GJxChTJ6g4AAAAASUVORK5CYII=\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": 35,
"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 = 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",
" # 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",
" # 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",
" # 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",
" # 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": 36,
"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(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.5.2"
}
},
"nbformat": 4,
"nbformat_minor": 2
}