mpc_python_learn/notebooks/MPC_racecar_tracking.ipynb

1053 lines
182 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",
"* $v$ velocity of the robot\n",
"* $\\theta$ heading of the robot\n",
"\n",
"The inputs of the model are:\n",
"\n",
"* $a$ acceleration of the robot\n",
"* $\\delta$ steering of the robot\n",
"\n",
"These are the differential equations f(x,u) of the model:\n",
"\n",
"$\\dot{x} = f(x,u)$\n",
"\n",
"* $\\dot{x} = v\\cos{\\theta}$ \n",
"* $\\dot{y} = v\\sin{\\theta}$\n",
"* $\\dot{v} = a$\n",
"* $\\dot{\\theta} = \\frac{v\\tan{\\delta}}{L}$\n",
"\n",
"Discretize with forward Euler Integration for time step dt:\n",
"\n",
"${x_{t+1}} = x_{t} + f(x,u)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",
"* ${v_{t+1}} = v_{t} + a_tdt$\n",
"* ${\\theta_{t+1}} = \\theta_{t} + \\frac{v\\tan{\\delta}}{L} dt$\n",
"\n",
"----------------------\n",
"\n",
"The Model is **non-linear** and **time variant**, but the Numerical Optimizer requires a Linear sets of equations. To approximate the equivalent **LTI** State space model, the **Taylor's series expansion** is used around $\\bar{x}$ and $\\bar{u}$ (at each time step):\n",
"\n",
"$ f(x,u) \\approx f(\\bar{x},\\bar{u}) + \\frac{\\partial f(x,u)}{\\partial x}|_{x=\\bar{x},u=\\bar{u}}(x-\\bar{x}) + \\frac{\\partial f(x,u)}{\\partial u}|_{x=\\bar{x},u=\\bar{u}}(u-\\bar{u})$\n",
"\n",
"This can be rewritten usibg the State Space model form Ax+Bu :\n",
"\n",
"$ f(\\bar{x},\\bar{u}) + A|_{x=\\bar{x},u=\\bar{u}}(x-\\bar{x}) + B|_{x=\\bar{x},u=\\bar{u}}(u-\\bar{u})$\n",
"\n",
"Where:\n",
"\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 v} & \\frac{\\partial f(x,u)}{\\partial \\theta} \\\\\n",
"\\end{bmatrix}\n",
"\\quad\n",
"=\n",
"\\displaystyle \\left[\\begin{matrix}0 & 0 & \\cos{\\left(\\theta \\right)} & - v \\sin{\\left(\\theta \\right)}\\\\0 & 0 & \\sin{\\left(\\theta \\right)} & v \\cos{\\left(\\theta \\right)}\\\\0 & 0 & 0 & 0\\\\0 & 0 & \\frac{\\tan{\\left(\\delta \\right)}}{L} & 0\\end{matrix}\\right]\n",
"$\n",
"\n",
"and\n",
"\n",
"$\n",
"B = \n",
"\\quad\n",
"\\begin{bmatrix}\n",
"\\frac{\\partial f(x,u)}{\\partial a} & \\frac{\\partial f(x,u)}{\\partial \\delta} \\\\\n",
"\\end{bmatrix}\n",
"\\quad\n",
"= \n",
"\\displaystyle \\left[\\begin{matrix}0 & 0\\\\0 & 0\\\\1 & 0\\\\0 & \\frac{v \\left(\\tan^{2}{\\left(\\delta \\right)} + 1\\right)}{L}\\end{matrix}\\right]\n",
"$\n",
"\n",
"are the *Jacobians*.\n",
"\n",
"\n",
"\n",
"So the discretized model is given by:\n",
"\n",
"$ x_{t+1} = x_t + (f(\\bar{x},\\bar{u}) + A|_{x=\\bar{x}}(x_t-\\bar{x}) + B|_{u=\\bar{u}}(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 LTI-equivalent kinematics model is:\n",
"\n",
"$ x_{t+1} = A'x_t + B' u_t + C' $\n",
"\n",
"with:\n",
"\n",
"$ A' = I+dtA|_{x=\\bar{x},u=\\bar{u}} $\n",
"\n",
"$ B' = dtB|_{x=\\bar{x},u=\\bar{u}} $\n",
"\n",
"$ C' = dt(f(\\bar{x},\\bar{u}) - A|_{x=\\bar{x},u=\\bar{u}}\\bar{x} - B|_{x=\\bar{x},u=\\bar{u}}\\bar{u}) $"
]
},
{
"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": 2,
"metadata": {},
"outputs": [],
"source": [
"\"\"\"\n",
"Control problem statement.\n",
"\"\"\"\n",
"\n",
"N = 4 #number of state variables\n",
"M = 2 #number of control variables\n",
"T = 20 #Prediction Horizon\n",
"DT = 0.2 #discretization step"
]
},
{
"cell_type": "code",
"execution_count": 3,
"metadata": {},
"outputs": [],
"source": [
"def get_linear_model(x_bar,u_bar):\n",
" \"\"\"\n",
" Computes the LTI approximated state space model x' = Ax + Bu + C\n",
" \"\"\"\n",
" \n",
" L=0.3 #vehicle wheelbase\n",
" \n",
" x = x_bar[0]\n",
" y = x_bar[1]\n",
" v = x_bar[2]\n",
" theta = x_bar[3]\n",
" \n",
" a = u_bar[0]\n",
" delta = u_bar[1]\n",
" \n",
" A = np.zeros((N,N))\n",
" A[0,2]=np.cos(theta)\n",
" A[0,3]=-v*np.sin(theta)\n",
" A[1,2]=np.sin(theta)\n",
" A[1,3]=v*np.cos(theta)\n",
" A[3,2]=v*np.tan(delta)/L\n",
" A_lin=np.eye(N)+DT*A\n",
" \n",
" B = np.zeros((N,M))\n",
" B[2,0]=1\n",
" B[3,1]=v/(L*np.cos(delta)**2)\n",
" B_lin=DT*B\n",
" \n",
" f_xu=np.array([v*np.cos(theta), v*np.sin(theta), a,v*np.tan(delta)/L]).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 np.round(A_lin,4), np.round(B_lin,4), np.round(C_lin,4)"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Motion Prediction: using scipy intergration"
]
},
{
"cell_type": "code",
"execution_count": 4,
"metadata": {},
"outputs": [],
"source": [
"# Define process model\n",
"# This uses the continuous model \n",
"def kinematics_model(x,t,u):\n",
" \"\"\"\n",
" Returns the set of ODE of the vehicle model.\n",
" \"\"\"\n",
" \n",
" L=0.3 #vehicle wheelbase\n",
" dxdt = x[2]*np.cos(x[3])\n",
" dydt = x[2]*np.sin(x[3])\n",
" dvdt = u[0]\n",
" dthetadt = x[2]*np.tan(u[1])/L\n",
"\n",
" dqdt = [dxdt,\n",
" dydt,\n",
" dvdt,\n",
" dthetadt]\n",
"\n",
" return dqdt\n",
"\n",
"def predict(x0,u):\n",
" \"\"\"\n",
" \"\"\"\n",
" \n",
" x_ = np.zeros((N,T+1))\n",
" \n",
" x_[:,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_[:,t]=x_next[1]\n",
" \n",
" return x_"
]
},
{
"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 3.46 ms, sys: 0 ns, total: 3.46 ms\n",
"Wall time: 2.88 ms\n"
]
}
],
"source": [
"%%time\n",
"\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:] = 0.2 #m/ss\n",
"u_bar[1,:] = np.radians(-np.pi/4) #rad\n",
"\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = 1\n",
"x0[2] = 0\n",
"x0[3] = np.radians(0)\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 2 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",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"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 2.9 ms, sys: 0 ns, total: 2.9 ms\n",
"Wall time: 1.93 ms\n"
]
}
],
"source": [
"%%time\n",
"\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:] = 0.2 #m/s\n",
"u_bar[1,:] = np.radians(-np.pi/4) #rad\n",
"\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = 1\n",
"x0[2] = 0\n",
"x0[3] = np.radians(0)\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(N,1)\n",
" ut=u_bar[:,t-1].reshape(M,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 2 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)')\n",
"#plt.xlabel('time')\n",
"\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"The results are the same as expected, so the linearized model is equivalent as expected."
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## PRELIMINARIES"
]
},
{
"cell_type": "code",
"execution_count": 9,
"metadata": {},
"outputs": [],
"source": [
"def compute_path_from_wp(start_xp, start_yp, step = 0.1):\n",
" \"\"\"\n",
" Computes a reference path given a set of waypoints\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,np.floor(section_len/delta).astype(int))\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))\n",
"\n",
"\n",
"def get_nn_idx(state,path):\n",
" \"\"\"\n",
" Computes the index of the waypoint closest to vehicle\n",
" \"\"\"\n",
"\n",
" dx = state[0]-path[0,:]\n",
" dy = state[1]-path[1,:]\n",
" dist = np.hypot(dx,dy)\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",
" return target_idx\n",
"\n",
"def get_ref_trajectory(state, path, target_v):\n",
" \"\"\"\n",
" \"\"\"\n",
" xref = np.zeros((N, T + 1))\n",
" dref = np.zeros((1, T + 1))\n",
" \n",
" #sp = np.ones((1,T +1))*target_v #speed profile\n",
" \n",
" ncourse = path.shape[1]\n",
"\n",
" ind = get_nn_idx(state, path)\n",
"\n",
" xref[0, 0] = path[0,ind] #X\n",
" xref[1, 0] = path[1,ind] #Y\n",
" xref[2, 0] = target_v #sp[ind] #V\n",
" xref[3, 0] = path[2,ind] #Theta\n",
" dref[0, 0] = 0.0 # steer operational point should be 0\n",
" \n",
" dl = 0.05 # Waypoints spacing [m]\n",
" travel = 0.0\n",
"\n",
" for i in range(T + 1):\n",
" travel += abs(target_v) * DT #current V or target V?\n",
" dind = int(round(travel / dl))\n",
"\n",
" if (ind + dind) < ncourse:\n",
" xref[0, i] = path[0,ind + dind]\n",
" xref[1, i] = path[1,ind + dind]\n",
" xref[2, i] = target_v #sp[ind + dind]\n",
" xref[3, i] = path[2,ind + dind]\n",
" dref[0, i] = 0.0\n",
" else:\n",
" xref[0, i] = path[0,ncourse - 1]\n",
" xref[1, i] = path[1,ncourse - 1]\n",
" xref[2, i] = 0.0 #stop? #sp[ncourse - 1]\n",
" xref[3, i] = path[2,ncourse - 1]\n",
" dref[0, i] = 0.0\n",
"\n",
" return xref, dref"
]
},
{
"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} $"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"# Problem Formulation: Study case\n",
"\n",
"In this case, the objective function to minimize is given by:\n",
"\n",
"https://borrelli.me.berkeley.edu/pdfpub/IV_KinematicMPC_jason.pdf\n",
"\n",
"$\n",
"\\begin{equation}\n",
"\\begin{aligned}\n",
"\\min_{} \\quad & \\sum^{t+T-1}_{j=t} (x_{j} - x_{j,ref})^TQ(x_{j} - x_{j,ref}) + \\sum^{t+T-1}_{j=t+1} u^T_{j}Ru_{j} + (u_{j} - u_{j-1})^TP(u_{j} - u_{j-1}) \\\\\n",
"\\textrm{s.t.} \\quad & x(0) = x0\\\\\n",
" & x_{j+1} = Ax_{j}+Bu_{j} \\quad \\textrm{for} \\quad t<j<t+T-1 \\\\\n",
" & u_{MIN} < u_{j} < u_{MAX} \\quad \\textrm{for} \\quad t<j<t+T-1 \\\\\n",
" & \\dot{u}_{MIN} < \\frac{(u_{j} - u_{j-1})}{ts} < \\dot{u}_{MAX} \\quad \\textrm{for} \\quad t+1<j<t+T-1 \\\\\n",
"\\end{aligned}\n",
"\\end{equation}\n",
"$\n",
"\n",
"\n",
"Where R,P,Q are the cost matrices used to tune the response.\n"
]
},
{
"cell_type": "code",
"execution_count": 10,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"-----------------------------------------------------------------\n",
" OSQP v0.6.0 - Operator Splitting QP Solver\n",
" (c) Bartolomeo Stellato, Goran Banjac\n",
" University of Oxford - Stanford University 2019\n",
"-----------------------------------------------------------------\n",
"problem: variables n = 322, constraints m = 404\n",
" nnz(P) + nnz(A) = 1051\n",
"settings: linear system solver = qdldl,\n",
" eps_abs = 1.0e-05, eps_rel = 1.0e-05,\n",
" eps_prim_inf = 1.0e-04, eps_dual_inf = 1.0e-04,\n",
" rho = 1.00e-01 (adaptive),\n",
" sigma = 1.00e-06, alpha = 1.60, max_iter = 10000\n",
" check_termination: on (interval 25),\n",
" scaling: on, scaled_termination: off\n",
" warm start: on, polish: on, time_limit: off\n",
"\n",
"iter objective pri res dua res rho time\n",
" 1 0.0000e+00 4.07e+00 4.07e+02 1.00e-01 3.74e-04s\n",
" 200 1.6634e+02 8.84e-03 6.79e-04 1.56e+00 1.99e-03s\n",
" 400 1.6749e+02 5.41e-04 3.89e-05 1.56e+00 3.67e-03s\n",
" 600 1.6755e+02 4.11e-05 2.52e-06 1.56e+00 5.25e-03s\n",
"\n",
"status: solved\n",
"solution polish: unsuccessful\n",
"number of iterations: 600\n",
"optimal objective: 167.5540\n",
"run time: 5.50e-03s\n",
"optimal rho estimate: 6.60e+00\n",
"\n",
"CPU times: user 117 ms, sys: 3.54 ms, total: 121 ms\n",
"Wall time: 117 ms\n"
]
}
],
"source": [
"%%time\n",
"\n",
"MAX_SPEED = 1.5 #m/s\n",
"MAX_STEER = np.radians(30) #rad\n",
"MAX_ACC = 1.0\n",
"REF_VEL=1.0\n",
"\n",
"track = compute_path_from_wp([0,3,6],\n",
" [0,0,0],0.05)\n",
"\n",
"# Starting Condition\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0 #x\n",
"x0[1] = -0.25 #y\n",
"x0[2] = 0.0 #v\n",
"x0[3] = np.radians(-0) #yaw\n",
" \n",
"#starting guess\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:] = MAX_ACC/2 #a\n",
"u_bar[1,:] = 0.1 #delta\n",
"\n",
"# dynamics starting state w.r.t world frame\n",
"x_bar = np.zeros((N,T+1))\n",
"x_bar[:,0] = x0\n",
"\n",
"#prediction for linearization of costrains\n",
"for t in range (1,T+1):\n",
" xt = x_bar[:,t-1].reshape(N,1)\n",
" ut = u_bar[:,t-1].reshape(M,1)\n",
" A, B, C = get_linear_model(xt,ut)\n",
" xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n",
" x_bar[:,t] = xt_plus_one\n",
"\n",
"#CVXPY Linear MPC problem statement\n",
"x = cp.Variable((N, T+1))\n",
"u = cp.Variable((M, T))\n",
"cost = 0\n",
"constr = []\n",
"\n",
"# Cost Matrices\n",
"Q = np.diag([10,10,10,10]) #state error cost\n",
"Qf = np.diag([10,10,10,10]) #state final error cost\n",
"R = np.diag([10,10]) #input cost\n",
"R_ = np.diag([10,10]) #input rate of change cost\n",
"\n",
"#Get Reference_traj\n",
"x_ref, d_ref = get_ref_trajectory(x_bar[:,0], track, REF_VEL)\n",
"\n",
"#Prediction Horizon\n",
"for t in range(T):\n",
" \n",
" # Tracking Error\n",
" cost += cp.quad_form(x[:,t] - x_ref[:,t], Q)\n",
"\n",
" # Actuation effort\n",
" cost += cp.quad_form(u[:,t], R)\n",
" \n",
" # Actuation rate of change\n",
" if t < (T - 1):\n",
" cost += cp.quad_form(u[:, t + 1] - u[:, t], R_)\n",
"\n",
" # Kinrmatics Constrains (Linearized model)\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_bar[:,0]] #starting condition\n",
"constr += [x[2,:] <= MAX_SPEED] #max speed\n",
"constr += [x[2,:] >= 0.0] #min_speed (not really needed)\n",
"constr += [cp.abs(u[0,:]) <= MAX_ACC] #max acc\n",
"constr += [cp.abs(u[1,:]) <= MAX_STEER] #max steer\n",
"# for t in range(T):\n",
"# if t < (T - 1):\n",
"# constr += [cp.abs(u[0,t] - u[0,t-1])/DT <= MAX_ACC] #max acc\n",
"# constr += [cp.abs(u[1,t] - u[1,t-1])/DT <= MAX_STEER] #max steer\n",
"\n",
"prob = cp.Problem(cp.Minimize(cost), constr)\n",
"solution = prob.solve(solver=cp.OSQP, verbose=True)"
]
},
{
"cell_type": "code",
"execution_count": 11,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "iVBORw0KGgoAAAANSUhEUgAAAa8AAAEYCAYAAADrpHnMAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjMuMSwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy/d3fzzAAAACXBIWXMAAAsTAAALEwEAmpwYAABUTklEQVR4nO3deVxU9f7H8dd3AEFEtgHBfTezrDTMckPFLSujzay8XrPyFi6l1b3ZLbPMLfVHWWqLZmV10xaxVUstNM3U0CythFLTXFBAFBQVzvf3x8gksg0wM2cGPs/Hwwdw5izvGRk+c77ne75fpbXWCCGEEF7EYnYAIYQQoqKkeAkhhPA6UryEEEJ4HSleQgghvI4ULyGEEF5HipcQQgiv42t2AFc6cOCA/fuIiAiOHj1qYpqqkfzmKSl7gwYNTErjec5/nxXypP9vyeK5OaDsLGW9z+TMSwghhNeR4iWEEMLrSPESQghRJp17AuPLJIylC9GGYXYcoJpf8xJCCFF5em8a+uvP0JvWwdkztoWNmqO69DY3GFK8hBBCnEefPYPe/C36m89h9y7wD0Bd0xsVOwDjrZfQSW+jY7qiavmbmlOKlxBCCAD0r9sxXpkBOScguhFqyEjUNb1QgXUAsNw2AmPW4+hVH6MG3mZqVileQggh0CdzMRYmQp1gLCP/DW0vQylVZB110aVwRWf0Fx+gu/VFBYeaExbpsCGEEALQ778O2VlY7hmPuvjyYoWrkOWWf8KZ0+hP3nNzwgtymHp0IYQQptM//4D+9ivUgJtQzVuXua6KboTqMQC9dgX60H43JSxOipcQQtRg+mQuxltzoX5j1A13OrSNumEI1PLH+PBNF6crnRQvIYSowfQHi+BYJpa7H0T5+Tm0jQoORQ24BbZ9j971s4sTlkyKlxBC1FB6x1b0ui9R/W9CNW9ToW1VnxshLALj/UWm3LgsxUsIIWogfeokxlsv2poLB91R4e2Vvz8qfijsSUVvXueChGWT4iWEEDWQ/mARZGViGT4W5VerUvtQV/eExs3RyxajC0fgcBMpXkIIUcOc/nEzeu1KVL94VIuLKr0fZbFguW0EZKSj13zmxITlk5uUhahGtm3bxqJFizAMg7i4OOLj44s8rrVm0aJFbN26FX9/fxISEmjRogUAo0aNIiAgAIvFgo+PD9OnTzfhGQhX03knOT53qm0EjRsd611YFnXx5XBpR/SKD9F9b0RZ3HNO5BXFa968eaSkpBASEsLs2bPNjiOERzIMg4ULF/LEE09gtVqZMGECMTExNGrUyL7O1q1bOXToEHPmzCE1NZUFCxYwdepU++NPPfUUwcHBZsT3KHr/btsQSQ2boepWr9dDJ72DPpqO5T8zKt1ceCF1ZVf0zymQfgCiG5W/gRN4RfHq2bMnAwYMYO7cuWZHEcJjpaWlER0dTVRUFABdunRh8+bNRYrXli1b6NGjB0op2rRpQ25uLllZWYSFhZkV22Now4CftmB8tRx+++nvB0LDoVEzVMNmtq+NmkGDxiiLj1lRK03/+Tt6zWfU7n8TZ1q2ddp+VfOL0IDenYqS4vW3du3akZ6ebnYMITxaZmYmVqvV/rPVaiU1NbXYOhEREUXWyczMtBevKVOmANC3b1/69OlT4nFWrVrFqlWrAJg+fXqR/RXy9fUtcbkZysuiT5/m1DdfcPKT9yj4608s1noE/nM0vs1akr/3d/L3/E7+3jTyV38C+WfRgG/z1oQ8/Ay+DZs6NYsracMga+YECAkl9J+jMAJqO2/fYWEcCQgk4NA+giv4/Cr7mnhF8XJUWW8qT3ozVYbkN4+3ZNdaF1t24fh0Za0zefJkwsPDyc7O5tlnn6VBgwa0a9eu2Pp9+vQpUtiOHj1abJ2IiIgSl5uhtCz6xHH0mk9tU3/kHIemrVD3PgxXduWU77k/jY1aQlfbt5b8fDh8AP37L+Qve4uMh+9G3fkv23QhpYwD6GgWdzCSV6B37UDdMx4joLbTc+imLTn1y3bOVHC/Zb0mDRo0KHW7alW8ynpTedKbqTIkv3lKyl7Wm8osVquVjIwM+88ZGRnFmgOtVmuR53L+OuHh4QCEhITQqVMn0tLSSixe1YE+uA8j8SnIOgqXX4Wlbzy0uaTMIqR8faFhE1TDJuj2MRgLZqMXvQC//Ah33Y8KCHTfE6ggffwY+qM34aL2qM6xLjmGat4GvWo5+uxZh0fqqArpKi9ENdGyZUsOHjxIeno6+fn5bNiwgZiYmCLrxMTEsHbtWrTW7Nq1i8DAQMLCwsjLy+PUqVMA5OXlsX37dpo0aWLG03A5/fuvGDMeg4J8LP+djc/oJ1AXXerw2ROACrNieXgyatCd6O/XYkweh96b5sLUVaM/eANOn8Zy1/0Vep4VoZq3hvx82L/bJfu/ULU68xKiJvPx8WHEiBFMmTIFwzDo1asXjRs35ssvvwSgX79+dOjQgZSUFMaOHUutWrVISEgAIDs7m1mzZgFQUFBAt27duOKKK8x6Ki6jf/oB4+VpEBKOZdwzqMjoSu9LWXxQNwxBX9QeY8FsjGn/Rt3yT1SfQS4rEJWhd/2M/m4N6tpbUfUbu+5AzWzDS+nduyo81FRleEXxev7559m5cycnTpzg/vvvZ/DgwfTu3dvsWEJ4nI4dO9KxY8ciy/r162f/XinFvffeW2y7qKgoZs6c6fJ8ZjK++xr95hxo2BTLg0+hgp3Tw1K1uQTLxOcx3nwRvXQh7EmDEQ+hfMzvjajzz2K8PR+s9VDX3e7ag4VZISQcdu9y7XHO8Yri9dBDD5kdQQjhxYwvl6HfXwRtL8OS8DiqtnOvT6mgYCwJj6M/fx+d9DZoA+4Zb3oB0199DAf3YRn9JMrf36XHUkpB8zbo3anlr+wEXlG8hBCiMrTWnHhzLjrpHbiyC5Z7HnZZZwKlFOq6wRg+PujCea5MLGA6Ix396XtwRWfU5Z3cckzVvDV620Z0bg6qTpBLjyXFSwhRLWmt0W/P4+TalaieA1F33OeWG4stA27BUMrWSQJMK2DGe6/Z8gy5z23HVM3boAH2pMIlHVx6LCleQohqR2uNXrIAvXYlgbcMI6//LW7tRGHpf7OtgL2/CLSGex92awEzNqyGbd+jbv4nylrPbcelaStQytZpQ4qXEEJUjF7+Dnr1J6g+gwi661+cPu/+N3ex9LsJA4V+/3V7AXMH/dtP6LfmQtvLUH1vdMsxC6nAOhDdCL3H9de9pHgJIaoV44sP0Z8tRXXvhxp8j6nd1i394m1nYEsXotHox1w7Ur8+tB9j3jSIjMZy/2O2G6vdTDVrjd6Rgtbapa+9FC8hXOz48eOsXbuWlJQU9u7dy8mTJwkMDKRp06ZcccUV9OzZU0ZydxLj68/QH72JuioWNfQBj7jfytL3RgxAL13IsWn/QQ9/0Om9HcE23JUx5xnw8cEydqLLO0yUqnkb+G4NZB4BFzZZSvESwoXeffdd1q1bR4cOHejduzcNGzakdu3anDp1ir/++oudO3fyn//8h27dunHXXXeZHderGetXo999xda77u4HPWrUd0vfGzECanPm7fkw4z9YxkxEWSOdtn999izGvKmQlYHlkSlVuvm6qlSLc502du+S4iWEtwoLC2POnDn4ldA9u3nz5nTr1o0zZ86wZs0aE9JVH3rLt+g3X4R2HbCM/LcpzWXlsXTvR90WrTk243GMqQ9jGf2EU0ai0Fqj35gDaTtRIx9FOXGqk0pp2BR8/WzTo8R0c9lhZGxDIVzo2muvtReuY8eOlbjOyZMnGTBggBtTVS9660aMBbOhVVvbDchuGBS2svwv74RlwnNQyx9j5uPoH9ZXeZ/6k/+hNyWj4odi6dTdCSmrRvn6QZMW6N2/ufQ4UryEcJMHH3ywxOXjxo1zc5Lqw1j9Ccb8adCkpa0pzsWjSDiDqt8Yy4SZ0KQFxsszMD5/v8SpahxhbPwa/cl7tmlZBt7m5KSVp5q3gb2/owsKXHYMKV5CuElJf6BOnjyJxSJvw4rSRgHGe6+h33sNruiM5eEpLukE4SoqOBTLw8+iOnVHL1uMfmMO+nSew9vrv/7EWDwX/caLtmlOho3yiM4pds3bwJnTcPBPlx3C8xqGhahmHnjgAQDOnDlj/75QTk4OXbt2NSOW19Kn8zBemwU/bkL1uRF123CP6pzhKOVXC+57BKIaoj99D71lHVzSEdWxC+qyTrZ7ps6jDQN+2oKx+hPbHGJ+tVBdeqNuGW5rqvMgqnlrNKD/2IVq1Nwlx5DiJYSLjRkzBq0106ZNY8yYMUUeCw0N9ciJLT2VPpaJ8dKz8OcfqDv/haXXdWZHqhKlFOrGO9GXXIHetBa9daPtn48vXHw5quM1qLaXoX/8Hr3mMzhyCEKtqJv+gereH1XXQ2+xiKwPderahonq0d8lh5DiJYSLFc5GvHDhQvy94JqMp9J/7bXdx5R7Asuo/7ptsFl3UK3aoVq1Qw8ZCbt3oVO+Q6dsQL/1EvbG5pZtUTcNQ3W42iN7U57PNsJ8a7QLp0fx7FdACC/3+eef07dvX/z8/EotXGfPnuWrr75i4MCBbk7nHXRBAXrjN+glr0GtACyPTkM1bWl2LJdQFoutSLVsi751OOzbjf51O6rNJahmrc2OVyGqWRv0Z0vRp/NQ/gFO37/XXCnetm0bDz74IGPGjCEpKclp+539w2y3LzPjmI7k8JTnWJ0cO3aMsWPH8uqrr/Ltt9/yxx9/cODAAf744w++/fZbXn31VcaOHcvx48fNjupxtGFgfJ+MMWk0+o0XIKohlsdnVtvCdSGlFKpJCyz94r2ucIHtuhfagL1pLtm/VxQvwzBYuHAhjz/+OImJiaxfv579+/c7Zd//l/J/bl9mxjEdyeEpz7E6ufPOO5kxYwbR0dGsWbOGqVOn8vDDDzNt2jS+/vprGjRowHPPPceQIUPMjuoxtGGgf9iA8fRY9ILZ4OOL5YHHsEyYiQp33qgUwsXO3YDtqskpvaLZMC0tjejoaKKiogDo0qULmzdvplGjRg5tP3FiMKmpvpw9ay3+YH+49Vare5dVYjs/v3P5XZnDhfv28/OF3g7uy8NceaUPEyZUfvvg4GAGDRrEoEGDnBeqFNu2bWPRokUYhkFcXBzx8fFFHtdas2jRIrZu3Yq/vz8JCQm0aNHCoW1dTefnw44UjOXvwL7dEN0Qdd8jqJhutuY04VVU3RCIiLINE+UCXlG8MjMzsVr//gNntVpJTS1ezVetWsWqVasAmD59OhEREQDUru2DUso+0sGe5k/zZ/Nn7Nt91794e6yrl5lxTEdymPkcm+yeSLPdTxV73GwWi7L/LnmywhaKJ554AqvVyoQJE4iJiSnyIW/r1q0cOnSIOXPmkJqayoIFC5g6dapD2zqLLiiA9INw4E/0gT///nr4ABTkQ2Q0asQ41FU9TJuFWDiHat4G/fuvLtm3VxSvkm7uLOmGvD59+tCnTx/7z0ePHgVgwgSIiIiw/wz/OvcPGr7WkL/u+6vIfly9rDLbFeZ3ZQ5X7jsiIgL/af4O7OsQnqbo745NZbq3nzx5kvfff5+dO3dy4sSJIr/X8+fPr3JOR1ootmzZQo8ePVBK0aZNG3Jzc8nKyuLIkSNVat04n/7lRw7PnWKbw6okBflw/sgLEVHQsCnq8k6opq3g8s4e35tOOKhZa9i8Dp2dhQoJc+quveI3xGq1knHeZHIZGRmEhTn3hRDC1RYsWEBmZia33norL774ImPGjOHjjz+mc+fOTtm/Iy0UmZmZRc4irVYrmZmZDrduQOktHIXyW7Ti9MBbMQyj5KC+vvg2aIJvk+b4NmqGCqhdoedZUb6+vh5z5uwpWdyV40yHq8h6/3WCMw/j37LkTieVzeIVxatly5YcPHiQ9PR0wsPD2bBhA2PHjnXKvsd3HO/2ZWYc05EcnvIcq6vt27eTmJhI3bp1sVgsdOrUiZYtWzJjxgyuv/76Ku/fkRaK0tZxtHUDSm/hsPOvQ8SwhOLLz3O68JucXNs/FyrpzNksnpLFXTl0sBUsFrJ/3IKlecmj3ZeVpawWDq8oXj4+PowYMYIpU6ZgGAa9evWicePGTtn3w1cWn5r7wmW6oIDxlySgc0+AYdiaPAyD8U2Hoo8cAh8f8PEFHx/Gt3sAfeY0+PrZLzJfuD9HjumOZa7MVZV9VVdaawIDbePvBQQEkJubS2hoKIcOOaep1JEWCqvVWuQPReE6+fn50rohnE75+0PDpi65WdkpxevNN98kNjaWZs2aOWN3JerYsSMdO3as1LbG+lUc+2UbBafP2O470PpcEcr/u/397Fk4ewbyz309e95XXUrzR1mUgtqBEBh07l8dCAyyDecSHgnhEbZuv2EREGb1uLHJhPM1bdqUnTt30r59e9q2bcvChQsJCAigfv36Ttm/Iy0UMTExrFixgq5du5KamkpgYCBhYWEEBwe7rHVD1GyqaSv0j5ucvl+nFK+CggKmTJlCcHAw3bt3p3v37kXaz013IpuCQ3+du0iswGKxFRdfX9sZUy1/2zhcfn62wTL9atke86sFvrXAz8/279zZFcpi+2qx2PZnFPxdBAu/njkNJ3PhZA46NwdO5sDBfejfjkHuCYC/h31RCsKsEN0IFd3o3NeGUL8RhIR71mjRotL+9a9/2ZvnRowYwbvvvktubi6jR492yv5La6H48ssvAejXrx8dOnQgJSWFsWPHUqtWLRISEsrcVogqi2oAJ7LRJ3OLDTZcFUpXdiKZCxiGwdatW1m3bh0pKSm0bt2aHj160LlzZwICnD80iCMOHDhg/95T2prBNio2WUch8wg60/aVI4fRB/fBob/g9Km/Vw6sA42aU7t1W/Ks0ajGzaFBE1Qt7xojz5Ne/4pyVm/D1NRUWrcuftE6LS2NVq1aVTqf2c5/nxXypP9vyWJuDp3yHcb8aVj+O7vEkUJMv+ZlsVi48sorufLKK9m3bx9z5sxh3rx5LFiwgK5duzJ48GDCw8OddTivpvwDoPAM64LHtNZwLBMO7bcVs7/+RO/fTd7qz9B5p2xnaxYLRDVENW4BTVqgmrSAxs1RQR46wrQA4Nlnn+XNN98stnzKlCksWrTIhERCuEGUrQDpwwecOsyV04rXyZMn2bhxI+vWrWPv3r107tyZe+65h4iICD799FOmTp3KrFmznHW4aksVNiGGWVEXX25fbg0P5+ivP8O+Pej9u9H7dqNTd8Cm5L+bH8MjoGEzVKOm5742sxU5uWfGVIVdxrXW9n+FDh8+jI/ciCuqs8ho29f0g07drVP+qs2ePZsff/yRiy++mL59+9KpUyf7aBYAw4YNY/jw4c44VI2lLBZUvQZQrwHqyi725frEcdj3B3rfH/DnbvRfe9A7t0JBga2o+fhCdEOIaoCKamArZvUa2D4N1Q2R62lucMcdd9i/v3AMQ4vFwk033eTuSEK4jarlb/tgnV68ebkqnFK8WrduzT333ENoaGiJj1ssFl577TVnHEpcQNUNhnZXoNpdYV+m88/Cob/Qf+2F/XtszY8H9qF/3AwF+X+fqdWqBaHnejue6/VISDjUCULVqQt1gmwdWQKDwN/fNnOrFLsKe+mll9BaM2nSJJ5++mm01rYRw5UiODiYWrVqmR1RCNeKaog+7IHFy5EBR2USPvdRvn7Q6FyzYedY+3JdUAAZ6XD4APrwX7ZOI1kZ6Kyj6F0/Q3amfdieUnvx1KoFfrZChp8fWM71uvTx+ft7pYr9Oz34bmh2kcufuyeKjLSNhD5v3jzA1oyYnZ0t91GJGkPVq4/est6p+5SLITWI8vGBevWhXn1U+yuLPa6NAsg5YevWn5sDuSfQhd+fOQ1nzsDZ039/f+62AG0UQIHx9y0DGkDb7qcr/KdkVPDc3FwWLFjAxo0b8fX1ZfHixWzZsoW0tDSZEkVUb/Ua2P6e5J6wteo4gRQvYacsPhAcavtXuMxJ+/aPiOCEB3QRNtNrr71GnTp1mDdvHuPH24bFatOmDW+99ZYUL1GtqagGts+0hw9AC+e0wMjHYSHc5KeffuLuu+8u0lwYHBxMdna2iamEcIN6f3eXdxYpXkK4SWBgICdOnCiy7OjRo3LtS1R/kVG2SwdO7HEoxUsIN4mLi2P27Nn8/PPPaK3ZtWsXc+fOpW/fvmZHE8KllK8fWCNtzYZOIte8hHCTG2+8ET8/PxYuXEhBQQHz58+nT58+DBw40OxoQrhevQZoJ96oLMVLCDdRSnHddddx3XXXmR1FCLdTUfXRG3+z3+dYVVK8hHCjAwcOsGfPHvLy8oos7927t0mJhHCTeg3g1Ek4kV2kR3NleXzx+u6773j//ff566+/mDp1Ki1btjQ7khCV8tFHH/Hhhx/StGnTYjftS/ES1Z29u3z6gZpRvBo3bswjjzzCq6++anYUIark888/Z+rUqTRt2tTsKEK4n727/EFUq3ZV3p3HF69GjRqZHUEIp6hVqxYNGzY0O4YQ5rDWsw0j56Tu8h5fvCpi1apVrFq1CoDp06cTERFhf8zX17fIz95G8punKtkLp0MBuP3223n99de57bbbCAkJKbKexSJ3rYjqTfn6gjXKad3lPaJ4TZ48mWPHjhVbPmTIEDp16uTwfvr06UOfPn3sP58/O6enzGBaWZLfPFWZSfn86VAKrV69utiyJUuWVC7cOTk5OSQmJnLkyBEiIyMZN24cQUFBxdbbtm0bixYtwjAM4uLiiI+PB2Dp0qWsXr2a4OBge+6OHTtWKZMQxUQ1QFenM68nn3zS7AhCuMRLL70E2Cai3LhxI9dcc02Rx7XWfP/991U+TlJSEu3btyc+Pp6kpCSSkpIYOnRokXUMw2DhwoU88cQTWK1WJkyYQExMjL1p/rrrrnNohgghKkvVq4/e9bNTustLW4UQLhQZGUlkZCT16tXjww8/tP98/vKPPvqoysfZvHkzsbG26W9iY2PZvHlzsXXS0tKIjo4mKioKX19funTpUuJ6QrhMVAM4nWebfqmKPOLMqyybNm3i9ddf5/jx40yfPp1mzZrx3//+1+xYQjjs559/BqCgoMD+faHDhw9Tu3btKh/j/PnBwsLCOH78eLF1MjMzsVqt9p+tViupqan2n1euXMnatWtp0aIFw4YNK7HZUYiqUPUKR5c/CKHW8lYvk8cXr6uuuoqrrrrK7BhCVNr8+fMBOHv2rP17sI24ERoayogRIxzaT1nXhh2hdfEpRgubbvr168ett94K2K6/vfXWWyQkJJS4n7I6RhXypA46ksVzchS0vYSjQJ2Txwk8d/zKZvH44iWEt5s7dy5gu/41evToSu+nrGvDISEhZGVlERYWRlZWlr3jxfmsVisZGRn2nzMyMuxna6GhofblcXFxzJgxo9RjldUxqpAnddCRLJ6TQysf8PUl5/ddnOxwtNwsZXWMkmteQrhJVQpXeWJiYkhOTgYgOTm5xF66LVu25ODBg6Snp5Ofn8+GDRuIiYkBICsry77epk2baNy4scuyippLWXwgItopPQ7lzEuIaiA+Pp7ExETWrFlDRESEfabmzMxMXnnlFSZMmICPjw8jRoxgypQpGIZBr1697EXq7bffZs+ePSiliIyMZOTIkWY+HVGdRTUAJ4wuL8VLiGqgbt26TJw4sdjy8PBwJkyYYP+5Y8eOJd6/NWbMGJfmE6KQqlcfvXMb2jBQVbg5X5oNhRBCuE9UQzh7Bo5llL9uGaR4CSGEcBtVr77tmyoOEyXFSwghhPtEFY4uL8VLCCGEtwi1gl+tKo8uL8VLCCGE2yiLBerVR1exx6EULyGEEO5Vr75c8xJCCOFdVL0GcPQQ2iio9D6keAkhhHCvqAaQnw8ZRyq9CyleQggh3ErVOzdmYRWue0nxEkII4V5Rtnu9qjLGoRQvIYQQ7hUSDv4BVeq04fFjGy5evJgffvgBX19foqKiSEhIoE6dOmbHEkIIUUlKqSp3l/f4M6/LLruM2bNnM2vWLOrXr8+yZcvMjiSEEKKKVL0GVTrz8vjidfnll+Pj4wNAmzZtyMzMNDmREEKIKos6110+P79Sm3t8s+H51qxZQ5cuXUp9vKzpyT1l+u3Kkvzm8ebsQniseg3AMChIPwi1ald4c48oXpMnT+bYsWPFlg8ZMsQ+I+xHH32Ej48P3bt3L3U/ZU1P7inTb1eW5DdPSdnLmp5cCFE+FVUfDRQc3AdN21R4e48oXk8++WSZj3/zzTf88MMPTJw40XahTwghhHc7d69XwYHKFS+Pv+a1bds2li9fzn/+8x/8/f3NjiOEEMIZ6oZA7UDyD+6v1OYeceZVloULF5Kfn8/kyZMBaN26NSNHjjQ5lRCeJScnh8TERI4cOUJkZCTjxo0jKCio2Hrz5s0jJSWFkJAQZs+eXeHthXAWW3f5BrZmw0rw+OL14osvmh1BCI+XlJRE+/btiY+PJykpiaSkJIYOHVpsvZ49ezJgwADmzp1bqe2FcCbV6mIs+WeozPC8Ht9sKIQo3+bNm4mNjQUgNjaWzZs3l7heu3btSjyjcnR7IZzJMuQ+Qh56qlLbevyZlxCifNnZ2YSFhQEQFhbG8ePHXbZ9WbekFPKk2wski+fmgMpnkeIlhJco65YSdyrrlpRCnnRrhGTx3BxQdpaybkmR4iWElyjrlpKQkBCysrIICwsjKyuL4ODgCu27qtsL4W7VunhdWLW9/cZSyW8eT88eExNDcnIy8fHxJCcn22/ud8f2pb02nvSaSZbiPCUHVC5Ljemw8dhjj5kdoUokv3m8IXt8fDzbt29n7NixbN++nfj4eAAyMzOZNm2afb3nn3+eJ554ggMHDnD//fezZs2aMrevLE96zSRLcZ6SAyqfpVqfeQlRU9StW5eJEycWWx4eHs6ECRPsPz/00EMV2l4IT1VjzryEEEJUHzWmeJ3fO8obSX7zeHN2s3jSayZZivOUHFD5LEprrZ2cRQghhHCpGnPmJYQQovqoER02tm3bxqJFizAMg7i4uCr3pHKXo0ePMnfuXI4dO4ZSij59+jBw4ECzY1WYYRg89thjhIeHe1QvJ0fk5uby8ssvs2/fPpRSPPDAA7RpU/HpG2oST3q/jRo1ioCAACwWCz4+PkyfPt1txy5pEGQzBkAuKcfSpUtZvXq1/X6+O+64g44dO7o0R2l/zyr9muhqrqCgQI8ePVofOnRInz17Vj/yyCN63759ZsdySGZmpv7999+11lqfPHlSjx071muyn++TTz7Rzz//vJ42bZrZUSrsxRdf1KtWrdJaa3327Fmdk5NjciLP5mnvt4SEBJ2dnW3KsXfs2KF///13PX78ePuyxYsX62XLlmmttV62bJlevHixKTmWLFmily9f7vJjn6+0v2eVfU2qfbNhWloa0dHRREVF4evrS5cuXbxm0NGwsDBatGgBQO3atWnYsCGZmZkmp6qYjIwMUlJSiIuLMztKhZ08eZJffvmF3r17A7Yx2OrUqWNyKs/mze83ZytpEGQzBkAubTBmdyvt71llX5Nq32yYmZmJ1Wq1/2y1WklNTTUxUeWkp6eze/duWrVqZXaUCnnjjTcYOnQop06dMjtKhaWnpxMcHMy8efPYu3cvLVq0YPjw4QQEBJgdzWN54vttypQpAPTt29f0XnZVHUDZmVauXMnatWtp0aIFw4YNc2uBO//vWWVfk2p/5qVL6EyplDIhSeXl5eUxe/Zshg8fTmBgoNlxHPbDDz8QEhJi/7TlbQoKCti9ezf9+vXjueeew9/fn6SkJLNjeTRPe79NnjyZGTNm8Pjjj7Ny5Up27txpWhZP0q9fP1588UWee+45wsLCeOutt9x2bGf9Pav2xctqtZKRkWH/OSMjw17lvUF+fj6zZ8+me/fudO7c2ew4FfLbb7+xZcsWRo0axfPPP8/PP//MnDlzzI7lMKvVitVqpXXr1gBcffXV7N692+RUns3T3m/h4eGAbeDhTp06kZaWZlqWwhxZWVkApg6AHBoaisViwWKxEBcXx++//+6W45b096yyr0m1L14tW7bk4MGDpKenk5+fz4YNG4iJiTE7lkO01rz88ss0bNiQ66+/3uw4FXbnnXfy8ssvM3fuXB566CEuvfRSxo4da3Ysh4WGhmK1Wjlw4AAAP/30E40aNTI5lWfzpPdbXl6evbk6Ly+P7du306RJE1OyFCocABmo1ADKzlJYLAA2bdpE48aNXX7M0v6eVfY1qRE3KaekpPDmm29iGAa9evXi5ptvNjuSQ3799VcmTpxIkyZN7E0v7ujS6go7duzgk08+8bqu8nv27OHll18mPz+fevXqkZCQ4BEXvz2Zp7zfDh8+zKxZswBbE3C3bt3cmuX5559n586dnDhxgpCQEAYPHkynTp1ITEzk6NGjREREMH78eJf/PpWUY8eOHezZswelFJGRkYwcOdLlZ8il/T1r3bp1pV6TGlG8hBBCVC/VvtlQCCFE9SPFSwghhNeR4iWEEMLrSPESQgjhdaR4CSGE8DpSvIQQQngdKV5CCCG8jhQvIYQQXkeKVw126NAh7r77bv744w/ANiL4Pffcw44dO0xOJoQQZZPiVYNFR0dz11138eKLL3L69Gnmz59PbGwsl1xyidnRhBCiTDI8lGDGjBmkp6ejlGLatGn4+fmZHUkIIcokZ16CuLg49u3bx4ABA6RwCSG8ghSvGi4vL48333yT3r178/7775OTk2N2JCGEKJcUrxpu0aJFNG/enPvvv5+OHTvy6quvmh1JCCHKJcWrBtu8eTPbtm1j5MiRAPzzn/9k9+7drFu3zuRkQghRNumwIYQQwuvImZcQQgivI8VLCCGE15HiJYQQwutI8RJCCOF1pHgJIYTwOlK8hBBCeB0pXkIIIbyOFC8hhBBeR4qXEEIIryPFSwghhNeR4iWEEMLrSPESQgjhdaR4CSGE8DpSvIQQQngdX3ccZN68eaSkpBASEsLs2bOLPa61ZtGiRWzduhV/f38SEhJo0aIFANu2bWPRokUYhkFcXBzx8fEOH/fAgQMlLo+IiODo0aOVei6uIHnK52mZGjRoYHYEj1HS+8zT/r/A8zJ5Wh7wvExlvc/ccubVs2dPHn/88VIf37p1K4cOHWLOnDmMHDmSBQsWAGAYBgsXLuTxxx8nMTGR9evXs3//fndEFkII4cHccubVrl070tPTS318y5Yt9OjRA6UUbdq0ITc3l6ysLI4cOUJ0dDRRUVEAdOnShc2bN9OoUaNK5dCH/kJ/lcTxgACMvLxK7KCMeTvDIlDX3oLy9atUNiGEMIvWGr1hNblGPrppG2jUDGXx7KtKbile5cnMzCQiIsL+s9VqJTMzk8zMTKxWa5Hlqamppe5n1apVrFq1CoDp06cX2SfAmaMHyf5pC6cBVem0JW2pMbIyqBMeTp0b76zwHn19fYtlNZOn5QHPzGSW8prSy2qGHzVqFAEBAVgsFnx8fJg+fToAOTk5JCYmcuTIESIjIxk3bhxBQUHufmrCBFpr9LLF6C8+IKdwYXAoqt0V0K4Dqt0VqJAwExOWzCOKly7hjEYpVery0vTp04c+ffrYfy7WdhtRH/XcIte0677wNDlLXufkZZ1RdUMqtKmntTN7Wh7wvExmXfMqbEp/4oknsFqtTJgwgZiYmCKtEec3w6emprJgwQKmTp1qf/ypp54iODi4yH6TkpJo37498fHxJCUlkZSUxNChQ932vIR59Mf/Q3/xAapHf6zDEshYvwZ2bEPv2Aobv0GD7Uysax8sfQaZHdfOI84LrVZrkT9MGRkZhIWFYbVaycjIKLbcE1kG3wOn89BJ75gdRVRjaWlp9qZ0X19fe1P6+Uprhi/L5s2biY2NBSA2NrbYPkX1ZHy6BP3pe6iufVB3PYCPNRJLlzgs9z2MZdabWJ5MRN38T/CrhV6yAP3zD2ZHtvOIM6+YmBhWrFhB165dSU1NJTAwkLCwMIKDgzl48CDp6emEh4ezYcMGxo4da3bcEqn6jVC9rkOv+Qzd61pUo+ZmRxLVkCNN6aU1wxd+8JsyZQoAffv2tbdUZGdn2x8PCwvj+PHjpWYor3kePLOZ19MymZ0n96PF5Cx/h4Ce1xI8+nGUj0/xTPXqQcfO6CF3kzFuGPp/r2J94W1UQG3TchdyS/F6/vnn2blzJydOnOD+++9n8ODB5OfnA9CvXz86dOhASkoKY8eOpVatWiQkJADg4+PDiBEjmDJlCoZh0KtXLxo3buyOyJWibhiC3vgNxtLXsYx7pswmTiEqw5Gm9LLWmTx5MuHh4WRnZ/Pss8/SoEED2rVrV6EM5TbP43nNvOB5mczMY3yZhH7/ddRVsZy5YyQZ587My8qk77wfY+bjHHnjJSy33u2WnGU1z7uleD300ENlPq6U4t577y3xsY4dO9KxY0cXpHI+VacuatAd6P+9Cj9+D1dcbXYkUc040pReWjM8QHh4OAAhISF06tSJtLQ02rVrR0hICFlZWYSFhZGVlVXsmpioPozVn9gKV0w31IiHUBYfh7ZTbS5Fde+H/mo5+qoeqCYtXZy0bB5xzas6UbHXQv3GGEtfR589a3YcUc20bNnS3pSen5/Phg0biImJKbJOTEwMa9euRWvNrl277M3weXl5nDp1CoC8vDy2b99OkyZN7NskJycDkJycTKdOndz7xIRbGF9/jn7vNeh4Deqe8SgfxwpXIXXLcAgKxnhrLtoocE1IB3nENa/qRPn4YBl8D8YLk9BrPkX1v8nsSKIaKa0p/csvvwTKbobPzs5m1qxZABQUFNCtWzeuuOIKAOLj40lMTGTNmjVEREQwfvx4U56fcB39+6/od1+Gy6/Cct8jKN+K//lXdYJQQ+5DvzrT9vetz40uSOpgFl1SA3k1YebwUAVznoG0nViefRkVHFrmutIWXz5PyyTDQ/1NhoeqHHfnKUicCH/+gWXaa6V2uHAkk9Ya48XJsOtnLE/PRVkjXREX8IDhoWoiy+ARcOY0erl0nRdCmEun7oSd21ADbqlyT0GlFJa77getMd6ZX2IHIXeQ4uUiKvpc1/l1X6H37TY7jhCiBjM+fhfqhqB6XuuU/SlrPdSNd8FPW+CH9U7ZZ0VJ8XIhdf0QCKyDsWSBaZ9OhBA1m/7tZ/h1O+raW1H+AU7br4q7AZq0xPjfq+jcnPI3cDIpXi6k6gShbrwTfvsJtsuIBUII9zM+fhdCwlCxA5y6X+Xjg2XYaDhxHP3Rm07dtyOkeLmY6jEAwiMxVn9idhQhRA2jf90Ou362nXXV8nf6/lXTlqi+g9BrV6L3pjl9/2WR4uViyscH1aM//PIj+nDJvR+FEMLZtNYYy9+F0HDb3yAXUdcPgdp1ML74wGXHKIkULzdQXfuAjw967QqzowghaopffoS0naiBt6H8arnsMKp2IKrntZDyHfrQXy47zoWkeLmBCg2HKzqj169Gnz1jdhwhRDWntbZd6wqLQHXr5/LjqT43gI8v+stlLj9WISlebmKJvRZyT6C3mNOtVAhRg+zYCr//eu6sy/Wzu6vgMFTXOPR3a9DHMl1+PHDj8FDlzf768ccfs27dOsA24d7+/ftZuHAhQUFBpc7+6lXaXgZRDdHJX8A1vcxOI4RH0vt3Q8YRuKRjpYYvEueddYVHorr1KX8DJ1H9bkKv/RK96mPUrcNdfjy3/HY4MvvroEGDGDTINkvnli1b+Oyzz4pMQ17S7K/eRCmF6tEf/f7r6P27Zb4vIS5grF2BfvdVKMiHkHBUj36oHv1RodbyNxZ/+/kH2L0L9Y9RKF/Xn3UVUvXqo2K6oteuQA+8DRVYx6XHc0vxOn/2V8A+++v5xet869evp2vXru6I5laqaxx62WJ08grUXQ+YHUd4qfJaMbTWLFq0iK1bt+Lv709CQgItWrTg6NGjzJ07l2PHjqGUok+fPgwcOBCApUuXsnr1avsHxDvuuMNtUxHp/HzbLL3ffA6XdsTSvT/Gui/Rn7yH/vx9VIdrUL0GQutLZI68cth7GFrrobrEuf34asDN6M3r0MlfoK691aXHckvxcmT210KnT59m27Zt3HPPPUWWlzT764UcmeEVTJzBNCKC7G59OL0xmfCR47HUrmNunlJ4Wh7wzExmcKQVY+vWrRw6dIg5c+aQmprKggULmDp1Kj4+PvzjH/+gRYsWnDp1iscee4zLLrvMvu11111nb/1wF33iOMYrM+C3n1D9bkLdMgxl8cGn4zXo9APob75Ar1+F3vItNGyK6huP6tJbilhpftoCe9NQ/xxjSrOratIS2nVAr/oY3WeQS3s5uuXZOTL7a6EffviBiy66qEiToaOzvzoywyuYO7q0vroX+psvOPrFMiw9BpiepySelgc8L5NZo8o70oqxZcsWevTogVKKNm3akJuba59osnBSytq1a9OwYUMyMzNLbQFxNb1/N8ZLUyA7CzViHJYLrgWreg1Qg+9B3zgUvSkZveYz9Bsv2JqjOshEryUxvv4MQq2oq827rm4ZcDPG/z2J3rDG6aN6nM8txcuR2V8LrV+/nm7duhVZVtrsr16pxUXQqLntE2X3/vIJUlSII60YmZmZRc5SrVYrmZmZRd5z6enp7N69m1atWtmXrVy5krVr19KiRQuGDRtW5APk+Rxp4SjvTDnvu6/JfmEyljpBhE6Zj1+bct7PN92JHjSYzPHDMT5YhLVHX5R/xUaM8LSzd2fnKUg/yNEdW6lz290ERUeblkl3603mx++iVy3HGn9HhSe8dJRbitf5s7+Gh4ezYcMGxo4dW2y9kydPsnPnTsaMGWNflpeXh9aa2rVr22d/vfVW17alupJSChU7AP3OfNi9y1bMhHCQI60Y5a2Tl5fH7NmzGT58OIGBgYBtEsvC99WSJUt466237JNYXsiRFo6yzpSNT99DL3/X9rv/wASyQ8PBwbNqPfgejFn/5ci7r2G5YYhD2ziSyQzOzmN8shSAUx27kFfJ/Tork+5zI8bL0zny5SdYOnUrf4NSlNXC4Zbi5cjsrwCbNm3i8ssvJyDg75GPy5r91Vupq2PRH7xh67ghxUtUgCOtGFartcgfoPPXyc/PZ/bs2XTv3p3OnTvb1wkNDbV/HxcXx4wZM1yS31i/Cr38XdTVvVDDRlX4moi6qD0qphv6iw/QXXqjrPVcktPb6IIC9Ler4JIOnvGadOhsuzVoxYfomK4uaWFy2xW9jh07Fuu9VFi0CvXs2ZOePXsWWRYVFcXMmTNdHc+tVECgrYBtWIMePAI8qClDeDZHWjFiYmJYsWIFXbt2JTU1lcDAQMLCwtBa8/LLL9OwYUOuv/76ItsUXhMD24fIxo0bOz27/vN39DsvQ9vLUMPHVro5Sd16N3r7Joylr+PzwGNOTumlfk6BYxlY7rjP7CQAKIsPqv9N6Ldegl+2QbsOTj+G3AVoEhV7LTp5Bfq7NdD0nvI3EALHWjE6dOhASkoKY8eOpVatWvbmv99++421a9fSpEkTHn30UeDvLvFvv/02e/bsQSlFZGQkI0eOdGpunZuDMX861KmL5b5HqnQdRFkjUdfehl7+DvqXH1EXX+7EpN7JWLcSgkPhsqvMjmKnru6FXv4uxoqP8JHiVX2oxs2hZVtbAbt9hNlxhBcprxVDKcW9995bbLu2bduydOnSEvd5/nVmZ9OGgbHw/yArA8ujU1HBoVXep+p/E3rDaoz/vYpl4gs1ejQOfSwDftpiu9XAg14H5ednmy7lgzfQu1NRzVs7df8ytqGJVI8BcOgvzv6cYnYUIVxGf77U9sf19ntQLds6ZZ/KrxaWwffAwX3obz5zyj69lV6/GgwD1b2v2VGKUT0GQFAwxisz0BnpTt23FC8TqZiuEBjEyRXuG4lZCHfSP6egP/4f6uqeqJ4Dnbvzy6+CSzuiP/4f+niWc/ftJbRhoL/9ynYdsZ459x6WRdUOxPLQJDiVizHzcXTGEaft2+FzzPz8fFJTU9m7dy+5ubnUqVOHpk2b0rp1a3w96FTVm6ha/qhufTm96mMsNw5FhUvHjerg2LFjbN++nT179nDy5EkCAwNp1qwZl112WZFefdWdzkjHWDAbGjRBDR3l9B5nSikst9+LMWks+qO3UMMfdOr+vcKvP8LRw6ib/mF2klKppq2wjHsGI3EixqzHbU3H4ZFV3m+5Vef48eMkJSWRnJxMUFAQDRs2JCAggLy8PL744gtycnKIjY0lPj7eqwfONYvqNRC9arltLDAP/gUU5du/fz9Llixhx44dtGjRgoYNGxIaGsqpU6dYu3Ytb7zxBpdccgm33367aaNauIs+c9rWQcMowPLAhArfUOwoFd0I1ecG9Mpl6B4DatytJ8balRBUF9XhGrOjlEk1a43locIC9l8sj0ypcgErt3g99dRT9OrVi5kzZ9pHujhfZmYm3377LU899RSJiYlVClMTqYgo/Dt14/Talejrb3fpWGDCtebNm8egQYMYO3YsfiXMoZSfn8/mzZuZP3++fazO6urEwudhbxqWUY+jolzbnKWuvx29MdnWeWPCTJSlZlwN0cePwbZNqF7XuWXOrqpSzVtjGff0eQVsapVam5Qu6Xb88+Tn5zvULOjoeu504MCBEpd72p32wQf2kPXUWNTwB7F0df9I0BfytNcHPC+TWWMbeqIL32c65TuM+dNQ196C5eZ/uiWDsfFr9MJE1L0PY+kcW+I6nvY7VNU8xsqP0B+8geWZuaj6zrkvzx2vkf7jN4zEiRAcaitgYaVPeVPW+6zcjyjnF6TXX3+9xHXeeOMNjytc3sSv/ZXQoAl6zSclDu0jvM9zzz1X4vLC0WKqtfYxBI14EHXjULcdUnXuCfUaoL/5wm3HNJPWGr3uK2h1sdMKl7uoFhdheehpOH4MY9Z/bV39K6FC59fJycklLl+7dm2lDi5slFKouOvhzz8g7Rez4wgn2LFjR4WWVyfKz486N9zusgFZSzymUqge/SBtJ/rgPrcd1zS7dsDhv1Dd+5W/rgdSLdvaClh2Fsbzk9BGQYX34dDp0po1awDb2IKF3xdKT0+nbt26FT6wKEp17on+8E30mk9Rrb10xHzBkiVLAFszeuH3hQ4fPkxkZNV7WYmSqWt6o5e9jV77Jer26j1qjV63EmrXQV1Z+UFvzWYrYJPgZA7KUvEPOg4Vr3Xr1gG2N2Th94VCQkIYNWpUhQ8silL+Aahu/Ww9DzOPSrd5L1U4aK5hGEUG0AXb9YTBgwebEatGUMGhqA5Xo79bg775H9W285POPYH+YQOqe8WnhfE0qtXFld7WoeL11FNPAfDee+8xZEjFpiEoVN7U5Tt27OC5556jXj3biMidO3e2T9FQ3rbVheo1EP2VdJv3ZoXjCLZp06bUGb+F66ge/dFbvkWnfIcqpeOGt9Mbv4H8s6ju/c2OYqpyi9f5vQjLKlxnz54tsXswODZ1OcDFF1/MY489VqltqwMVEQWXX4WWbvNeKTs7m5CQEIAyC9exY8dq1M3KbnVRe4iMRq/7Eqpr8fr2K2jayjY+ag1WboeNRx55hOXLl5OZmVni41lZWSxfvpx///vfpe7j/KnLfX197VOXO6Iq23ojS+/rIOc4etO68lcWHuXpp59mwYIF7Nq1C8MwijxmGAa7du1iwYIFTJ48uUrH2bZtGw8++CBjxowhKSmp2ONaa15//XXGjBnDI488wh9//FHutjk5OUyePJmxY8cyefJkcnJyqpTRLMpisXVi+O0n9KG/zI7jdHrfbti/B+UBt9SYrdwzr2eeeYakpCQeffRRgoKCqF+/PrVr1+bUqVMcPHiQkydPEhsby9NPP13qPhyZuhxg165dPProo4SFhfGPf/yDxo0bO7wtODY9OXj2dOC6W28y3n8dtfYLwgcNdskkbhXJ4yk8MdOFnnvuOVatWsUrr7xCeno69erVs79X0tPTiY6Opm/fvgwfPrzSx3CkJWLr1q0cOnSIOXPmkJqayoIFC5g6dWqZ2yYlJdG+fXvi4+NJSkoiKSmJoUPd19XdmVSXONt0Keu+RN12t9lxnEpv/Bp8fFAx3c2OYrpyi1dwcDDDhg3jzjvvJDU1lT///JPc3FyCgoJo0qQJrVq1KvceL0emLm/evDnz5s0jICCAlJQUZs6cyZw5cxzatpAj05OD59+saPS8Fr14Hkc3rjOl56GnvT7geZlKunnS19eXAQMGMGDAAI4ePcqff/7JyZMn7eOAljRCTUWd3xIB2Fsizi9eW7ZsoUePHiilaNOmDbm5uWRlZXHkyJFSt928eTOTJk0CIDY2lkmTJnlv8QoJg8s7ozesRscP9YrRJxyhjQL092vh0itRdWUoPofvLPb19eXiiy/m4osr3jvEkanLAwMD7d937NiRhQsXcvz4cYe2rW7s3eZXfyLd5r1URESES84UHWmJyMzMLHJsq9VKZmZmmdtmZ2fb31dhYWEcP3681AyOtHCYfaZ8+obbOPb0Bur+sZOAc01sZme6UEXznN72PceyMwnpN4gAFz0PT3uNylLhYTF+/PFH9uzZQ15eXpHlt99+e6nbODJ1+bFjxwgJCUEpRVpaGoZhULduXerUqVPuttWNdJv3fvn5+XzzzTclvldGjx5d6f060hJR2joVacUoiyMtHGafKesGzcFaj+zPPiDnoss9ItOFKprHWLkcAutwonlbclz0PDztNSpreKgKFa+FCxfy3Xffcckll+BfgfsLHJm6fOPGjXz55Zf4+PhQq1YtHnroIZRSpW5b3Um3ee/20ksvsXfvXq688kp7D0RncKQlwmq1FvkDVLhOfn5+qduGhISQlZVFWFgYWVlZXj9DRGHHDZ30Njr9gEfOdVUROu+Urfv/1T2lF/I5FSpe69ev57nnnqvUaWV5U5cXXitwdNvq7u9u8yvQA29D+QeYHUlUwI8//shLL71EnTp1nLpfR1oxYmJiWLFiBV27diU1NZXAwEDCwsIIDg4udduYmBiSk5OJj48nOTmZTp06OTW3GVTXOPTH76LXfYW6xT0DBLuK3roRzpxGXd3L7Cgeo0LFq7AZT7iHpf9NGNs2or/+DDXgFrPjiAqIiIjg7NmzTt+vI60YHTp0ICUlhbFjx1KrVi37jdNltWLEx8eTmJjImjVriIiIYPz48U7P7m4q1AqXXYVevwp9451mx6kSvfFriIiCKoxIUd1UqHhdf/31zJkzh5tuuqlYU0hhDybhPKrVxbZpzld+hO55LSogsPyNhEfo0aMHM2fO5Nprry12Q/Kll15apX2X14qhlOLee+91eFuwfTCdOHFilXJ5IkuPfhjbNsKPmyF6kNlxKkVnZcAvP6KuM+fWGU9VoeK1YMECAFJSUoo9duEgpMI5LIPuwpj6MHrVJ6jrS+8UIzzLihUrAPjf//5XZLlSipdeesmMSDXTJR0gPMI243B/Ly1em5JBa2kyvECFipcUKPdTzVvbrn19lYTufR0qMMjsSMIBc+fONTuCAJTFx9Zz9+N3KTh8AHy8r7OD/u5raHGRy2ek9jY1Y75sL2e58S44mYv+arnZUYTwOqprH1AWTn31sdlRKkzv2w1/7ZWzrhKUe+Y1ZcoU/vvf/wIwceLEUttcyxoeSlSNatwcruyCXvUxOu4GVJB3d2OursaNG0diYiIADzzwQKnrzZ8/312RBNjuk2x/Jae+/hz63VSpuaPMYhsOyhfVyXvn7XKVcotXbOzfIzP37t3bpWFE6Sw33ImR8h165TKv7/ZbXf3rX/+yfz9mzBgTk4gLWbr2wZg/DcuObdD+SrPjOEQXFKC/T4b2V8oH1hKUW7y6dfu74vfs2bPcHS5YsKDUnk6i8lTDJqhOPdBrPkX3HYQKrt5DZHmjtm3b2r9v1678Yb2mTZvGhAkTXBlJFLosBhUcirH+K3y8pHjxy4+QnYVFmgxL5PRrXhfOtCycR90wBM6eRX/xkdlRhBP8+uuvZkeoMZSvH7Vj+8O2TegTpY/b6En0xq8hsA5c5v03jLuC04tXSeOnCedQ0Q1R1/RCJ3+BPpZR/gZCCLvacddDQT76+2/MjlIunXcKvXUjKqZbtRkV39mcXrzkJjrXUtffDkYB+vP3zY4ihFfxbdoSmrVGf/uVx3/I1inf2YaDukaaDEtT4VHlK2vbtm0sWrQIwzCIi4sjPj6+yOPr1q1j+XJbV/CAgADuvfdemjVrBsCoUaMICAjAYrHg4+PD9OnT3RXb46jIaFTXPuh1X6L734KyRpodSQivobr2Qb8zH/78HZq2MjtOqfTGryEyGlrKcFClcXrxKukTjSOzv9arV49JkyYRFBTE1q1befXVV5k6dar98aeeesrrR7p2FnXdYNtEe58tQQ2r/PQawlye/um/OlJXdUcvXYj+dhXKQ4uXzkiHX7ejrrtdWrLKUOHidezYMdLS0jhx4kSRN19hN/ru3YtPT+3I7K8XXXSR/fvWrVsXmbpBFKXCI1Hd+9tGnB9ws9dP91BdODoCTeHcdzfddFOFj5GTk0NiYiJHjhwhMjKScePGERRUfNSV0lo6Fi9ezA8//ICvry9RUVEkJCRQp04d0tPTGTdunH3+pNatWzNy5MgK5/N0KjAI1eEa9KZk9OARHjm9iF67ElCobn3NjuLRKlS8Nm3axIsvvkj9+vXZt28fjRs3Zt++fbRt29ZevO67775i2zky++v51qxZQ4cOHYosmzJlCgB9+/YtMhFeTaUG3ob+bg3G4nlYxk+WT2ge4PwPXGfOnOH777+nVatW9gn+0tLS6Ny5s32dyhSvpKQk2rdvT3x8PElJSSQlJTF06NAi65TV0nHZZZdx55134uPjw9tvv82yZcvs20dHRzNz5sxKPnvvobr1sRWvrRtRV/UwO04ROv8set2Xtq79ckmgTBUe2zAhIYFrrrmGu+++m+eee46vv/6affv2lbldRWZw/fnnn/n666955pln7MsmT55MeHg42dnZPPvsszRo0KDE+2gcmZ4cPG+q60rliYjg5PAxnHj5Oeps3UBgvxvNzeNinpjpQoVTjwA8//zzPPjgg1x99dX2Zd9//z3fffddlY6xefNmJk2aBNgGEJg0aVKx4lVWS8fll19uX69NmzZs3LixSnm80kXtwVoPvX4VeFrx2roRTmRjib3W7Cger0LF6+jRo1xzzTVFlsXGxjJy5EiGDRtW6naOzP4KsHfvXl555RUmTJhA3bp17cvDw8MB22yvnTp1Ii0trcTi5cj05OB5U11XNo/u0AUuas+JN14kt9lFtmFwTMzjSp6WqazpyQG2bt1abJLITp06MW/evCodNzs72/7eCQsL4/jx4vcsOdrSsWbNGrp06WL/OT09nX//+9/Url2bIUOGcPHF1bOzgLJYUF3i0J++h85IR1nrmR3JTn/zhW3erks6lL9yDVeh4hUcHMyxY8cIDQ0lMjKSXbt2UbduXQzDKHM7R2Z/PXr0KLNmzWL06NFF/jDk5eWhtaZ27drk5eWxfft2br311orErraUxYJl2GiMp8dgvDMfy+gnpPnQQ0RHR7NixQoGDhxoX7Zy5Uqio6PL3Xby5MkcO3as2PIhQ4Y4dGxHWjo++ugjfHx87Neow8LCmDdvHnXr1uWPP/5g5syZzJ49m8DA4nPIOdLC4YlnyudnKrj+Vo5++h61t20k6PYRpucByP/zDzJ2/UzQsATq1DOnoHri/1tpKlS84uLi+PXXX7n66qu57rrrePrpp1FKcf3115e5nSOzv37wwQfk5OTY5wwr7BKfnZ3NrFmzACgoKKBbt25cccUVlXiq1ZOqVx8V/w9bD6rvk1FX9zQ7kgDuv/9+Zs2axccff0x4eDiZmZn4+Pjw8MMPl7vtk08+WepjISEhZGVlERYWRlZWVok9cMtr6fjmm2/44Ycfigy07efnh9+5m2FbtGhBVFQUBw8epGXLlsX270gLh6edKcMFmSx+0PYycr/6mFO9rkdZ3D/BxoWvkZH0P/D15eQV13DKpNfO0/7fymrhqFDxOv/erNjYWC655BLy8vKK9BosTXmzv95///3cf//9xbaLioqqEReRq0LFXY/e8i16yWvodleggkPNjlTjNW/enBdeeIHU1FSysrIIDQ2lTZs2+PpW7e6UmJgYkpOTiY+PJzk5mU6dig8dVFZLx7Zt21i+fDlPP/00/v7+9m2OHz9OUFAQFouFw4cPc/DgwWo/O7rq2ge9YDb89hNcfHn5G7iQzjuF3vg16squqLoh5W8gqnafl7ecXlZ3yuKD5Z9jMCY/hP7fq6h//dvsSAJbE4yzrxvFx8eTmJjImjVriIiIYPz48YDtOlfh9eLSWjoAFi5cSH5+PpMnTwb+7hK/c+dOli5dio+PDxaLhfvuu6/ELvjViepwNbp2HfT6VSizi9emtXDqJKqndNRwlNLV+E7JAwcOlLjc006NnZXH+GwpOultLA9MQHW8pvwNXJzHmTwtU3kdNmqSkt5nnvb/BSVnMt6Zj16/GsusN9w+S3lhHq01xuSHQGssE18w9bq1p/2/lfU+k5mUqxHV/2Zo3Bzj3ZfRuTlmxxHC46mufeDsGfTmb80L8cdvsG83KvZa6XBVAVK8qhHl64tl+Fg4kY1eutDsOEJ4vqatoGFT9LdfmRZBJ38B/rVRV8eWv7Kwk+JVzagmLVH9b7aNffjTD2bHEcKjKaVQPfrDnlT0bz+5/fg65zh687eoa3qiAorfliBKJ8WrGlI3DIEGTTAWzEIf+NPsOEJ4NNWtL4SEYXzyntuPrTeshvyzKBlRo8KkeFVDyq8WljFPgl8tjBeelokrhSiDquWPGnAL/PaTW8++tGHYRtRo1Q7VqJnbjltdSPGqplREFJYxEyH3BMYLz6BPnTQ7khAeS/Xo7/azrzPbN8ORQ0j3+MqR4lWNqaYtsdz/HziwF+Pl6ej8fLMjCeGRzDj7OrViGdQNQXXsUv7KohgpXtWcuvRK1D9Gwc5t6LdekgkQhSiFO8++dOZRTm/+FtW1D+rcsFyiYqR41QCWbn1RN9yB/m4N+uP/mR1HCI/kzrMvnbQYLBZbwRSVIsWrhlA3DLGN5fbpexjrvjQ7jhAeyR1nX/rX7ejvvqbOjXeiIsufZUCUrGqjhFZAadOSF9Jas2jRIrZu3Yq/vz8JCQm0aNHCoW1F+ZRSMDQBfSwD/fY8dGg4qn2M2bGE8CiFZ196yQL0bz+hLmrv1P3rs2cx3pkPEVHUuW04eSdkJJzKcsuZV+G05I8//jiJiYmsX7+e/fv3F1ln69atHDp0iDlz5jBy5Ej71CiObCsco3x9bR04GjXDmDcVY+0KsyMJ4XFcefalV34Ih/7Cctf9KP8Ap++/JnHLmVdZ05IX2rJlCz169EApRZs2bcjNzSUrK4sjR46Uu61wnAoIxDJ+MsZrs9CL52HsTkXd+S+UXy2zowkH5OTkkJiYyJEjR4iMjGTcuHEljv5eWmvF0qVLWb16tX0esDvuuMM+VdGyZctYs2YNFouFu+++u8bOm+eqsy+dfgD92fuomG6oS690yj5rMrcUL0emJc/MzCwyxYrVaiUzM9PhKc3BsRlewfNmC3V7nogI9NNzyH1vAbkfvInPoX2E/nsqPufa3z3t9QH3ZtIFBRQc+gt9Mge/1u3cckxHJSUl0b59e+Lj40lKSiIpKYmhQ4cWWaewteKJJ57AarUyYcIEYmJi7B/4rrvuOgYNGlRkm/3797Nhwwb+7//+j6ysLCZPnswLL7yAxYRJGj2B6tEfveJDjE/ew8cJxUtrjfHOy+Dnh7r9HickFG4pXo5MS17aOo5sW8iRGV7B84b9Ny1P/1uw1GtI/uuJHB0/HMvIR1EXX+5xrw+45jXSRgEcPQwH/kT/9Scc2GcbTuvQfsg/Cw2a4PP0SyVua9aUKJs3b2bSpEmAbULYSZMmFStejrR0lLTfLl264OfnR7169YiOjiYtLY02bdq47Ll4MmeffenN62DnNtQdI1Gh1vI3EOVyS/Eqb1rywnXO/+NUuE5+fn6524rKUx2uxvLf2RjzpmEkPoW65Z/oO+81O5ZL6PyzsCcNvetndOoOSPsF8k79vUJ4BDRoimp3BTRogmrU1LSspcnOzrb//oeFhXH8+PFi65TXWrFy5UrWrl1LixYtGDZsGEFBQWRmZtK6dWv7OuHh4WRmZpaYwZEWjupw9q5vuoujXy7DZ8WHhHftVenjGrknyHj/dXxatSX8ln+gfHwqlccdPDFTadxSvMqalrxQTEwMK1asoGvXrqSmphIYGEhYWBjBwcHlbiuqRkU3wvL4TIw35qA/WET2X3vQNw1DhXn3J0R99izs/s1WrHbtgN9/gTNnbA/Wb4zqHAtNW6EaNLEVq9qeMar35MmTOXbsWLHlQ4YMcWj7slor+vXrx6233grAkiVLeOutt0hISKjQzeuOtHBUl7N33e8mzi5ZQPr7b2LpdV2ljmu8Mx+dfQxGP0lGVlaV8riap2Uqq4XDLcWrtGnJv/zSdr9Rv3796NChAykpKYwdO5ZatWqRkJBQ5rbCuVRAIJZ//Qe98iNOJ70Nm79Fde+HGnALKtw7Polpw4D9e9C//Ij+ZRuk7rAVK6WgYTNU9/6o1pdAm0tQdUPMjluqJ598stTHQkJCyMrKIiwsjKysLHvHi/OV1dIRGhpqXx4XF8eMGTNK3CYzM5Pw8PCqPhWvp2KvRe/chn73FYyso6j4f6AqcB1Q//EbOnkFqvf1qKYtXZi05nHbfV4dO3a092oq1K9fP/v3Sinuvbfk5qqSthXOp5RCDbiFsL43kPHOq+i1K9DrVqK69UUNuBVljTQ7YhFaazhyEP3rT/DLj+hft0POuWa0+o1R3fqhLr4MWl+KquPeKd5dJSYmhuTkZOLj40lOTqZTp07F1imrpaOw8AFs2rTJ/kEwJiaGOXPmcP3115OVlcXBgwdp1aqV+56Yh1J+flhG/Rf97ivoLz6EjKMwfKxDQzrpggKMt+dBSBjqxrvckLZmcVvxEt7DJ6oBlmGj0QNvQ3/xAXrdV+h1X9nGYRt4K8paz5Rc2jDg4D5bE2DqDtvX7HPXZULDUe2vhIuvQLW9zOubPEsTHx9PYmIia9asISIigvHjxwO2M6VXXnmFCRMmlNla8fbbb7Nnzx6UUkRGRjJy5EgAGjduzDXXXMP48eOxWCzcc889Nban4YWUjw8MfQCskehli9HZmVgSJqACS/9ApDOOoD9bAvt2Y7n/MY9pkq5OlK7GI7UeOHCgxOWe1q7r6Xl0xhH0F++jv10FaGhzKeqi9qi2l9muGfk6/zOQ1hqys2zNgPt3U2vfH5zesQ1yT9hWCLWi2lwCrS9BXXQpRDcqtReqK5jV29ATlfQ+87TfaXBOJmPjN+g35kC9+lgenFSkNUJrDak7MFZ/Cls3AqBiB9juoyzhd7O6vkbOZPo1L+HdlDUSNTTBdia2+hP0jq3opLfRAP61oXU7VNv2tu7EjZqhfB0fJVufPQsnsuF4lq2b+v496P17YP8e2/Jz8qMaoK64ytYE2OYSiIhya7ESAsBydU90SBjG/GkY0x7FMnYiRDVEb0pGr/nU9ntbpy6qXzyq10DTWilqAilewmEqPBJ12wi4DfTxY7DrZ/RvP6F//Qn9wQ/YT+Fr+UPtOhB47l/tQFTtOuDrh845brsudSLb9vX8ruoAfrVsPf8u6wSNm9tmmG3UjIimzT3qE6GoudTFl2P5zwyMF57GeG4C+PraWgQaNUMNG426Khbl7292zGpPipeoFBUcCjHdUDHdANDHMm3TSBw5BKdy4dRJ9MkcOHUSck6g0w/ZbvwNqgtBwajI+lA3GOqGQN1gVFAI1G8M9erb74MRwlOphk2xTJiJsWA2BNXF0vsGWy9WaQ1wGylewilUaLjtvikhaggVZsXn0almx6ixpDuREEIIryPFSwghhNeR4iWEEMLrVOv7vIQQQlRPNfLM67HHHjM7QhGSp3yemEmUzhP/vzwtk6flAc/MVJoaWbyEEEJ4NyleQgghvE6NLF7nz0XkCSRP+TwxkyidJ/5/eVomT8sDnpmpNNJhQwghhNepkWdeQgghvJsULyGEEF6nRo1tuG3bNhYtWoRhGMTFxREfH292JEaNGkVAQAAWiwUfHx+mT5/u1uPPmzePlJQUQkJCmD17NgA5OTkkJiZy5MgRIiMjGTduHEFB7puJuKRMS5cuZfXq1fZp7++44w6ZXdtDyfusOHmfuYCuIQoKCvTo0aP1oUOH9NmzZ/Ujjzyi9+3bZ3YsnZCQoLOzs007/o4dO/Tvv/+ux48fb1+2ePFivWzZMq211suWLdOLFy82PdOSJUv08uXL3ZpDVJy8z0om7zPnqzHNhmlpaURHRxMVFYWvry9dunRh8+bNZscyXbt27Yp92tu8eTOxsbYR4mNjY93+OpWUSXgHeZ+VTN5nzldjmg0zMzOxWq32n61WK6mpqSYm+tuUKVMA6Nu3r0d0Vc3OziYsLAyAsLAwjh8/bnIim5UrV7J27VpatGjBsGHDvPqNV13J+8xx8j6rmhpTvHQJdwR4wsRxkydPJjw8nOzsbJ599lkaNGhAu3btzI7lcfr168ett94KwJIlS3jrrbdISEgwOZW4kLzPvJs3vc9qTLOh1WolIyPD/nNGRob9U4+ZwsPDAQgJCaFTp06kpaWZnMiWJSsrC4CsrCz7xVszhYaGYrFYsFgsxMXF8fvvv5sdSZRA3meOk/dZ1dSY4tWyZUsOHjxIeno6+fn5bNiwgZiYGFMz5eXlcerUKfv327dvp0mTJqZmAoiJiSE5ORmA5ORkOnXqZHIi7G9ygE2bNtG4cWMT04jSyPvMcfI+q5oaNcJGSkoKb775JoZh0KtXL26++WZT8xw+fJhZs2YBUFBQQLdu3dye6fnnn2fnzp2cOHGCkJAQBg8eTKdOnUhMTOTo0aNEREQwfvx4t7Z7l5Rpx44d7NmzB6UUkZGRjBw50iM+0Yvi5H1WnLzPnK9GFS8hhBDVQ41pNhRCCFF9SPESQgjhdaR4CSGE8DpSvIQQQngdKV5CCCG8jhQvIYQQXkeKlxBCCK/z/3aogtG30TmsAAAAAElFTkSuQmCC\n",
"text/plain": [
"<Figure size 432x288 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",
"v_mpc=np.array(x.value[2, :]).flatten()\n",
"theta_mpc=np.array(x.value[3, :]).flatten()\n",
"a_mpc=np.array(u.value[0, :]).flatten()\n",
"delta_mpc=np.array(u.value[1, :]).flatten()\n",
"\n",
"#simulate robot state trajectory for optimized U\n",
"x_traj=predict(x0, np.vstack((a_mpc,delta_mpc)))\n",
"\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_ref[0,:],x_ref[1,:],\"g+\")\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, 3)\n",
"plt.plot(a_mpc)\n",
"plt.ylabel('a_in(t)')\n",
"#plt.xlabel('time')\n",
"\n",
"\n",
"plt.subplot(2, 2, 2)\n",
"plt.plot(theta_mpc)\n",
"plt.ylabel('theta(t)')\n",
"\n",
"plt.subplot(2, 2, 4)\n",
"plt.plot(delta_mpc)\n",
"plt.ylabel('d_in(t)')\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"full track demo"
]
},
{
"cell_type": "code",
"execution_count": 14,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CVXPY Optimization Time: Avrg: 0.1654s Max: 0.2158s Min: 0.1471s\n"
]
}
],
"source": [
"track = compute_path_from_wp([0,3,4,6,10,12,14,6,1,0],\n",
" [0,0,2,4,3,3,-2,-6,-2,-2],0.05)\n",
"\n",
"# track = compute_path_from_wp([0,10,10,0],\n",
"# [0,0,1,1],0.05)\n",
"\n",
"sim_duration = 200 #time steps\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.5 #m/s\n",
"MAX_ACC = 1.0 #m/ss\n",
"MAX_D_ACC = 1.0 #m/sss\n",
"MAX_STEER = np.radians(30) #rad\n",
"MAX_D_STEER = np.radians(30) #rad/s\n",
"\n",
"REF_VEL = 1.0 #m/s\n",
"\n",
"# Starting Condition\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0 #x\n",
"x0[1] = -0.25 #y\n",
"x0[2] = 0.0 #v\n",
"x0[3] = np.radians(-0) #yaw\n",
" \n",
"#starting guess\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:] = MAX_ACC/2 #a\n",
"u_bar[1,:] = 0.0 #delta\n",
"\n",
"for sim_time in range(sim_duration-1):\n",
" \n",
" iter_start = time.time()\n",
" \n",
" # dynamics starting state\n",
" x_bar = np.zeros((N,T+1))\n",
" x_bar[:,0] = x_sim[:,sim_time]\n",
" \n",
" #prediction for linearization of costrains\n",
" for t in range (1,T+1):\n",
" xt = x_bar[:,t-1].reshape(N,1)\n",
" ut = u_bar[:,t-1].reshape(M,1)\n",
" A,B,C = get_linear_model(xt,ut)\n",
" xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n",
" x_bar[:,t] = xt_plus_one\n",
" \n",
" #CVXPY Linear MPC problem statement\n",
" x = cp.Variable((N, T+1))\n",
" u = cp.Variable((M, T))\n",
" cost = 0\n",
" constr = []\n",
"\n",
" # Cost Matrices\n",
" Q = np.diag([20,20,10,0]) #state error cost\n",
" Qf = np.diag([10,10,10,10]) #state final error cost\n",
" R = np.diag([10,10]) #input cost\n",
" R_ = np.diag([10,10]) #input rate of change cost\n",
"\n",
" #Get Reference_traj\n",
" x_ref, d_ref = get_ref_trajectory(x_bar[:,0] ,track, REF_VEL)\n",
" \n",
" #Prediction Horizon\n",
" for t in range(T):\n",
"\n",
" # Tracking Error\n",
" cost += cp.quad_form(x[:,t] - x_ref[:,t], Q)\n",
"\n",
" # Actuation effort\n",
" cost += cp.quad_form(u[:,t], R)\n",
"\n",
" # Actuation rate of change\n",
" if t < (T - 1):\n",
" cost += cp.quad_form(u[:,t+1] - u[:,t], R_)\n",
" constr+= [cp.abs(u[0, t + 1] - u[0, t])/DT <= MAX_D_ACC] #max acc rate of change\n",
" constr += [cp.abs(u[1, t + 1] - u[1, t])/DT <= MAX_D_STEER] #max steer rate of change\n",
"\n",
" # Kinrmatics Constrains (Linearized model)\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_bar[:,0]] #starting condition\n",
" constr += [x[2,:] <= MAX_SPEED] #max speed\n",
" constr += [x[2,:] >= 0.0] #min_speed (not really needed)\n",
" constr += [cp.abs(u[0,:]) <= MAX_ACC] #max acc\n",
" constr += [cp.abs(u[1,:]) <= MAX_STEER] #max steer\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[:,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": 15,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 1080x720 with 5 Axes>"
]
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"#plot trajectory\n",
"grid = plt.GridSpec(4, 5)\n",
"\n",
"plt.figure(figsize=(15,10))\n",
"\n",
"plt.subplot(grid[0:4, 0:4])\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, 4])\n",
"plt.plot(u_sim[0,:])\n",
"plt.ylabel('a(t) [m/ss]')\n",
"\n",
"plt.subplot(grid[1, 4])\n",
"plt.plot(x_sim[2,:])\n",
"plt.ylabel('v(t) [m/s]')\n",
"\n",
"plt.subplot(grid[2, 4])\n",
"plt.plot(np.degrees(u_sim[1,:]))\n",
"plt.ylabel('delta(t) [rad]')\n",
"\n",
"plt.subplot(grid[3, 4])\n",
"plt.plot(x_sim[3,:])\n",
"plt.ylabel('theta(t) [rad]')\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## OBSTACLE AVOIDANCE\n",
"see dccp paper for reference"
]
},
{
"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.8.5"
}
},
"nbformat": 4,
"nbformat_minor": 4
}