From 26832658416dbbf6725291dd5c066ddebe373e62 Mon Sep 17 00:00:00 2001 From: mcarfagno Date: Wed, 22 Apr 2020 15:32:10 +0100 Subject: [PATCH] WIP: fixed equations for cte --- .../MPC_cvxpy-checkpoint.ipynb | 225 +--- notebook/MPC_cte_cvxpy.ipynb | 1084 +++++++++++++++++ .../{MPC_scipy.ipynb => MPC_cte_scipy.ipynb} | 0 notebook/MPC_cvxpy_v2.ipynb | 1083 ---------------- notebook/MPC_scipy_v2.ipynb | 616 ++++++++++ ...C_cvxpy.ipynb => MPC_tracking_cvxpy.ipynb} | 277 +---- notebook/equations.ipynb | 19 +- 7 files changed, 1818 insertions(+), 1486 deletions(-) create mode 100644 notebook/MPC_cte_cvxpy.ipynb rename notebook/{MPC_scipy.ipynb => MPC_cte_scipy.ipynb} (100%) delete mode 100644 notebook/MPC_cvxpy_v2.ipynb create mode 100644 notebook/MPC_scipy_v2.ipynb rename notebook/{MPC_cvxpy.ipynb => MPC_tracking_cvxpy.ipynb} (50%) diff --git a/notebook/.ipynb_checkpoints/MPC_cvxpy-checkpoint.ipynb b/notebook/.ipynb_checkpoints/MPC_cvxpy-checkpoint.ipynb index a84d822..2ba65d1 100644 --- a/notebook/.ipynb_checkpoints/MPC_cvxpy-checkpoint.ipynb +++ b/notebook/.ipynb_checkpoints/MPC_cvxpy-checkpoint.ipynb @@ -2,7 +2,14 @@ "cells": [ { "cell_type": "code", - "execution_count": 117, + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + }, + { + "cell_type": "code", + "execution_count": 2, "metadata": {}, "outputs": [], "source": [ @@ -211,7 +218,7 @@ }, { "cell_type": "code", - "execution_count": 118, + "execution_count": 3, "metadata": {}, "outputs": [], "source": [ @@ -228,7 +235,7 @@ }, { "cell_type": "code", - "execution_count": 119, + "execution_count": 4, "metadata": {}, "outputs": [], "source": [ @@ -274,7 +281,7 @@ }, { "cell_type": "code", - "execution_count": 120, + "execution_count": 5, "metadata": {}, "outputs": [], "source": [ @@ -329,15 +336,15 @@ }, { "cell_type": "code", - "execution_count": 121, + "execution_count": 6, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "CPU times: user 6.68 ms, sys: 142 µs, total: 6.82 ms\n", - "Wall time: 10.8 ms\n" + "CPU times: user 7.87 ms, sys: 0 ns, total: 7.87 ms\n", + "Wall time: 7.41 ms\n" ] } ], @@ -367,7 +374,7 @@ }, { "cell_type": "code", - "execution_count": 122, + "execution_count": 7, "metadata": {}, "outputs": [ { @@ -426,15 +433,15 @@ }, { "cell_type": "code", - "execution_count": 123, + "execution_count": 8, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "CPU times: user 2.25 ms, sys: 121 µs, total: 2.37 ms\n", - "Wall time: 1.49 ms\n" + "CPU times: user 1.8 ms, sys: 650 µs, total: 2.45 ms\n", + "Wall time: 1.79 ms\n" ] } ], @@ -468,7 +475,7 @@ }, { "cell_type": "code", - "execution_count": 124, + "execution_count": 9, "metadata": {}, "outputs": [ { @@ -529,7 +536,7 @@ }, { "cell_type": "code", - "execution_count": 125, + "execution_count": 10, "metadata": {}, "outputs": [], "source": [ @@ -619,7 +626,7 @@ }, { "cell_type": "code", - "execution_count": 126, + "execution_count": 11, "metadata": {}, "outputs": [], "source": [ @@ -657,7 +664,7 @@ }, { "cell_type": "code", - "execution_count": 127, + "execution_count": 12, "metadata": {}, "outputs": [ { @@ -700,7 +707,7 @@ }, { "cell_type": "code", - "execution_count": 128, + "execution_count": 13, "metadata": {}, "outputs": [], "source": [ @@ -738,7 +745,7 @@ }, { "cell_type": "code", - "execution_count": 129, + "execution_count": 14, "metadata": {}, "outputs": [ { @@ -866,15 +873,15 @@ }, { "cell_type": "code", - "execution_count": 130, + "execution_count": 28, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "CPU times: user 367 ms, sys: 110 µs, total: 367 ms\n", - "Wall time: 363 ms\n" + "CPU times: user 219 ms, sys: 3.99 ms, total: 223 ms\n", + "Wall time: 217 ms\n" ] } ], @@ -901,7 +908,7 @@ "x0[3]=psi\n", "x0[4]=cte\n", "\n", - "# Prediction\n", + "# Linearized Model Prediction\n", "x_bar=np.zeros((N,T+1))\n", "x_bar[:,0]=x0\n", "\n", @@ -925,16 +932,21 @@ "\n", "for t in range(T):\n", " \n", - " # Cost function\n", - " cost += 10*cp.sum_squares( x[3, t]) # psi\n", - " cost += 10*cp.sum_squares( x[4, t]) # cte\n", - " \n", - " # Actuation effort\n", - " cost += cp.quad_form( u[:, t],10*np.eye(M))\n", - " \n", + " # Tracking\n", + " if t > 0:\n", + " idx,_,_ = calc_err(x_bar[:,t],track)\n", + " delta_x = track[:,idx]-x[0:3,t]\n", + " cost+= cp.quad_form(delta_x,10*np.eye(3))\n", + "\n", + " # Tracking last time step\n", + " if t == T:\n", + " idx,_,_ = calc_err(x_bar[:,t],track)\n", + " delta_x = track[:,idx]-x[0:3,t]\n", + " cost+= cp.quad_form(delta_x,100*np.eye(3))\n", + "\n", " # Actuation rate of change\n", " if t < (T - 1):\n", - " cost += cp.quad_form(u[:, t + 1] - u[:, t], 5*np.eye(M))\n", + " cost += cp.quad_form(u[:, t + 1] - u[:, t], 25*np.eye(M))\n", " \n", " #constrains\n", " A,B,C=get_linear_model(x_bar[:,t],u_bar[:,t])\n", @@ -948,7 +960,7 @@ "\n", "\n", "prob = cp.Problem(cp.Minimize(cost), constr)\n", - "solution = prob.solve(solver=cp.ECOS, verbose=False)" + "solution = prob.solve(solver=cp.OSQP, verbose=False)" ] }, { @@ -960,7 +972,7 @@ }, { "cell_type": "code", - "execution_count": 131, + "execution_count": 29, "metadata": {}, "outputs": [ { @@ -972,7 +984,7 @@ }, { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ "
" ] @@ -1031,126 +1043,7 @@ }, { "cell_type": "code", - "execution_count": 132, - "metadata": {}, - "outputs": [], - "source": [ - "\n", - "# track = compute_path_from_wp([0,5,7.5,10,12,13,13,10],\n", - "# [0,0,2.5,2.5,0,0,5,10])\n", - "\n", - "# sim_duration =100 \n", - "# opt_time=[]\n", - "\n", - "# x_sim = np.zeros((N,sim_duration))\n", - "# u_sim = np.zeros((M,sim_duration-1))\n", - "\n", - "# MAX_SPEED = 1.25\n", - "# MIN_SPEED = 0.75\n", - "# MAX_STEER_SPEED = 1.57/2\n", - "\n", - "# # Starting Condition\n", - "# x0 = np.zeros(N)\n", - "# x0[0] = 0\n", - "# x0[1] = -0.5\n", - "# x0[2] = np.radians(-0)\n", - "# _,psi,cte = calc_err(x0,track)\n", - "# x0[3]=psi\n", - "# x0[4]=cte\n", - "\n", - "# x_sim[:,0]=x0\n", - " \n", - "# #starting guess\n", - "# u_bar = np.zeros((M,T))\n", - "# u_bar[0,:]=0.5*(MAX_SPEED+MIN_SPEED)\n", - "# u_bar[1,:]=0.01\n", - "\n", - "# for sim_time in range(sim_duration-1):\n", - " \n", - "# iter_start=time.time()\n", - " \n", - "# # Prediction\n", - "# x_bar=np.zeros((N,T+1))\n", - "# x_bar[:,0]=x_sim[:,sim_time]\n", - "\n", - "# for t in range (1,T+1):\n", - "# xt=x_bar[:,t-1].reshape(5,1)\n", - "# ut=u_bar[:,t-1].reshape(2,1)\n", - "\n", - "# A,B,C=get_linear_model(xt,ut)\n", - "\n", - "# xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", - "\n", - "# _,psi,cte = calc_err(xt_plus_one,track)\n", - "# xt_plus_one[3]=psi\n", - "# xt_plus_one[4]=cte\n", - "\n", - "# x_bar[:,t]= xt_plus_one\n", - "\n", - "\n", - "# #CVXPY Linear MPC problem statement\n", - "# cost = 0\n", - "# constr = []\n", - "\n", - "# for t in range(T):\n", - "\n", - "# # Tracking\n", - "# if t > 0:\n", - "# idx,_,_ = calc_err(x_bar[:,t],track)\n", - "# delta_x = track[:,idx]-x[0:3,t]\n", - "# cost+= cp.quad_form(delta_x,10*np.eye(3))\n", - " \n", - "# # Tracking last time step\n", - "# if t == T:\n", - "# idx,_,_ = calc_err(x_bar[:,t],track)\n", - "# delta_x = track[:,idx]-x[0:3,t]\n", - "# cost+= cp.quad_form(delta_x,100*np.eye(3))\n", - "\n", - "# # Actuation rate of change\n", - "# if t < (T - 1):\n", - "# cost += cp.quad_form(u[:, t + 1] - u[:, t], 25*np.eye(M))\n", - " \n", - "# # Actuation effort\n", - "# cost += cp.quad_form( u[:, t],1*np.eye(M))\n", - " \n", - "# # Constrains\n", - "# A,B,C=get_linear_model(x_bar[:,t],u_bar[:,t])\n", - "# constr += [x[:,t+1] == A*x[:,t] + B*u[:,t] + C.flatten()]\n", - "\n", - "# # sums problem objectives and concatenates constraints.\n", - "# constr += [x[:,0] == x_sim[:,sim_time]] # starting condition\n", - "# constr += [u[0, :] <= MAX_SPEED]\n", - "# constr += [u[0, :] >= MIN_SPEED]\n", - "# constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED]\n", - " \n", - "# # Solve\n", - "# prob = cp.Problem(cp.Minimize(cost), constr)\n", - "# solution = prob.solve(solver=cp.ECOS, verbose=False)\n", - " \n", - "# #retrieved optimized U and assign to u_bar to linearize in next step\n", - "# u_bar=np.vstack((np.array(u.value[0, :]).flatten(),\n", - "# (np.array(u.value[1, :]).flatten())))\n", - " \n", - "# u_sim[:,sim_time] = u_bar[:,0]\n", - " \n", - "# # Measure elpased time to get results from cvxpy\n", - "# opt_time.append(time.time()-iter_start)\n", - " \n", - "# # move simulation to t+1\n", - "# tspan = [0,dt]\n", - "# x_sim[:,sim_time+1] = odeint(kinematics_model,\n", - "# x_sim[:,sim_time],\n", - "# tspan,\n", - "# args=(u_bar[:,0],))[1]\n", - " \n", - "# print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n", - "# np.max(opt_time),\n", - "# np.min(opt_time))) " - ] - }, - { - "cell_type": "code", - "execution_count": 137, + "execution_count": 23, "metadata": {}, "outputs": [ { @@ -1164,16 +1057,16 @@ "name": "stdout", "output_type": "stream", "text": [ - "CVXPY Optimization Time: Avrg: 0.1679s Max: 0.2200s Min: 0.1538s\n" + "CVXPY Optimization Time: Avrg: 0.1416s Max: 0.2571s Min: 0.1279s\n" ] } ], "source": [ "\n", - "track = compute_path_from_wp([0,3,4,6],\n", - " [0,0,2,1])\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 =50\n", + "sim_duration =100 \n", "opt_time=[]\n", "\n", "x_sim = np.zeros((N,sim_duration))\n", @@ -1229,8 +1122,16 @@ " for t in range(T):\n", "\n", " # Tracking\n", - " cost += 50*cp.sum_squares( x[3, t]) # psi\n", - " cost += 10*cp.sum_squares( x[4, t]) # cte\n", + " if t > 0:\n", + " idx,_,_ = calc_err(x_bar[:,t],track)\n", + " delta_x = track[:,idx]-x[0:3,t]\n", + " cost+= cp.quad_form(delta_x,10*np.eye(3))\n", + " \n", + " # Tracking last time step\n", + " if t == T:\n", + " idx,_,_ = calc_err(x_bar[:,t],track)\n", + " delta_x = track[:,idx]-x[0:3,t]\n", + " cost+= cp.quad_form(delta_x,100*np.eye(3))\n", "\n", " # Actuation rate of change\n", " if t < (T - 1):\n", @@ -1267,21 +1168,21 @@ " x_sim[:,sim_time+1] = odeint(kinematics_model,\n", " x_sim[:,sim_time],\n", " tspan,\n", - " args=(u_bar[:,1],))[1]\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))) " + " np.min(opt_time))) " ] }, { "cell_type": "code", - "execution_count": 138, + "execution_count": 24, "metadata": {}, "outputs": [ { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ "
" ] diff --git a/notebook/MPC_cte_cvxpy.ipynb b/notebook/MPC_cte_cvxpy.ipynb new file mode 100644 index 0000000..7d2b8ef --- /dev/null +++ b/notebook/MPC_cte_cvxpy.ipynb @@ -0,0 +1,1084 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 69, + "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 track w.r.t robot frame, cte is a function of the track and x\n", + "\n", + "The inputs of the model are:\n", + "\n", + "* $v$ linear velocity of the robot\n", + "* $w$ angular velocity of the robot\n", + "\n", + "These are the differential equations f(x,u) of the model:\n", + "\n", + "* $\\dot{x} = v\\cos{\\theta}$ \n", + "* $\\dot{y} = v\\sin{\\theta}$\n", + "* $\\dot{\\theta} = w$\n", + "* $\\dot{\\psi} = -w$\n", + "* $\\dot{cte} = v\\sin{\\psi}$\n", + "\n", + "The **Continuous** State Space Model is\n", + "\n", + "$ {\\dot{x}} = Ax + Bu $\n", + "\n", + "with:\n", + "\n", + "$ A =\n", + "\\quad\n", + "\\begin{bmatrix}\n", + "\\frac{\\partial f(x,u)}{\\partial x} & \\frac{\\partial f(x,u)}{\\partial y} & \\frac{\\partial f(x,u)}{\\partial \\theta} & \\frac{\\partial f(x,u)}{\\partial \\psi} & \\frac{\\partial f(x,u)}{\\partial cte} \\\\\n", + "\\end{bmatrix}\n", + "\\quad\n", + "=\n", + "\\quad\n", + "\\begin{bmatrix}\n", + "0 & 0 & -vsin(\\theta) & 0 & 0 \\\\\n", + "0 & 0 & vcos(\\theta) & 0 & 0 \\\\\n", + "0 & 0 & 0 & 0 & 0 \\\\\n", + "0 & 0 & 0 & 0 & 0 \\\\\n", + "0 & 0 & 0 & vcos(\\psi) & 0 \n", + "\\end{bmatrix}\n", + "\\quad $\n", + "\n", + "\n", + "$ B = \\quad\n", + "\\begin{bmatrix}\n", + "\\frac{\\partial f(x,u)}{\\partial v} & \\frac{\\partial f(x,u)}{\\partial w} \\\\\n", + "\\end{bmatrix}\n", + "\\quad\n", + "=\n", + "\\quad\n", + "\\begin{bmatrix}\n", + "\\cos{\\theta_t} & 0 \\\\\n", + "\\sin{\\theta_t} & 0 \\\\\n", + "0 & 1 \\\\\n", + "0 & -1 \\\\\n", + "\\sin{(\\psi_t)} & 0 \n", + "\\end{bmatrix}\n", + "\\quad $\n", + "\n", + "discretize with forward Euler Integration for time step dt:\n", + "\n", + "* ${x_{t+1}} = x_{t} + v_t\\cos{\\theta}*dt$\n", + "* ${y_{t+1}} = y_{t} + v_t\\sin{\\theta}*dt$\n", + "* ${\\theta_{t+1}} = \\theta_{t} + w_t*dt$\n", + "* ${\\psi_{t+1}} = \\psi_{t} - w_t*dt$\n", + "* ${cte_{t+1}} = cte_{t} + v_t\\sin{\\psi}*dt$\n", + "\n", + "The **Discrete** State Space Model is then:\n", + "\n", + "${x_{t+1}} = Ax_t + Bu_t $\n", + "\n", + "with:\n", + "\n", + "$\n", + "A = \\quad\n", + "\\begin{bmatrix}\n", + "1 & 0 & -v\\sin{\\theta}dt & 0 & 0 \\\\\n", + "0 & 1 & v\\cos{\\theta}dt & 0 & 0 \\\\\n", + "0 & 0 & 1 & 0 & 0 \\\\\n", + "0 & 0 & 0 & 1 & 0 \\\\\n", + "0 & 0 & 0 & vcos{(\\psi)}dt & 1 \n", + "\\end{bmatrix}\n", + "\\quad\n", + "$\n", + "\n", + "$\n", + "B = \\quad\n", + "\\begin{bmatrix}\n", + "\\cos{\\theta_t}dt & 0 \\\\\n", + "\\sin{\\theta_t}dt & 0 \\\\\n", + "0 & dt \\\\\n", + "0 & -dt \\\\\n", + "\\sin{\\psi_t}dt & 0 \n", + "\\end{bmatrix}\n", + "\\quad\n", + "$\n", + "\n", + "This State Space Model is **non-linear** (A,B are time changing), to linearize it the **Taylor's series expansion** is used around $\\bar{x}$ and $\\bar{u}$:\n", + "\n", + "$ \\dot{x} = f(x,u) \\approx f(\\bar{x},\\bar{u}) + A(x-\\bar{x}) + B(u-\\bar{u})$\n", + "\n", + "So:\n", + "\n", + "$ x_{t+1} = x_t + (f(\\bar{x},\\bar{u}) + A(x_t-\\bar{x}) + B(u_t-\\bar{u}) )dt $\n", + "\n", + "$ x_{t+1} = (I+dtA)x_t + dtBu_t +dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\bar{u}))$\n", + "\n", + "The Discrete linearized kinematics model is\n", + "\n", + "$ x_{t+1} = A'x_t + B' u_t + C' $\n", + "\n", + "with:\n", + "\n", + "$ A' = I+dtA $\n", + "\n", + "$ B' = dtB $\n", + "\n", + "$ C' = dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\bar{u}) $" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "-----------------\n", + "[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": 70, + "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" + ] + }, + { + "cell_type": "code", + "execution_count": 71, + "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": 72, + "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": 73, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "CPU times: user 7 ms, sys: 0 ns, total: 7 ms\n", + "Wall time: 5.8 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": 74, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#plot trajectory\n", + "plt.subplot(2, 2, 1)\n", + "plt.plot(x_bar[0,:],x_bar[1,:])\n", + "plt.plot(np.linspace(0,10,T+1),np.zeros(T+1),\"b-\")\n", + "plt.axis('equal')\n", + "plt.ylabel('y')\n", + "plt.xlabel('x')\n", + "\n", + "plt.subplot(2, 2, 2)\n", + "plt.plot(np.degrees(x_bar[2,:]))\n", + "plt.ylabel('theta(t) [deg]')\n", + "#plt.xlabel('time')\n", + "\n", + "plt.subplot(2, 2, 3)\n", + "plt.plot(np.degrees(x_bar[3,:]))\n", + "plt.ylabel('psi(t) [deg]')\n", + "#plt.xlabel('time')\n", + "\n", + "plt.subplot(2, 2, 4)\n", + "plt.plot(x_bar[4,:])\n", + "plt.ylabel('cte(t)')\n", + "\n", + "plt.tight_layout()\n", + "plt.show()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "the results seems valid:\n", + "* the cte is correct\n", + "* theta error is correct" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Motion Prediction: using the state space model" + ] + }, + { + "cell_type": "code", + "execution_count": 75, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "CPU times: user 3.28 ms, sys: 461 µs, total: 3.74 ms\n", + "Wall time: 2.68 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": 76, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#plot trajectory\n", + "plt.subplot(2, 2, 1)\n", + "plt.plot(x_bar[0,:],x_bar[1,:])\n", + "plt.plot(np.linspace(0,10,T+1),np.zeros(T+1),\"b-\")\n", + "plt.axis('equal')\n", + "plt.ylabel('y')\n", + "plt.xlabel('x')\n", + "\n", + "plt.subplot(2, 2, 2)\n", + "plt.plot(x_bar[2,:])\n", + "plt.ylabel('theta(t)')\n", + "#plt.xlabel('time')\n", + "\n", + "plt.subplot(2, 2, 3)\n", + "plt.plot(x_bar[3,:])\n", + "plt.ylabel('psi(t)')\n", + "#plt.xlabel('time')\n", + "\n", + "plt.subplot(2, 2, 4)\n", + "plt.plot(x_bar[4,:])\n", + "plt.ylabel('cte(t)')\n", + "\n", + "plt.tight_layout()\n", + "plt.show()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The results are the same as expected" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "------------------\n", + "\n", + "the kinematics model predictits psi and cte for constant heading references. So, for non-constant paths appropriate functions have to be developed.\n", + "\n", + "-----------------" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## PRELIMINARIES" + ] + }, + { + "cell_type": "code", + "execution_count": 77, + "metadata": {}, + "outputs": [], + "source": [ + "def compute_path_from_wp(start_xp, start_yp, step = 0.1):\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", + " return np.vstack((final_xp,final_yp))\n", + "\n", + "def get_nn_idx(state,path):\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", + " return target_idx\n", + "\n", + "def road_curve(state,track):\n", + " \n", + " #given vehicle pos find lookahead waypoints\n", + " nn_idx=get_nn_idx(state,track)\n", + " LOOKAHED=6\n", + " lk_wp=track[:,nn_idx:nn_idx+LOOKAHED]\n", + "\n", + " #trasform lookahead waypoints to vehicle ref frame\n", + " dx = lk_wp[0,:] - state[0]\n", + " dy = lk_wp[1,:] - state[1]\n", + "\n", + " wp_vehicle_frame = np.vstack(( dx * np.cos(-state[2]) - dy * np.sin(-state[2]),\n", + " dy * np.cos(-state[2]) + dx * np.sin(-state[2]) ))\n", + "\n", + " #fit poly\n", + " return np.polyfit(wp_vehicle_frame[0,:], wp_vehicle_frame[1,:], 3, rcond=None, full=False, w=None, cov=False)\n", + "\n", + "def f(x,coeff):\n", + " return round(coeff[0]*x**3 + coeff[1]*x**2 + coeff[2]*x**1 + coeff[3]*x**0,6)\n", + "\n", + "def df(x,coeff):\n", + " return round(3*coeff[0]*x**2 + 2*coeff[1]*x**1 + coeff[2]*x**0,6)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "test it" + ] + }, + { + "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= MIN_SPEED]\n", + "constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED]\n", + "\n", + "prob = cp.Problem(cp.Minimize(cost), constr)\n", + "solution = prob.solve(solver=cp.OSQP, verbose=True)" + ] + }, + { + "cell_type": "code", + "execution_count": 108, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "x_mpc=np.array(x.value[0, :]).flatten()\n", + "y_mpc=np.array(x.value[1, :]).flatten()\n", + "theta_mpc=np.array(x.value[2, :]).flatten()\n", + "psi_mpc=np.array(x.value[3, :]).flatten()\n", + "cte_mpc=np.array(x.value[4, :]).flatten()\n", + "v_mpc=np.array(u.value[0, :]).flatten()\n", + "w_mpc=np.array(u.value[1, :]).flatten()\n", + "\n", + "#simulate robot state trajectory for optimized U\n", + "x_traj=predict(x0, np.vstack((v_mpc,w_mpc)))\n", + "\n", + "#plt.figure(figsize=(15,10))\n", + "#plot trajectory\n", + "plt.subplot(2, 2, 1)\n", + "plt.plot(track[0,:],track[1,:],\"b+\")\n", + "plt.plot(x_traj[0,:],x_traj[1,:])\n", + "plt.axis(\"equal\")\n", + "plt.ylabel('y')\n", + "plt.xlabel('x')\n", + "\n", + "#plot v(t)\n", + "plt.subplot(2, 2, 2)\n", + "plt.plot(v_mpc)\n", + "plt.ylabel('v(t)')\n", + "#plt.xlabel('time')\n", + "\n", + "#plot w(t)\n", + "# plt.subplot(2, 2, 3)\n", + "# plt.plot(w_mpc)\n", + "# plt.ylabel('w(t)')\n", + "#plt.xlabel('time')\n", + "\n", + "plt.subplot(2, 2, 3)\n", + "plt.plot(psi_mpc)\n", + "plt.ylabel('psi(t)')\n", + "\n", + "plt.subplot(2, 2, 4)\n", + "plt.plot(cte_mpc)\n", + "plt.ylabel('cte(t)')\n", + "\n", + "plt.tight_layout()\n", + "plt.show()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "full track demo" + ] + }, + { + "cell_type": "code", + "execution_count": 97, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "CVXPY Optimization Time: Avrg: 0.1852s Max: 0.2253s Min: 0.1567s\n" + ] + } + ], + "source": [ + "track = compute_path_from_wp([0,3,4,6],\n", + " [0,0,2,1])\n", + "\n", + "sim_duration = 20\n", + "opt_time=[]\n", + "\n", + "x_sim = np.zeros((N,sim_duration))\n", + "u_sim = np.zeros((M,sim_duration-1))\n", + "\n", + "MAX_SPEED = 1.25\n", + "MIN_SPEED = 0.75\n", + "MAX_STEER_SPEED = 1.57/2\n", + "\n", + "# Starting Condition\n", + "x0 = np.zeros(N)\n", + "x0[0] = 0\n", + "x0[1] = -0.25\n", + "x0[2] = np.radians(-0)\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.00\n", + "\n", + "for sim_time in range(sim_duration-1):\n", + " \n", + " iter_start=time.time()\n", + " \n", + " K=road_curve(x_sim[:,sim_time],track)\n", + " \n", + " # dynamics starting state\n", + " x_bar=np.zeros((N,T+1))\n", + " x_bar[3,0]=x_bar[2,0]-np.arctan2(df(x_bar[0,0],K),x_bar[0,0])\n", + " x_bar[4,0]=f(x_bar[0,0],K)-x_bar[1,0]\n", + " \n", + " #x_bar[:,0]=x_sim[:,sim_time]\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", + " xt_plus_one[3]=xt_plus_one[2]-np.arctan2(df(xt_plus_one[0],K),xt_plus_one[0])\n", + " xt_plus_one[4]=f(xt_plus_one[0],K)-xt_plus_one[1]\n", + " \n", + " x_bar[:,t]= xt_plus_one\n", + " \n", + " #CVXPY Linear MPC problem statement\n", + " cost = 0\n", + " constr = []\n", + " x = cp.Variable((N, T+1))\n", + " u = cp.Variable((M, T))\n", + " \n", + " for t in range(T):\n", + "\n", + " # Tracking\n", + " cost += 10*cp.sum_squares( x[3, t]) # psi\n", + " cost += 50*cp.sum_squares( x[4, t]) # cte\n", + "\n", + " # Actuation rate of change\n", + " if t < (T - 1):\n", + " cost += cp.quad_form(u[:, t + 1] - u[:, t], 10*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_bar[:,0]] #<--watch out the start condition\n", + " constr += [u[0, :] <= MAX_SPEED]\n", + " constr += [u[0, :] >= MIN_SPEED]\n", + " constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED]\n", + " \n", + " # Solve\n", + " prob = cp.Problem(cp.Minimize(cost), constr)\n", + " solution = prob.solve(solver=cp.OSQP, verbose=False)\n", + " \n", + " #retrieved optimized U and assign to u_bar to linearize in next step\n", + " u_bar=np.vstack((np.array(u.value[0, :]).flatten(),\n", + " (np.array(u.value[1, :]).flatten())))\n", + " \n", + " u_sim[:,sim_time] = u_bar[:,0]\n", + " \n", + " # Measure elpased time to get results from cvxpy\n", + " opt_time.append(time.time()-iter_start)\n", + " \n", + " # move simulation to t+1\n", + " tspan = [0,dt]\n", + " x_sim[:,sim_time+1] = odeint(kinematics_model,\n", + " x_sim[:,sim_time],\n", + " tspan,\n", + " args=(u_bar[:,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": 98, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#plot trajectory\n", + "grid = plt.GridSpec(2, 3)\n", + "\n", + "plt.figure(figsize=(15,10))\n", + "\n", + "plt.subplot(grid[0:2, 0:2])\n", + "plt.plot(track[0,:],track[1,:],\"b+\")\n", + "plt.plot(x_sim[0,:],x_sim[1,:])\n", + "plt.axis(\"equal\")\n", + "plt.ylabel('y')\n", + "plt.xlabel('x')\n", + "\n", + "plt.subplot(grid[0, 2])\n", + "plt.plot(u_sim[0,:])\n", + "plt.ylabel('v(t) [m/s]')\n", + "\n", + "plt.subplot(grid[1, 2])\n", + "plt.plot(np.degrees(u_sim[1,:]))\n", + "plt.ylabel('w(t) [deg/s]')\n", + "\n", + "plt.tight_layout()\n", + "plt.show()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.6.9" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/notebook/MPC_scipy.ipynb b/notebook/MPC_cte_scipy.ipynb similarity index 100% rename from notebook/MPC_scipy.ipynb rename to notebook/MPC_cte_scipy.ipynb diff --git a/notebook/MPC_cvxpy_v2.ipynb b/notebook/MPC_cvxpy_v2.ipynb deleted file mode 100644 index 818b4e0..0000000 --- a/notebook/MPC_cvxpy_v2.ipynb +++ /dev/null @@ -1,1083 +0,0 @@ -{ - "cells": [ - { - "cell_type": "code", - "execution_count": 77, - "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 track w.r.t robot frame, cte is a function of the track and x\n", - "\n", - "The inputs of the model are:\n", - "\n", - "* $v$ linear velocity of the robot\n", - "* $w$ angular velocity of the robot\n", - "\n", - "These are the differential equations f(x,u) of the model:\n", - "\n", - "* $\\dot{x} = v\\cos{\\theta}$ \n", - "* $\\dot{y} = v\\sin{\\theta}$\n", - "* $\\dot{\\theta} = w$\n", - "* $\\dot{\\psi} = -w$\n", - "* $\\dot{cte} = v\\sin{\\psi}$\n", - "\n", - "The **Continuous** State Space Model is\n", - "\n", - "$ {\\dot{x}} = Ax + Bu $\n", - "\n", - "with:\n", - "\n", - "$ A =\n", - "\\quad\n", - "\\begin{bmatrix}\n", - "\\frac{\\partial f(x,u)}{\\partial x} & \\frac{\\partial f(x,u)}{\\partial y} & \\frac{\\partial f(x,u)}{\\partial \\theta} & \\frac{\\partial f(x,u)}{\\partial \\psi} & \\frac{\\partial f(x,u)}{\\partial cte} \\\\\n", - "\\end{bmatrix}\n", - "\\quad\n", - "=\n", - "\\quad\n", - "\\begin{bmatrix}\n", - "0 & 0 & -vsin(\\theta) & 0 & 0 \\\\\n", - "0 & 0 & vcos(\\theta) & 0 & 0 \\\\\n", - "0 & 0 & 0 & 0 & 0 \\\\\n", - "0 & 0 & 0 & 0 & 0 \\\\\n", - "0 & 0 & 0 & vcos(\\psi) & 0 \n", - "\\end{bmatrix}\n", - "\\quad $\n", - "\n", - "\n", - "$ B = \\quad\n", - "\\begin{bmatrix}\n", - "\\frac{\\partial f(x,u)}{\\partial v} & \\frac{\\partial f(x,u)}{\\partial w} \\\\\n", - "\\end{bmatrix}\n", - "\\quad\n", - "=\n", - "\\quad\n", - "\\begin{bmatrix}\n", - "\\cos{\\theta_t} & 0 \\\\\n", - "\\sin{\\theta_t} & 0 \\\\\n", - "0 & 1 \\\\\n", - "0 & -1 \\\\\n", - "\\sin{(\\psi_t)} & 0 \n", - "\\end{bmatrix}\n", - "\\quad $\n", - "\n", - "discretize with forward Euler Integration for time step dt:\n", - "\n", - "* ${x_{t+1}} = x_{t} + v_t\\cos{\\theta}*dt$\n", - "* ${y_{t+1}} = y_{t} + v_t\\sin{\\theta}*dt$\n", - "* ${\\theta_{t+1}} = \\theta_{t} + w_t*dt$\n", - "* ${\\psi_{t+1}} = \\psi_{t} - w_t*dt$\n", - "* ${cte_{t+1}} = cte_{t} + v_t\\sin{\\psi}*dt$\n", - "\n", - "The **Discrete** State Space Model is then:\n", - "\n", - "${x_{t+1}} = Ax_t + Bu_t $\n", - "\n", - "with:\n", - "\n", - "$\n", - "A = \\quad\n", - "\\begin{bmatrix}\n", - "1 & 0 & -v\\sin{\\theta}dt & 0 & 0 \\\\\n", - "0 & 1 & v\\cos{\\theta}dt & 0 & 0 \\\\\n", - "0 & 0 & 1 & 0 & 0 \\\\\n", - "0 & 0 & 0 & 1 & 0 \\\\\n", - "0 & 0 & 0 & vcos{(\\psi)}dt & 1 \n", - "\\end{bmatrix}\n", - "\\quad\n", - "$\n", - "\n", - "$\n", - "B = \\quad\n", - "\\begin{bmatrix}\n", - "\\cos{\\theta_t}dt & 0 \\\\\n", - "\\sin{\\theta_t}dt & 0 \\\\\n", - "0 & dt \\\\\n", - "0 & -dt \\\\\n", - "\\sin{\\psi_t}dt & 0 \n", - "\\end{bmatrix}\n", - "\\quad\n", - "$\n", - "\n", - "This State Space Model is **non-linear** (A,B are time changing), to linearize it the **Taylor's series expansion** is used around $\\bar{x}$ and $\\bar{u}$:\n", - "\n", - "$ \\dot{x} = f(x,u) \\approx f(\\bar{x},\\bar{u}) + A(x-\\bar{x}) + B(u-\\bar{u})$\n", - "\n", - "So:\n", - "\n", - "$ x_{t+1} = x_t + (f(\\bar{x},\\bar{u}) + A(x_t-\\bar{x}) + B(u_t-\\bar{u}) )dt $\n", - "\n", - "$ x_{t+1} = (I+dtA)x_t + dtBu_t +dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\bar{u}))$\n", - "\n", - "The Discrete linearized kinematics model is\n", - "\n", - "$ x_{t+1} = A'x_t + B' u_t + C' $\n", - "\n", - "with:\n", - "\n", - "$ A' = I+dtA $\n", - "\n", - "$ B' = dtB $\n", - "\n", - "$ C' = dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\bar{u}) $" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "-----------------\n", - "[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": 78, - "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" - ] - }, - { - "cell_type": "code", - "execution_count": 79, - "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": 80, - "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": 81, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "CPU times: user 7.22 ms, sys: 0 ns, total: 7.22 ms\n", - "Wall time: 5.83 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": 82, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "#plot trajectory\n", - "plt.subplot(2, 2, 1)\n", - "plt.plot(x_bar[0,:],x_bar[1,:])\n", - "plt.plot(np.linspace(0,10,T+1),np.zeros(T+1),\"b-\")\n", - "plt.axis('equal')\n", - "plt.ylabel('y')\n", - "plt.xlabel('x')\n", - "\n", - "plt.subplot(2, 2, 2)\n", - "plt.plot(np.degrees(x_bar[2,:]))\n", - "plt.ylabel('theta(t) [deg]')\n", - "#plt.xlabel('time')\n", - "\n", - "plt.subplot(2, 2, 3)\n", - "plt.plot(np.degrees(x_bar[3,:]))\n", - "plt.ylabel('psi(t) [deg]')\n", - "#plt.xlabel('time')\n", - "\n", - "plt.subplot(2, 2, 4)\n", - "plt.plot(x_bar[4,:])\n", - "plt.ylabel('cte(t)')\n", - "\n", - "plt.tight_layout()\n", - "plt.show()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "the results seems valid:\n", - "* the cte is correct\n", - "* theta error is correct" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Motion Prediction: using the state space model" - ] - }, - { - "cell_type": "code", - "execution_count": 83, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "CPU times: user 2.58 ms, sys: 0 ns, total: 2.58 ms\n", - "Wall time: 1.89 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": 84, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAAAaIAAAEYCAYAAAAeWvJ8AAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAADh0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uMy4xLjMsIGh0dHA6Ly9tYXRwbG90bGliLm9yZy+AADFEAAAgAElEQVR4nOzdeVxU5f7A8c9zQEVEdvct13LLDdMsxQXLbCNLzdJy6Za5kLaZlomZaxqJW5vh1i1bjPZF9LqU18IUzfSqqKUmhgIiiChwnt8f8xMlQBBhzszwfb9evS4zc+acr8/l8J15lu+jtNYaIYQQwiKG1QEIIYQo3yQRCSGEsJQkIiGEEJaSRCSEEMJSkoiEEEJYShKREEIIS7lbHcC1On78eIHPBwYGcurUKTtH45ikLS4prC1q165tQTTOQe6xoklbXFKSe8zpE5EQwiYuLo6oqChM06RXr16EhobmeT0rK4uFCxdy6NAhqlatyrhx46hevbpF0QpxiXTNCeECTNNk6dKlTJo0iYiICH766SeOHTuW55j169dTpUoVFixYwJ133sn7779vUbRC5CWJSAgXEB8fT82aNalRowbu7u506dKF2NjYPMds27aN7t27A9C5c2d2795NSQqr6Mxz5Mx9kfM7Y4s+WIhikK45IVxAcnIyAQEBuY8DAgI4cOBAoce4ubnh6elJWloa3t7eeY6LiYkhJiYGgFmzZhEYGJjn9eyEY5xOP8Pp8KfwvGsAXoOfRFWqVBb/LKfh7u6er53Kq5K0hSQiIUQeISEhhISE5D7ON/BcwQM9aS6Vv/mIjK8+IuPX/2KMGI9q0MTOkToOmaxwSUkmK0jXnBAuwN/fn6SkpNzHSUlJ+Pv7F3pMTk4OGRkZVK1atUTXUxUr4f3YeIzxU+FcBubM5zC//gidk1Pyf4QotyQRCeECGjduTEJCAomJiWRnZ7NlyxaCgoLyHNOhQwc2bNgAwNatW2nZsiVKqWu6rmrRDiN8Aap9F3T0KszXJqITC57uLURhJBEJ4QLc3NwYPnw406dPZ/z48dx8883Uq1eP1atXs23bNgB69uxJeno6Y8eO5auvvuLhhx8ulWurKl4Yjz+HeuwZSDiK+co4zE3flWgihCiflLPvRySL7YombXGJLGi9eldzj+nkU5jL5sPendA6COPRsSgfP3uEaSm5xy6RMSIhhKWUfyDGuKmoBx+H/+3CDB+L3v5fq8MSDk4SkRCiVCnDwOh1F8bkCPCvhrlkJmbUfPS5DKtDEw5KEpEQokyoWvUwJs5B3TkA/d//YE4NQ+/fbXVYwgFJIhJClBnlXgEjdDDGhFng5oY590XMT5ahs7KsDk04EElEQogypxrfgDH5DVTX29Hfr8Gc8Qz62GGrwxIOQhKREMIulEdljCGjMMZOhjOnMac/g/n9GrQpi2DLO0lEQgi7Ujd2xAhfAK2D0J8sw5z3EvrU31aHJSwkiUgIYXeqqg/GkxNRQ5+CI4cwp4Zhblkni2DLKUlEQghLKKUwbumFMSUS6jVER83HfHMWOu2M1aEJO5NEJISwlAqsgfHsdNQDQ2FnLGb4GPRv26wOS9iRJCIhhOWU4YZxez+MF+dBVR/MyFcwVy1Gn8+0OjRhBw6zH9GpU6dYtGgRp0+fRilFSEgIffv2tTosIYQdqXoNMV6ch45+H702Gr13J8bw8ajGN1gdmihDDpOI3NzcGDJkCI0aNeLcuXO88MIL3HjjjdStW9fq0IRwaOnp6URERHDy5EmqVavG+PHj8fLyynPMH3/8wTvvvMO5c+cwDIN+/frRpUsXiyK+MlWhIqr/MPSNHTHfi8Cc/QLqzv6oOwei3B3mT5YoRQ7TNefn50ejRo0AqFy5MnXq1CE5OdniqIRwfNHR0bRu3ZrIyEhat25NdHR0vmMqVqzImDFjeP3115k0aRLLli3j7NmzFkRbfOr6VhhTIlGdu6O/Wo0563l0wjGrwxJlwCE/XiQmJnL48GGaNMm/9XBMTAwxMTEAzJo1q9C90WUP+UukLS5xxbaIjY0lPDwcgODgYMLDwxk8eHCeYy4vwe/v74+Pjw9nzpyhSpUq9gz1qinPKqjh49BtbsJctQhz2jjUA0NR3fuiDIf5HC2ukcMloszMTObNm8fQoUPx9PTM93pISAghISG5jwvbA0T2B7lE2uISV9yPKDU1FT8/254/vr6+pKamXvH4+Ph4srOzqVGjRoGvO+SHvdvvIadjF84snsmFD96mwp4deI99CbeAava5fhFc8QNOSZWkLRwqEWVnZzNv3jy6du1Kp06drA5HCIcxbdo0Tp8+ne/5Bx98MM9jpdQVt/9OSUlhwYIFjB49GqOQbxSO/GFPP/ECatP3XPhoKafCHkYNfhKjY1e7xlAQ+bB3SUk+7DlMItJa8+abb1KnTh3uuusuq8MRwqFMnjy50Nd8fHxISUnBz8+PlJQUvL29CzwuIyODWbNmMWjQIJo1a1ZWoZYppRQquA/6hhsxl76Ofvs1zLhfUA89gariVfQJhENymE7Wffv2sWnTJnbv3s1zzz3Hc889x/bt260OSwiHFxQUxMaNGwHYuHEjHTt2zHdMdnY2c+fOpVu3bnTu3NneIZY6VaM2xoTZqHsfQv/6o22vo707rQ5LlJDDfCO64YYb+Oijj6wOQwinExoaSkREBOvXr8+dvg1w8OBB1q5dy8iRI9myZQt79+4lLS2NDRs2ADB69Giuu+466wK/RsrNDXXXg+hWHTCXvo75+mRUyD2o+4agKlayOjxxFZR28iqDx48fL/B56bO9RNriElecrFDWnOEe0+fPo9csR6//CmrVw3jsaVT9xna7viO1hdWceoxICFd05swZNm3axPbt2/nzzz/JyMjA09OTBg0a0LZtW7p3717omI4oPlWpEmrQ47ZFsMvmY854FnX3INQd96MMN6vDE0WQRCREGXn//ff58ccfadeuHT179qROnTpUrlyZc+fO8ddff7Fnzx4mTJjArbfeysMPP2x1uC5BtWyHEb4AvWoJOnoV+rdtthJB1WtZHZq4AklEQpSRgIAAIiMjqVChQr7XGjZsyK233sqFCxdYv369BdG5LlWlKjz+HLTthH7/TcxXnkINGIHqetsVp7YL6zjMrDkhXE2fPn1yk1BBa4DANqW6T58+9gyrXFBKYXQKxgiPhEbXo1cuwlz4KvpMitWhiQJIIhLCDp566qkCn784w02UDeVfDWPcVNTAx2DvTswpY9E7tlodlvgHl+ya0//bxQVvb/TFUieGG1SqBJU8oFJlqOqNqlDR2iBFuVLQ5NSMjIxCqxuI0qMMAxVyD7pFW9s078UzULeEoAY+hqqcv4yYsD+XTETmG1NIycm58kGVPaGqL/gHoqrVhMAaqBq1oXYDqF4L5SYzbcS1e/LJJwG4cOFC7s8Xpaenc8stt1gRVrmkatfHmPga+ssP0d9+iv7fLttEhmYtrQ6t3HPJRGQ8/So+Pt6Xij/m5MD5TNtuj+fPQdoZSEuF1BR08kl03M+QlkruZ1b3ClCnAaphM2h0Parx9VCtlgx0iqs2duxYtNbMnDmTsWPH5nnN19dX1i/ZmXKvgLpvCLp1kG2vo7mTULf3Q93zEKqASSXCPmRB6//T5zPhxF/ov/6Av/5EHzkEhw/YEheAXyCqeRto3gbVsh2qqk8pRG8fstjuEqsWtJ4/f55KlZxztb8zLGgtCZ15Dv3RUvTmH6BuQ9si2DoNSnQuZ2+L0iQLWq+BquQBDRqjGlxaja3NHDh+FB2/F/2/nbZvTlvWoZUBTZuj2nVGteuCcpBS9MKxfPPNN/Tu3ZsKFSoUmoSysrJYu3Ytffv2tXN0QnlURj0yBt2mE+bySMxXx9vKA4XcK3sd2ZkkoitQhhvUvQ5V9zrofoctMf15CL3rF/SOrejVS9Grl0KzVqjO3VEdbkF5OvZGY8J+Tp8+TVhYGO3ataNFixbUrl0bDw8PMjMzOX78OHv27GHHjh0EBwdbHWq5ptp0xJi6EHPFQvTHUehd2zCGPYUKqG51aOWGdM1dA514HP3LZvTWDfD3X1CxIuqmYNvukQ3sV+eqKNJtcIm9u+bOnDnDhg0biIuL48iRI5w9exYvLy/q169Pu3btCA4OpmrVqmVy7dLiql1z/6S1Rv8Ug/7wXTAUatATtg+YxRgbdrW2uBYlucckEZUCrTX8cQC9+Qf0zxvhwnlodD3G7fdB206W17qSm+QSVyx6mp6eTkREBCdPnsytvu3lVfDePBkZGTz99NN07NiRESNGFOv8jnCP2ZM+eQLzvTcgfg906IIxeBTK68r1AF21LUqiJPeYdISWAqUUqmEzjEfGYLwWhXrwX5CWirlkFubLYzA3/4DOzrY6TOGioqOjad26NZGRkbRu3Zro6OhCj129ejXNmze3Y3TOR1WrifHcdNT9j0LcL5jhY9G//Wp1WC5NxohKmfL0QvW6G92jL/rX/6K/+wS9YiH6209sU0Rv6mr5NyRhfxkZGXz88cfs2bOHtLS0PAtclyxZck3njo2NJTw8HIDg4GDCw8MZPHhwvuMOHTpEamoqbdu25eDBg9d0TVenDDdUn/vRLdvbFsFGTkV1vwP1wDDbxCZRquQbURlRhhtGx1sxXorAGDMZKlVGL30d85Vx6D07rA5P2Nm7777L4cOHeeCBB0hPT2f48OEEBgZy5513XvO5U1NT8fPzA2xrk3LXz13GNE1WrFjBkCFDrvl65Ymq1xDjxXmo20LRG7+z3b+H9lkdlsuRb0RlTCkFbTpitO6A/nUL+rMVmBFToM1NGP2H26o5CJe3a9cuIiIiqFq1KoZh0LFjRxo3bszs2bO56667inz/tGnTCiyc+uCDD+Z5rJQqcHD9hx9+oF27dgQEBBR5rZiYGGJiYgCYNWsWgYGBBR7n7u5e6Gsu58nnudA1hNTIaZizX6DKA49Spf9QlLvtT2i5aosilKQtHCoRxcXFERUVhWma9OrVi9DQUKtDKjXKMFAdb0W37YRe9wX6q48ww8eg7hyA6nM/yl1WdbsyrTWenra6Zh4eHmRkZODr68uJEyeK9f7JkycX+pqPjw8pKSn4+fmRkpJS4EZ7+/fvZ+/evfzwww9kZmaSnZ2Nh4dHgfsghYSEEBISkvu4sEH4cjdAX7M+vPQG6sO3OfvRe5z9eRPGiKdRteqWv7a4gpJMVnALv9i5XAzLli3D19cXX1/fEgV4JaZpMmPGDF588UXuu+8+oqKiaNGiRZG7V6alpRX4vKenJxkZGaUe57VSbm6oJi1QXXpB8kn0+q/R2/+Lqt8Y5V82n6gctS2sUFhblPUU6p07dxIYGEiNGjWIj49nx44d7Nq1i+zs7Dx/9Evi1KlTJCQkcMMNN/D9999TrVo1brzxxjzHdOrUibvuuos777wTHx8fvL29efTRR4t1fme7x8qSqlAR1e5mVJ366K0b0P/5Gip74tmiDefOnbM6PIdQknvsqr4RmabJ9OnT8fb2pmvXrnTt2rVYX/WLIz4+npo1a1KjRg0AunTpQmxsLHXr1r3qc738sjcHDriTlVU6sZWNAGAWOj0Nth2Hz7IgIBsCqpd6TbsKFRy9LeynQwc3Jk60/3WfeOKJ3AkKw4YN44MPPuDs2bOMGTPmms8dGhpKREQE69evz52+DXDw4EHWrl3LyJEjr/kaIi/V4RaMxs0xl0eiP3ib03vj0A89ifKT+6wkrnodkWma7Nixg82bN7N9+3aaNm1Kt27d6NSpEx4eJZ9NsnXrVuLi4nJvmk2bNnHgwIF8ax3+2X994cKFfOd65hk3fvvNKLD0viPSOTnkJBzDPJ2MquyJe93rUKVYl0wp5TRtUdbatlW89lpWvucrVizbbUEOHDhA06ZN8z0fHx9PkyZNyvTa16q8rSO6Glpr9MZv0R9HgXsF1OBRGB1vtTosS9l9QevRo0eJjIzkyJEjVKxYkVtuuYUBAwbg7+9/1ecqbiL6J1e6SfSvWzBXLoKcbIyhYagOpbNFgDO2RVmxakHro48+yvLly/M9P2zYMKKiosr02tfKle6xsuJ7PoOkeS/D4f2oTsGoh55AeRa8qNjV2aXoaUZGBlu3bmXz5s38+eefdOrUiREjRhAYGMhXX33FjBkzmDt37tWeFn9/f5KSknIfJyUllSihOTPVoQtGw6aYb83BfHM2KuQe1P2XZuYI52OaJvD/n5z//7+L/v77b9xk3yuX4F6nPsaE2ehvPkZ/9SF6/++2enXN21gdmlO4qr9w8+bNY+fOnTRv3pzevXvTsWNHKly2h8cjjzzC0KFDSxRI48aNSUhIIDExEX9/f7Zs2UJYWFiJzuXMlH81jOdmoD9Zho75Av3XnxhPTEBVKZ+frpzdoEGDcn/+51RrwzC477777B2SKCPKzQ1194PoVh1si2Bfn2z7MNnvEdkRughX1TX3xRdf0K1btyvOmruWfVe2b9/O8uXLMU2THj160K9fvyLf48rdBuaWdegViyCwBsaYl1A165ToPK7QFqXF3l1zJ0+eRGtNeHg4U6dORWudu9bH29u7zMemSoMr32Ol5Z9toc+fR38ahf7PN1Crnm2vo/qOUwi5LEnR08u4yk2iD+zBXDwD0BhhU2y7xl4lV2mL0mB10VPTNPNUQnAGrn6PlYbC2kLv3o65LBLSz6DuGYTq08/lS3xJ0VMXpJq2wJg4Bzw8Mee9JOWBnNTZs2eZP38+Dz/8cG6X87Zt2/jwww8tjkyUJdWqPcbUBah2ndGfrcScMxF9sniLmMsTSUROQFWvjTFhNlSriRk5Db1jq9Uhiav0zjvv4OnpyeLFi3H//8knzZo1Y8uWLRZHJsqaqlIV9fhzqMeegeNHMaeG2SryO3dnVKmSROQklK8/xnMzoH4jzLdmSzJyMr/99hvDhg3L0yXn7e1dYIFS4XqUUhidgjHCI6FhM/SKhZiLpqPPpFgdmkOQRORElKcXxripUL+xLRnF/Wx1SKKYPD0985XKOXXqlFONFYlrp/yrYYx/BTVwBPy+AzM8TD5UIonI6SjPKpcloznofb9ZHZIohl69ejFv3jx2796N1pr9+/ezaNEievfubXVows6UYWCE3IsxOQL8AjAXz8BcFonOLF91+y4nicgJKc8qGGEv28aMFr6KPiKbnDm6e++9ly5durB06VJycnJYsmQJQUFB9O3b1+rQhEVU7foYE19D9e2P3rIec+pT6AN7rA7LEjJ924np5JOYsyeAqTGmv4mqWPD6rfLQFsVl9fRtZ1Se77Hiuta20PF7MN97A079jbq9n2035wrOuTWMXUr8CMeh/KthjHsFEhMKTULCcRw/fpw//viDzMzMPM/37NnTooiEo1BNWmC8/Ab6o/fQ332K3r3dtgi2TgOrQ7MLSUROTtWqC7WufqsMYV9r1qzh008/pUGDBvkqj1xrIkpPTyciIoKTJ0/mbgPh5ZW/JNSpU6d48803c2s6Tpw4kerVq1/TtUXpUR6eqEfGoNvchLl8Aear41H3PWIrE2S49iiKJCIh7OCbb75hxowZNGhQ+p9wo6Ojad26NaGhoURHRxMdHc3gwYPzHbdw4UL69evHjTfeSGZmZqnveyVKh2pzE0b4AsyVi9Afv4feFYsxbBwqoJrVoZUZ106zQjiIihUrUqdOyWoFFiU2Npbg4GAAgoODiY2NzXfMsWPHyMnJyd251cPDo8Q1IUXZU96+GKMmoR4dC3/EY04di7n1Py67CFa+EQlRRi5uAQEwcOBA3nvvPfr374+Pj0+e44xr7Ha5vHadr69vgYtkjx8/TpUqVZg7dy6JiYm0bt2ahx9+uMBr/3PzycDAgrewd3d3L/S18qbM2iJ0ENmdu3Em8lWylkZQcU8c3iOfx/D2Kfq9FilJW0giEqKMXL4FxEXr1q3L99zq1auLPNe0adM4ffp0vuf/ubXExcre/2SaJnv37mXOnDkEBgYSERHBhg0bChyfCgkJISQkJPdxYbPBZNbcJWXaFu6V0OPCUd9Hc/7z9zm5ZyfG0LGoVh3K5nrXSGbNCeFAFi5cCNg2xdu6dSs333xznte11vz8c/GqY0yePLnQ13x8fEhJScHPz4+UlBS8vb3zHePv7891111HjRo1ALjpppvYv3+/zNhzEspwQ91xP7plO8z3IjDnT0V174t6YCiqkofV4V0zGSMSooxUq1aNatWqUb16dT799NPcx5c/v2bNmmu+TlBQEBs3bgRg48aNdOzYMd8xTZo0ISMjgzNnzgCwe/du6taV2ZbORtVvhPHiPNRtoeiN32K+Mg59aJ/VYV0z+UYkRBnavXs3ADk5Obk/X/T3339TuXLla75GaGgoERERrF+/Pnf6NsDBgwdZu3YtI0eOxDAMhgwZwiuvvILWmkaNGuXpfhPOQ1WoiOo/HN06CDPqDczZE1B3DkD1HYByd84/6VJZoRyQtrjE3pUVRo8eDdjGWS4fwFVK4evrS2hoKEFBQWVy7dIi91jRrGoLnXEW/eHb6P/+Bxo0sS2CrWntN12nHSNauXIlv/76K+7u7tSoUYNRo0ZRpUoVq8MS4potWrQIsI0XjRkzxuJohKtRnlVQw8fbFsGuXIw5bRzqgWG28SMnWifmEGNEN954I/PmzWPu3LnUqlWLzz77zOqQhChVkoREWVIdbsEIXwDNWqH//Rbm/HD06SSrwyo2h0hEbdq0wc3Nto97s2bNSE5OtjgiIYRwLsrXHyNsCurhkXDgd9teR9t+tDqsYnGIRHS59evX07ZtW6vDEEIIp6OUwujeF2PyfNs2MW/NwVz6Ojoj3erQrshuY0RXWpB3cbrpmjVrcHNzo2vXroWeR1Z9Xz1pi0ukLUR5oGrWwZgwG/3Nx+ivV6P377bVq7vhRqtDK5DDzJrbsGEDa9eu5eWXX76qGlgyo6do0haXyH5EV0/usaI5clvow/sxl0bA33+hQu5F9RuCqlCxzK5XknvMIbrm4uLi+Pzzz5kwYYIUYhRCiFKkGjbDmPwGqkdfdMznmK8+jT5yyOqw8nCI6dtLly4lOzubadOmAdC0aVMef/xxi6MSQgjXoCpVQj00En1jR8xlCzBnPIu69yHU7fehDDerw3OMRLRgwQKrQxBCCJenWnXACI9Er1qCXrPCttfR8PGoajUtjcshuuaEEELYh/LyRj3xPGrE0/DXEcypT2Fu/sHSvY4kEQkhRDmjlMLo3B1jSiRc1wS9YiHmounoM/lnNtuDJCIhhCinVEA1jKenoQaMgN93YIaPRccVb2uS0uQQY0RCiJJLT08nIiKCkydP5lbf9vLyynfcqlWr2L59O1prWrduzbBhw5yqHpkoG8owUL3vRbdoi/nu65iLpqNu7Y0aOALl4WmXGOQbkRBOLjo6mtatWxMZGUnr1q2Jjo7Od8y+ffvYt28fc+fOZd68eRw8eJA9e/ZYEK1wVKpOA4wX59o24PspBnPqU+h4+/yOSCISwsnFxsYSHBwMQHBwMLGxsfmOUUpx4cIFsrOzycrKIicnBx8fH3uHKhyccq+A0e9RjOdmAmDOmYS5ZgU6O6tMrytdc0I4udTUVPz8/ADw9fUlNTU13zHNmjWjZcuWPP7442it6dOnT6E7tEoZravncm0R2A2zbQfS3osk89tPcPvfTnzGTcG9fqMi31qStpBEJIQTuFKtxssppQoc9zlx4gR//fUXb775Zu759u7dS/PmzfMdGxISkmf31sJK1zhyWRt7c9m2GPgvjOtvJHvFQpKeGYbq9wiq190oo/DONKfdGE8IcWWTJ08u9DUfHx9SUlLw8/MjJSUFb2/vfMf88ssvNG3aFA8PDwDatWvH/v37C0xEQlxOte2E0eh6zBUL0R8ttS2CHfoUKqBaqV1DxoiEcHJBQUFs3LgRgI0bN+ZWs79cYGAge/fuJScnh+zsbPbs2UOdOnXsHapwUsrbF2P0i6hHxsDhA5hTwzC3bii1RbCSiIRwcqGhoezatYuwsDB+++03QkNDATh48GBuV1znzp2pUaMGzz77LM899xwNGjQgKCjIyrCFk1FKYXS9DWPKfKhTH730dfTbr6HPpl37uR1lG4iSkhL1RZO2uES2gbh6co8Vrby1hTZz0N9/hv783+DljTE0DNWqPeDE20AIIYRwHspww7jjAYxJr4FnFcz54Zj/fhN9/nyJzieJSAghRImo+o0xJkfYKjP85xvMaePIOrz/qs8jiUgIIUSJqQoVMQaMwHjatp+ccq9w1eeQRCSEEOKaqeZtMF5ZiHu9hlf9XklEQgghSkVJd3uVRCSEEMJSkoiEEEJYyunXEQkhhHBuLvuN6IUXXrA6BIchbXGJtEXpkba8RNrikpK0hcsmIiGEEM5BEpEQQghLuYWHh4dbHURZadSo6E2cygtpi0ukLUqPtOUl0haXXG1byGQFIYQQlpKuOSGEEJZyuR1a4+LiiIqKwjRNevXqlbs3S3k0evRoPDw8MAwDNzc3Zs2aZXVIdrN48WK2b9+Oj48P8+bNAyA9PZ2IiAhOnjxJtWrVGD9+PF5eXhZH6nzK8z0mv1eXnDp1ikWLFnH69GmUUoSEhNC3b9+StYd2ITk5OXrMmDH6xIkTOisrSz/77LP66NGjVodlmVGjRunU1FSrw7DE77//rg8ePKiffvrp3OdWrlypP/vsM6211p999pleuXKlVeE5rfJ+j8nv1SXJycn64MGDWmutMzIydFhYmD569GiJ2sOluubi4+OpWbMmNWrUwN3dnS5duhAbG2t1WMICLVq0yPcpLDY2luDgYACCg4Pld6MEyvs9Jr9Xl/j5+eVOSqhcuTJ16tQhOTm5RO3hUl1zycnJBAQE5D4OCAjgwIEDFkZkvenTpwPQu3dvQkJCLI7GWqmpqfj5+QHg6+tLamqqxRE5H7nH8pPfK0hMTOTw4cM0adKkRO3hUolI5DVt2jT8/f1JTU3l1VdfpXbt2rRo0cLqsByCUgqllNVhCBdTHn+vMjMzmTdvHkOHDsXT0zPPa8VtD5fqmvP39ycpKSn3cVJSEv7+/hZGZK2L/3YfHx86duxIfHy8xRFZy8fHh5SUFABSUlLw9va2OCLnI/dYfuX59yo7O5t58+bRtWtXOnXqBOvNKi4AACAASURBVJSsPVwqETVu3JiEhAQSExPJzs5my5YtBAUFWR2WJTIzMzl37lzuz7t27aJ+/foWR2WtoKAgNm7cCMDGjRvp2LGjxRE5H7nH8iuvv1daa958803q1KnDXXfdlft8SdrD5Ra0bt++neXLl2OaJj169KBfv35Wh2SJv//+m7lz5wKQk5PDrbfeWq7a4o033mDPnj2kpaXh4+PDgAED6NixIxEREZw6dapcTbMtbeX5HpPfq0v+97//8fLLL1O/fv3c7rdBgwbRtGnTq24Pl0tEQgghnItLdc0JIYRwPpKIhBBCWEoSkRBCCEtJIhJCCGEpSURCCCEsJYlICCGEpSQRCSGEsJQkIiGEEJaSROSiTpw4wbBhwzh06BBgq5o8YsQIfv/9d4sjE0KIvCQRuaiaNWvy8MMPs2DBAs6fP8+SJUsIDg6mZcuWVocmhBB5SIkfFzd79mwSExNRSjFz5kwqVKhgdUhCCJGHfCNycb169eLo0aP06dNHkpAQwiFJInJhmZmZLF++nJ49e/Lxxx+Tnp5udUhCCJGPJCIXFhUVRaNGjRg5ciTt27fn7bfftjokIYTIRxKRi4qNjSUuLo5//etfADz66KMcPnyYzZs3WxyZEELkJZMVhBBCWEq+EQkhhLCUJCIhhBCWkkQkhBDCUpKIhBBCWEoSkRBCCEtJIhJCCGEpSURCCCEsJYlICCGEpSQRCSGEsJQkIiGEEJaSRCSEEMJSkoiEEEJYShKREEIIS0kiEkIIYSl3qwO4VsePHy/w+cDAQE6dOmXnaByTtMUlhbVF7dq1LYim9CxevJjt27fj4+PDvHnz8r2utSYqKoodO3ZQqVIlRo0aRaNGjYp1brnHiiZtcUlJ7jH5RiSEC+jevTuTJk0q9PUdO3Zw4sQJIiMjefzxx3n33XftGJ0QV+b034iEKA59Nh29+h2yHxwBnt5Wh1PqWrRoQWJiYqGvb9u2jW7duqGUolmzZpw9e5aUlBT8/Pyu+lo6/Qx6zQrOeHhgZmbmP8AwoIo3VK0KXt4oL2+4+J+PP6pChau+pnBtkoiEy9N74jCj5kPaabI63AxtOlsdkt0lJycTGBiY+zggIIDk5OQCE1FMTAwxMTEAzJo1K8/7AHIwSd69nfMKVAH7O+ucbHT6GTBN2+PLXzQM3KrXwq1OfdzrNMCtTgPc//9nw9f/mv+dVnF3d8/XTuVVSdpCEpFwWfrCefSaFeh1X0LNuhijJ1E56GbOSl/+FYWEhBASEpL7OH9/v4Ga816hYwEK0KYJ5zIg/UzufzotFZJPYp74i5yEY1zY9StkXbj0Rv9AVJMW0KS57X/r1EcZbmXzjyxlMkZ0SUnGiCQRCZek/4zHfPd1OHEM1etuVL9HUBUrWR2WZfz9/fP8cUhKSsLfv+y+gSjDgCpetv9q2P4AqX8co00TUk5BwjF0wlE4tA+9fzf8ssn2LaqyJzS6HtW0Jap1ENRriFL/PItwBZKIhEvROTno7z5Ff/kBVPXFGD8V1aKd1WFZLigoiO+++45bbrmFAwcO4OnpWaLxodKkDAMCqkNAdVSr9oBtdh9Jiej4vRC/Bx2/F/35++joVbbj2tyEatsJmrZEucufL1ch/08Kl6ETj2O+9wYc/B/qpm6oh0aiqnhZHZZdvPHGG+zZs4e0tDRGjhzJgAEDyM7OBuC2226jXbt2bN++nbCwMCpWrMioUaMsjrhgSikIrIEKrAGduwOgz6Sgd8aid/6C3vwDev1X4FkF1ToI1b4L3BiEcpcJEM5Maa0LGG4sfXFxcURFRWGaJr169SI0NDTP66dOnWLRokWcPXsW0zR56KGHaN++fZHnlTUORXP1ttBaozd/j/7oPXBzQz00EqNTcIHHuuo6orLkSPeYPp8Je+LQcT+jd/0C6WlQ1QfVuTvq1t6o2vXtGs9Frn6PXQ2HHSMyTZOlS5fy0ksvERAQwMSJEwkKCqJu3bq5x3z66afcfPPN3HbbbRw7doyZM2cWKxGJ8k2npmAuXwC/bYPmbTCGPoXyl9lLrkpV8oB2nVHtOqNzcmDPDswf16LXf4Ve+7ltTOmWEFTHrqjKnlaHK4rJLokoPj6emjVrUqNGDQC6dOlCbGxsnkSklCIjIwOAjIwMy/uvhePT2/+LuXIRnM9EPfg4qkdf27iDKBeUmxu0DsKtdRD6zGn01g3oH9eiVy5Cr34XdXMP1G2hqOrybdfR2SURJScnExAQkPs4ICCAAwcO5Dmmf//+vPrqq3z33XecP3+eyZMnF3iuotY4XCTz+i9xtbYwM86StvQNMtd/jXuj6/EZNwX3etcV672u1hbCRnn7om4LRfe+1zb7bvMP6J9i0Ju+h/Y3Y9x+P6phU6vDFIVwmMkKP/30E927d+fuu+9m//79LFiwgHnz5mH84xNu0WscbKTP9hJXagu9f7dtQkLyKdSdAzDvGshp9wpQzH+fjBG5NqUUNL4B1fgG9H1D0Ou+RG/4FvPXLXB9a4zb+0Gr9jIN3MHYpR/D39+fpKSk3McFrWFYv349N998MwDNmjUjKyuLtLQ0e4QnnIDOysL8ZBnm3BfBMDCen4kROlhmS4lCKR8/jH6PYMxZiuo/HBITMCOnYk4NQ2//L3aapyWKwS6JqHHjxiQkJJCYmEh2djZbtmwhKCgozzGBgYHs3r0bgGPHjpGVlYW3t+vVBBNXTx/7A3PGM+jv16C63obx8nxUk+ZWhyWchPLwxLgtFGPGW6hh4yAnG3PJTMxZz6P37bY6PIGduubc3NwYPnw406dPxzRNevToQb169Vi9ejWNGzcmKCiIRx55hLfeeouvv/4agFGjRsnX53JOmznotV+go1eCpxfGmMmoNh2tDks4KeVeAdWlJ7pTMHrLOvQXH2DOnQStgzD6DUHVbWh1iOWW3dYRlRVHWuPgqJyxLXRSom0saP9uaNcZY8hoVFWfaz6vjBFdPVe9x/SF87Zp399+AucyUJ2CUfc8hKpW86rP5extUZocdh2REMWltUb/9z/oD94CQA19CtWlp3w7FqVOVayE6nM/uuvttrJQ675Eb/sJdccDqDvuR1WoaHWI5YYkIuEwdNoZzFWLYPt/oWkLjOHjbaVehChDqooX6v5H0T3vQn8Shf7yA/TW/2A89ASqVQerwysXJBEJh6B/24a5LBLOpqMeGIrqfa/TbAEgXIPyC0D961n0rb0x//0m5vyp0L4LxsARKP9qVofn0iQRCUvpzHPoj6PQm76DOg0wxk1F1ZNBY2Ed1bwNxsuR6B8+Q3/zEebv21F3D7JtJyIVv8uEtKqwjD74P8z3IuDkCdRt96FCH5Z+eeEQVIUKqDsHoDsFY374jq3L7ucNtu7iutdZHZ7LkcJcwu50djbm5+9jzn4BsrMxnnkVo/8wSULC4ajAGriNeQlj1CQ4nYw5/WnMbz9FmzlWh+ZS5BuRsCudcAxz6evwZzzq5p6oB/+F8qxidVhCXJFq1xmjSQvM9xej1yxH7/wZY9g4VA2Z9l8aJBEJu9Cmid7wDfqTZVCpEsbIF1Adulgdlkspas+vDRs2sHLlytzyWn369KFXr15WhOqUVFVvjCcmoH/ZhP73W5ivhKHuH4rq3tfq0JyeJCJR5nRKkm1G3J4dtlXsj4xB+foX/UZRbMXZ8wtsW7CMGDHCoiidn1IK1SkYfX0rzOUL0R+8jY77mZxnXgFkrVtJyRiRKFNm7GbM8LEQvwc1eBTG2MmShMrA5Xt+ubu75+75JcqG8g3ACHsZ9cgYOLSPpKcfRe/+1eqwnJZ8IxJlQp9NR//7LfQvG6FhM4wRT0t/ehkqzp5fAD///DN79+6lVq1aPProowXuzSR7fl2F+x4i+6ZbSJ07mez5U6ly/yNUGfQYyq38/mktye9F+W0tUWb0njjMqPmQdhp170OoO/rbdtMUlurQoQO33HILFSpUYO3atSxatIgpU6bkO072/LpKlaoQMOsdTi6aydlPV3D2t18x/vUsyjeg6Pe6IIeuNVfUQCrAli1b+Pjjj1FK0aBBA5566il7hSdKgb5wHr1mBXrdl1CzDsboOajrZFdMeyjOnl9Vq1bN/blXr16sWrXKbvG5OlWpEsYjYzCbtUSvWoL5yjhbL0DLdlaH5hTskoiKM5CakJBAdHQ006ZNw8vLi9TUVHuEJkqJ/vOgbVp2wlFUz7tQ/R5FVapkdVjlxuV7fvn7+7NlyxbCwsLyHJOSkoKfnx8A27ZtyzeRQVw7o3MPdIOmmG/NxpwfjurbH3XPIClXVQS7JKLLB1KB3IHUy2+EdevWcfvtt+Pl5QWAj8+1l/wXZU/n5NgqF3/5AVT1sZXokU+BdlecPb++/fZbtm3bhpubG15eXowaNcrqsF2SqlUXY+Jc9Advob/+CH30MMZjz6Aqe1odmsOyy35EW7duJS4ujpEjRwKwadMmDhw4kGca6Zw5c6hduzb79u3DNE369+9P27Zt853rnwOpFy5cKPCa7u7uZGdnl8G/xvmUVVtkJxzjTOQ0sv73G5Vu7YX3489hVHXsXXULa4uKFaWqQ2FcdT+i0lRYW5j/+Qb94dtQow7GmJdQ1WtZEJ19OfQYUVFM0yQhIYEpU6aQnJzMlClTmDt3LlWq5F11LwOpV6+020Jrjd78A/qjpWC4oR57huxOwSSfvwDnHbvNZWM8YU9Gj77omnUw35qDOf0ZjJETUM3bWB2Ww7HLOqLiDKT6+/sTFBSEu7s71atXp1atWiQkJNgjPHEV9JkUzIWvolcugkbXY4RHYnQKtjosIRyWat4GY9Jc8PHDfGMK5n++xsk3xi51dklElw+kZmdns2XLFoKCgvIcc9NNN/H7778DcObMGRISEnLHlIRj0HFbMcPDYE8cauBjtvEg2adFiCKp6rUwJr4GrYNs6+tWLUFnZ1kdlsOwS9dccQZS27Rpw86dOxk/fjyGYTB48OA8002FdXRmBvrDd9E/xUD9RhjPTEfVqW91WEI4FVXZE2PURHT0KvS3n6L//gtj1ESUp5fVoVnOLpMVypIMpBbtWtpCH9hj2zMo6STqjgdQdw9EuVco5Qjtx4oxotTUVHbu3Mkff/xBRkYGnp6eXHfdddx44434+vqW2XVLi9xjRbvatjD/+x/08gW29XZPhaP8XGfxa5lOVjh16hR//vknZ8+epUqVKjRo0EDKe7gwnZWF/uLf6O/XQGANjOdnopo0tzosp3Ls2DFWr17N77//TqNGjahTpw6+vr6cO3eOTZs2sWzZMlq2bMnAgQNlTU85Y9zcA+3jh7lkJuas5zDCwst1L8MVE1F2djYxMTGsXbuWxMREatasiYeHB5mZmZw4cYLq1avTu3dvQkJCcJctdF2G/utPzHdfh2OHUV1vQw0YgfKobHVYTmfx4sXcc889hIWFUaFC/m+RWVlZbNu2jSVLljB9+nQLIhRWUi3aYjw3EzNyKuacCRijX0I1a2l1WJa4Ytfc+PHjadWqFbfeeitNmzbFMC7NbTBNk/j4eDZv3szvv//O66+/bpeA/0m6DYpW3LbQpomO+QL92QqoXAXj0TBUm452iNB+ZPr21ZN7rGjX1P196m/M+VPh1N8Yjz2N6nBLKUdnX6XeNRceHl5ohQPDMGjWrBnNmjXjzJkzVxmqcDQ6KdFWqHTfb9C2M8Yjo1FVpbpFaZkzZw7PP/98vufnzp3Ls88+a0FEwlGowBoYL8zGXDAN8605qIH/wuh1l9Vh2dUVp29fnoS++OKLAo/56quv8PZ27NX0onBaa8wt6zGnhsEf8aihYbaZPJKEStXFpQnFfV6UL6pKVYynp0GbTugP38b8bFW5WmtU7IGdTz/9lHvuuafA5++6q3xlb1eh085grloM27dAkxYYw8ehqtW0OiyXsnr1asA23nrx54v+/vtvqlWTdVjCRlWshPHkBNsao28+gguZMGAESrn+zq9FJqLdu3cDtjGhiz9f9Pfff1O5sgxiOyP926+YyyMhPc1WKfv2UKkQXAYuVhQxTTNPdRGw9aUPGDDAirCEg1KGGwwZDRUroWO+gPOZMPhJl783i0xES5YsAeDChQu5P4Nt73ZfX1+GDx9edtGJUqfPZ6I/iUJv+BZq18cIm4Kq38jqsFzWxQrXzZo1y1MjUYjCKKVg4GNQqfL/fzM6D8PGufTmkkUmokWLFgGwcOFCxowZU+YBibKjD+3DXBoBJxNQt4WiQgejKkjV6bJy+vTp3AWrV0pClx8nBNiSkbpvMGbFirZKDFkXbLu+OvFi8isp9hiRJCHnpbOzMT//t+3Tla8/xtPTUDfcaHVYLu+VV16hRYsWdOvWjSZNmhS4/GHTpk3s3buXefPmWRipcFTGnQMwK3mgV7+LuWgGxpMvoCq63oaTV0xEEydO5J577qFjx44FLljNzs7ml19+4auvvmLGjBllFqQoOX3iGMmzn0fH/w91cw/Ug4+jPKsU/UZxzebMmUNMTAxvvfUWiYmJVK9encqVK3Pu3LncBeK9e/dm6NChpXK9uLg4oqKiME2TXr16ERoamuf1rKwsFi5cyKFDh6hatSrjxo2jevXqpXJtUXaMkHswK1ZCr1qMGfkKxtjJqEoeVodVqq6YiEaPHs3q1at59913adiwIbVr186trJCQkMChQ4do1aqV7PTogLTW6A3f2MaDKnrY9kFx8oVyzsbd3Z0+ffrQp08fTp06xZEjR8jIyMgtkfXPrVCuhWmaLF26lJdeeomAgAAmTpxIUFBQntJB69evp0qVKixYsICffvqJ999/n/Hjx5daDKLsGN1utyWj997AXPgqxpjJqEqu883oiomobt26PPPMM5w+fZpdu3Zx5MgR0tLSqFKlCt26dWPMmDHF3tK7qE9rF23dupXXX3+dmTNn0rhx46v/Fwn06STMZZHw+w5o1Z6A8eGkmFZHVb4FBgaWaW3G+Ph4atasmbt1SpcuXYiNjc2TiLZt20b//v0B6Ny5M++99x5a63IxPdgVGJ27Y6JtyWjxdNuOry4yxlusMSJfX1+6detW4osU59MawLlz5/j2229p2rRpia9V3pmxP6JXLYbsLNTDT6KC++DmHwhSisVSWVlZfPLJJ/z000+kpaWxfPlydu7cSUJCAn369Lnm8ycnJxMQcKmCc0BAAAcOHCj0GDc3Nzw9PUlLS8u3ID0mJoaYmBgAZs2aVWgCdXd3l8LH/89ubXFXf85VrsyZhTNwf3cevi/MdLhkVJK2uGIi2rNnDy1atADIt4bocq1atbriRYrzaQ1si//uvffeQqs4iMLpjHTbhls/b4SGzTCGj0fVrGN1WOL/LV++nOTkZMLCwnLHU+vVq8fy5ctLJRGVppCQkDyz/AqroSa15i6xa1u06YwaMpoLKxeROP15W7e7A82mK/Vac0uXLs2dzXP5GqLLKaVYuHDhFQMrzqe1Q4cOcerUKdq3by+J6CrpvTttdeJSk1H3PoS6o79LrzlwRr/88guRkZF4eHjkdoX5+/uTnJxcKuf39/fPs2A2KSkp3xjUxWMCAgLIyckhIyNDNp90Uka32zFzctD/fhPznbkY/3oO5cQ7IFwx8sunlF5cT1QWTNNkxYoVxZr0IN0Gl+gL50lf9SYZX67GrU59fCbOokLTFvmOKw9tUVxWtYW7uzummXeg7syZM6WWCBo3bkxCQgKJiYn4+/uzZcsWwsLC8hzToUMHNmzYQLNmzdi6dSstW7aU8SEnZvToi5mTjV79Lnrp6/DYM077AbTEKXT37t0YhpHbdXclRX1ay8zM5OjRo0ydOhWwLfC7WK34nxMWpNvARh85aNszKOEoqsed6PuHklqpUoFjQa7eFlfDqm0gOnfuzMKFC3OnaqekpLBs2TK6dOlSKud3c3Nj+PDhTJ8+HdM06dGjB/Xq1WP16tU0btyYoKAgevbsycKFCxk7dixeXl6MGzeuVK4trGOE3GP7ZvRJFLi72yowGFesZe2Qir1V+JQpUxg0aBA33HAD0dHRfP311xiGwe23306/fv2u+N6cnByeeuopXn75Zfz9/Zk4cSJhYWHUq1evwOPDw8MZMmRIsWbNlbe9UrSZg/5uDfqLD6CqN8bQp1At213xPa7aFiVhVSLKzs5m1apVrFu3jgsXLlCxYkV69erFww8/XOCmeY6kvN1jJWF1W5hff4SOXoXqcSdq0OOWftMt063Cjx49SrNmzQBYt24dU6ZMwcPDg8mTJxeZiIrzaU0UTZ88gfleBMTvRXW4BTVkFKqK9PE7A3d3d4YOHcrQoUNzu+SkW0yUFtW3P5xNQ6/9HKr6oO5+0OqQrkqxE9HFL04nTpwAyJ3xdvbs2WK9v3379rRv3z7PcwMHDizw2PDw8OKGVS5ordE/rkWvXgqGgRrxNKpTsPwhcyLDhg0jKioKIM906ccee4x3333XqrCEi1BKwQPDID0N/cW/Mb2qYvS40+qwiq3Yiej666/nvffeIyUlhY4dbdtHnzhxQmbdlDF9JgVzxSLY+Qtc39q2Z5C/7GHjbHJycvI9l52dnW8CgxAlpQwDHh1rW8rxwduYnl4YnYKtDqtYip2IRo8ezZdffom3t3fuBnnHjx+nb9++ZRZceafjttqS0LkM1MARqJ53O+VAZHn28ssvo5QiKyuLKVOm5HktKSkpt7tbiNKg3NwwHn8Oc/5UdNQbaE8vVOsOVodVpGInosqVK2MYBps3b+bLL7/Ez8+PLl26FDk+JK6ezsxAf/gu+qcYqN8I45npqDr1rQ5LlEDPnj0B26LuHj165D6vlMLHx4fWrVtbFZpwUapiJYzRL2LOexHzzZkY46ehmjS3OqwrKnYieuedd0hISGD48OFUq1aNkydP8tlnn5GcnCxFT0uRPrDHNiEh6SSqb3/U3Q861KppcXW6d+8OwObNm6lVqxbXX3997mv79u1j5cqVpVZ9W4iLlGcVjKfCMWe/gLngFYznZqLqXmd1WIUqdj9PbGwsEyZMoF27dtStW5d27drx/PPPExsbW5bxlRs6OwtzzXLM1yaCUhjPz8C4b4gkIRfxxx9/5FuO0KhRI3788UeLIhKuTnn7Yjz9ClSshBn5Cjolqeg3WaTYicjX15fz58/nee7ChQv4+fmVelDljf7rT8zpz6K//RR1a2+Ml99ANSl6obBwHkqpfBMTTNOkmMv4hCgRFVAdI2wKnDtrS0bnMqwOqUBu4cWcK33u3Dnef/99DMMgNTWV33//nWXLltG1a1eys7NJTEzM3fzLntLS0gp83tPTk4wMx2z0i7Rpotd+jn57DuTkYDz+HMbt95X6tyBnaAt7Kawtynr25/79+zl8+DCtW7fOTUqrV6/Gw8ODW25x7H2inPkesxdHbgvl44dq0AQd8zn6j3hUx65lOumpJPdYsSsrjB49ushjilMAtbQ566pvnXQSM+oN2PcbtO2EMWQ0ytu3TK7l6G1hT1ZVVkhKSmLWrFmcPn06NwY/Pz8mTJiQpyCwI3LWe8yenKEtzB/XopcvQN3aG/XImDJbh1imlRXKsuhpeaK1Rm/dgP7gLTA16tGxqFtCZHGqiwsICGD27NnEx8fnVsBu0qQJhkzHF3Zi3NobMykR/dVqCKiOuqvgggJWcN664U5Ip5/BXLUYft0CTZrb9gyqVtPqsISdGIYh64aEpdQ9D8GpRPTn72P6V8Po0tPqkABJRHajd/+KuWwBpJ9B9XsEdft9KMM5S7YLIZyTUgoeHYM+nYResQDtF4Bq3sbqsIo/a06UjD6fifn+m5jzp0IVL4xJczHueECSkBDCEsq9AsaTL0CNOphLZqKPH7E6JPlGVJb04f2YSyMg8Tiq972o+4Y43P7ywvmlp6cTERHByZMnqVatGuPHj8fLyyvfcQMHDqR+fVuFjsDAQCZMmGDvUIWDUJ5eGGFTMGc8g7nwVYxJc1Fe3kW/sYzYLRHFxcURFRWFaZr06tWL0NDQPK9/9dVXrFu3Djc3N7y9vXnyySepVs05i3vq7Gz0Nx+hv/4IfP0xnp6GuuFGq8MSLio6OprWrVsTGhpKdHQ00dHRDB48ON9xFStW5LXXXrMgQuGIVEA1jFGTMOe+iPnmbIxx4ZYtoLdL15xpmixdupRJkyYRERHBTz/9xLFjx/Icc9111zFr1izmzp1L586dWbVqlT1CK3X6xDHM2RPQX36IuqkbxpRISUKiTMXGxhIcbKuyHBwcLNVORLGpxjegHh0L+35Df/C2ZQus7fKNKD4+npo1a1KjRg0AunTpQmxsbO6eRgCtWrXK/blp06Zs3rzZHqGVGq01esM3ti17K1TCGDkB1cGxFyoK15Camppb4cTX15fU1NQCj8vKyuKFF17Azc2Ne++9l5tuusmeYQoHZXTujnn8CPrbT6B2fVSvu+0eg10SUXJycp5FewEBARw4cKDQ49evX0/btm0LfC0mJoaYmBgAZs2aRWBgYIHHubu7F/paactJPsmZhTO4sONnKrbrjPeYSbj52+faxWHPtnB0ztoW06ZN4/Tp0/mef/DBvDtxKqUKXZO2ePFi/P39+fvvv3nllVeoX78+NWvmXz7giPeYo3P2ttCPjSM1OZHzHy2larPmVGrXucTnKklbONxkhU2bNnHo0KFCd2kNCQkhJCQk93Fhq5nttdJZb/sRc9USyDqPengk2cF3kGICDrTK2hlWfduLVZUVrtXkyZMLfc3Hx4eUlBT8/PxISUnJswPs5fz9/QGoUaMGLVq04I8//igwETnaPeYMXKEt9ODR8NcRTr82GWPia6hadYt+UwFKco/ZZYzI39+fpKRLlV+TkpJyb4rL7dq1i88++4znn3+eChUcu+q0zkjHXPo65ltzoHotjMnzMbr3lQoJwu6CgoLYuHEjABs3bszdQfly6enpZGVlAXDmzBn27duXp2tcCOVRGWPMS+DujrlwGvpswTUGy4JdvhE1btyYhIQEEhMT8ff3Z8uWFMn+uQAACV9JREFULYSFheU55vDhw7zzzjtMmjQJHx8fe4RVYnrvTsxl8+F0MuruQag7B6DcZF2QsEZoaCgRERGsX78+d/o2wMGDB1m7di0jR47kr7/+4u2338YwDEzTJDQ0VBKRyEcFVLfNpJt3cSbdVLv8bSt20dNrtX37dpYvX45pmvTo0YN+/fqxevVqGjduTFBQENOmTePIkSP4+toKfxZ3nYM9CzLqrAvoNSvRMZ9DjToYI55GNWxaqtcoC67QbVBanLVrzkpS9LRortYW5k/r0Mvmo24Lxeg//KreW6ZFT69V+/btad++fZ7nBg68VHTvSn3gjkAfOWhbnHr8CKpHX9T9w1CVKlkdlhBClDrjll6Yfx5A/xCN2aAJxk3dyvR6DjdZwdFoMwf9/Wfoz/8NXt4YT4WjWrUv+o1CCOHE1IAR6KN/oJdHomvXQ9VtWGbXklpzV6BPnsB8bRJ6zQpU204Y4ZGShIQQ5YJyr4AxcgJ4emEunlmmkxckERVAa425+QfMqU/BX0dQI55GPfG8pbWYhBDC3pSPH8bIFyD5FOa789BmTplcRxLRP+gzpzEXTUevWAgNm2KER2J07i7TsoUQ5ZJqfANq0OOwe7ttiKIMyBjRZXTcz5grFsK5DNTAEaied5fp3u5CCOEMVLfb4c949Dcfoxs0QbW/uVTPL4kI0JkZ6NVL0T+uhXoNMZ6ZjqpT3+qwhBDCISilYNAT6GN/YL73Bkatuqha9Urt/OX+476O34M59Sn0T+tQdzxg25dDkpAQQuShKlSwjRdVrIi5ZBY681ypnbvcJiKdnYW5ZjnmnEmgFMbzMzD6PWLZfhxCCOHolH8gxr+ehRN/oVcuLrVtI8pl15z+6wjm0nlw9DCq622oAcNRHp5WhyWEEA5PNW+DumcQ+vP3oWkLVPc7rvmc5SoRadNEr/sSvWYFVPbEGP0iqm0nq8MSQginovr2Rx/ci179DrphU1SDJtd0vnLTNaeTTmK+Phn90VJo2c62OFWSkBBCXDVlGBjDn4aqvphvzkafTb+m87l8ItJaY279D+bUMPjjAOqRMbZvQt5+VocmhBBOS1X1xnjieUg5hbls/jWNF9mtay4uLo6oqChM06RXr16EhobmeT0rK4uFCxdy6NAhqv5fe3cX09QZxgH8f1oytYCVFsGl1mRWjdE7LKgkBnVNlqDZotlUlpARLhYubPkIWYAJaWYIzbKuJn6MkHlBmEu8GVwvxMgFSMQxkikhYmMWTDQIpQzSaaB9d6G0NpUJ7bEHzvn/7nrO4Zw3T87Th/NweN/sbNTU1CAvLy+la4r5fyB++Qnij37Athe6ylpIeR+mdE4iInpFsu2F9HnFq39/+b0H0ienkjpPWp6IIpEIrl+/jqamJvh8PvT39+PJkydxx9y6dQuZmZm4fPkyTpw4gRs3bqR0zZd/DiLidkGMDEI6VQ7dN20sQkREMpM+/hQoKIb4rRNifDSpc6SlED169Ajbtm1Dfn4+MjIyUFxcjKGhobhj7t27h6NHjwIADh06hPv37yf1qCdevkTk13YEv6sDDJnQNf0AXekXkHRcuI7U6c6dO6irq8PZs2fh9/uXPW5kZATV1dVwOp3o6elJ4whJzSRJgu4rJ5Cbj0jH94gEA6s+R1pac4FAAGazOfrZbDZjfHx82WP0ej0MBgPm5uaweXP8RKO9vb3o7e0FAHg8HuTm5sbtj/wbQmDsL2z8rAyZX34N6QOuGZSRkZEQJ61SYyysVivq6+vR0dGx7DFLXYkLFy7AbDajsbERdrudq7SSLCRDJnRVDYj82IyFv/2AZXVLRqy717cdDgccDkf089tWAhTfepFl2f56X/rWXV+r1LZ6ZCrUuELrSorJm10JANGuBAsRyUWyfgSd52dssGzH3Cq/b9LSmjOZTJieno5+np6ehslkWvaYcDiMUCiE7OzspK4nbdiY/GCJVOhtXYlAYPUtFKL/k+x3b1qeiGw2G54+fYrJyUmYTCYMDAzA5XLFHXPgwAHcvn0be/bsweDgIPbv38+lF4heu3jxIoLBYML2c+fOobCwUNZrvav9vUSNbc5kMRYxycQiLYVIr9ejsrISra2tiEQiOHbsGKxWK27evAmbzQa73Y7jx4/jypUrcDqdyMrKQk1NTTqGRrQuNDc3p/TzK+lKLFlJ+xtgy/dNjEVMMu1vScg1ax0RKcrtdqO8vBw2my1hXzgcRnV1NVpaWmAymdDY2AiXywWrVb6p/ImSpdqZFRoaGpQewprBWMSoMRZ3795FVVUVHj58CI/Hg9bWVgCv/i7U1tYGIL4rUVtbi8OHD6dchNQYy2QxFjHJxGLdvTVHRPGKiopQVFSUsH3pyWdJQUEBCgoK0jk0ohVR7RMRERGtD3q32+1WehDvy86dO5UewprBWMQwFvJhLGMYi5jVxoIvKxARkaLYmiMiIkWxEBERkaJU99bcu9Y9Urtr165heHgYRqMRXq8XADA/Pw+fz4fnz59j69atqK2tRVZWlsIjfb+mpqZw9epVBINBSJIEh8OB0tJSTcZCblrOMeZXjKw5JlQkHA6L8+fPi2fPnomFhQVRX18vJiYmlB5WWj148ED4/X5RV1cX3dbV1SW6u7uFEEJ0d3eLrq4upYaXNoFAQPj9fiGEEKFQSLhcLjExMaHJWMhJ6znG/IqRM8dU1ZpbybpHardv376E3z6GhoZQUlICACgpKdFETHJycqJv7mzatAkWiwWBQECTsZCT1nOM+RUjZ46pqhBxhuG3m52dRU5ODgBgy5YtmJ2dVXhE6TU5OYnHjx9j165dmo9FqphjiXhPpZ5jqipE9G6SJGlqVvMXL17A6/WioqICBoMhbp/WYkHvnxbvKTlyTFWFaDUzDGuJ0WjEzMwMAGBmZiZh1Vu1WlxchNfrxZEjR3Dw4EEA2o2FXJhjibR8T8mVY6oqRG+ue7S4uIiBgQHY7Xalh6U4u92Ovr4+AEBfX5/s69esRUIItLe3w2Kx4OTJk9HtWoyFnJhjibR6T8mZY6qbWWF4eBidnZ3RdY9Onz6t9JDS6tKlSxgdHcXc3ByMRiPOnDmDwsJC+Hw+TE1Naeb10rGxMbS0tGDHjh3R1kBZWRl2796tuVjITcs5xvyKkTPHVFeIiIhofVFVa46IiNYfFiIiIlIUCxERESmKhYiIiBTFQkRERIpiISIiIkWxEBERkaL+A1AZp+TS5iHfAAAAAElFTkSuQmCC\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "#plot trajectory\n", - "plt.subplot(2, 2, 1)\n", - "plt.plot(x_bar[0,:],x_bar[1,:])\n", - "plt.plot(np.linspace(0,10,T+1),np.zeros(T+1),\"b-\")\n", - "plt.axis('equal')\n", - "plt.ylabel('y')\n", - "plt.xlabel('x')\n", - "\n", - "plt.subplot(2, 2, 2)\n", - "plt.plot(x_bar[2,:])\n", - "plt.ylabel('theta(t)')\n", - "#plt.xlabel('time')\n", - "\n", - "plt.subplot(2, 2, 3)\n", - "plt.plot(x_bar[3,:])\n", - "plt.ylabel('psi(t)')\n", - "#plt.xlabel('time')\n", - "\n", - "plt.subplot(2, 2, 4)\n", - "plt.plot(x_bar[4,:])\n", - "plt.ylabel('cte(t)')\n", - "\n", - "plt.tight_layout()\n", - "plt.show()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "The results are the same as expected" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "------------------\n", - "\n", - "the kinematics model predictits psi and cte for constant heading references. So, for non-constant paths appropriate functions have to be developed.\n", - "\n", - "-----------------" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## PRELIMINARIES" - ] - }, - { - "cell_type": "code", - "execution_count": 85, - "metadata": {}, - "outputs": [], - "source": [ - "def compute_path_from_wp(start_xp, start_yp, step = 0.1):\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", - " return np.vstack((final_xp,final_yp))\n", - "\n", - "def get_nn_idx(state,path):\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", - " return target_idx\n", - "\n", - "def road_curve(state,track):\n", - " \n", - " #given vehicle pos find lookahead waypoints\n", - " nn_idx=get_nn_idx(state,track)\n", - " LOOKAHED=6\n", - " lk_wp=track[:,nn_idx:nn_idx+LOOKAHED]\n", - "\n", - " #trasform lookahead waypoints to vehicle ref frame\n", - " dx = lk_wp[0,:] - state[0]\n", - " dy = lk_wp[1,:] - state[1]\n", - "\n", - " wp_vehicle_frame = np.vstack(( dx * np.cos(-state[2]) - dy * np.sin(-state[2]),\n", - " dy * np.cos(-state[2]) + dx * np.sin(-state[2]) ))\n", - "\n", - " #fit poly\n", - " return np.polyfit(wp_vehicle_frame[0,:], wp_vehicle_frame[1,:], 3, rcond=None, full=False, w=None, cov=False)\n", - "\n", - "def f(x,coeff):\n", - " return coeff[0]*x**3+coeff[1]*x**2+coeff[2]*x**1+coeff[3]*x**0\n", - "\n", - "def df(x,coeff):\n", - " return 3*coeff[0]*x**2+2*coeff[1]*x+coeff[2]" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "test it" - ] - }, - { - "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= MIN_SPEED]\n", - "constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED]\n", - "\n", - "prob = cp.Problem(cp.Minimize(cost), constr)\n", - "solution = prob.solve(solver=cp.OSQP, verbose=True)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Print Results:" - ] - }, - { - "cell_type": "code", - "execution_count": 112, - "metadata": {}, - "outputs": [ - { - "name": "stderr", - "output_type": "stream", - "text": [ - "No handles with labels found to put in legend.\n" - ] - }, - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "x_mpc=np.array(x.value[0, :]).flatten()\n", - "y_mpc=np.array(x.value[1, :]).flatten()\n", - "theta_mpc=np.array(x.value[2, :]).flatten()\n", - "psi_mpc=np.array(x.value[3, :]).flatten()\n", - "cte_mpc=np.array(x.value[4, :]).flatten()\n", - "v_mpc=np.array(u.value[0, :]).flatten()\n", - "w_mpc=np.array(u.value[1, :]).flatten()\n", - "\n", - "#simulate robot state trajectory for optimized U\n", - "x_traj=predict(x0, np.vstack((v_mpc,w_mpc)))\n", - "\n", - "#plt.figure(figsize=(15,10))\n", - "#plot trajectory\n", - "plt.subplot(2, 2, 1)\n", - "plt.plot(track[0,:],track[1,:],\"b*\")\n", - "plt.plot(x_traj[0,:],x_traj[1,:])\n", - "plt.axis(\"equal\")\n", - "plt.ylabel('y')\n", - "plt.xlabel('x')\n", - "\n", - "#plot v(t)\n", - "plt.subplot(2, 2, 2)\n", - "plt.plot(v_mpc)\n", - "plt.ylabel('v(t)')\n", - "#plt.xlabel('time')\n", - "\n", - "#plot w(t)\n", - "plt.subplot(2, 2, 3)\n", - "plt.plot(w_mpc)\n", - "plt.ylabel('w(t)')\n", - "#plt.xlabel('time')\n", - "\n", - "plt.subplot(2, 2, 4)\n", - "plt.plot(cte_mpc)\n", - "plt.ylabel('cte(t)')\n", - "plt.legend(loc='best')\n", - "\n", - "plt.tight_layout()\n", - "plt.show()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "full track demo" - ] - }, - { - "cell_type": "code", - "execution_count": 93, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "CVXPY Optimization Time: Avrg: 0.1988s Max: 0.2729s Min: 0.1579s\n" - ] - } - ], - "source": [ - "track = compute_path_from_wp([0,3,4,6],\n", - " [0,0,2,1])\n", - "\n", - "sim_duration = 20\n", - "opt_time=[]\n", - "\n", - "x_sim = np.zeros((N,sim_duration))\n", - "u_sim = np.zeros((M,sim_duration-1))\n", - "\n", - "MAX_SPEED = 1.25\n", - "MIN_SPEED = 0.75\n", - "MAX_STEER_SPEED = 1.57/2\n", - "\n", - "# Starting Condition\n", - "x0 = np.zeros(N)\n", - "x0[0] = 0\n", - "x0[1] = -0.25\n", - "x0[2] = np.radians(-0)\n", - "\n", - "K=road_curve(x0,track)\n", - "\n", - "x0[3]=-np.arctan(K[2])\n", - "x0[4]=K[3]\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.00\n", - "\n", - "for sim_time in range(sim_duration-1):\n", - " \n", - " iter_start=time.time()\n", - " \n", - " K=road_curve(x_sim[:,sim_time],track)\n", - " \n", - " # dynamics\n", - " x_bar=np.zeros((N,T+1))\n", - " x_bar[:,0]=x_sim[:,sim_time]\n", - " for t in range (1,T+1):\n", - " xt=x_bar[:,t].reshape(5,1)\n", - " ut=u_bar[:,t-1].reshape(2,1)\n", - "\n", - " A,B,C=get_linear_model(xt,ut)\n", - "\n", - " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", - "\n", - " xt_plus_one[3]=-np.arctan(df(x_bar[0,t],K))\n", - " xt_plus_one[4]=f(x_bar[0,t],K)\n", - " x_bar[:,t]= xt_plus_one\n", - " \n", - " #CVXPY Linear MPC problem statement\n", - " cost = 0\n", - " constr = []\n", - " x = cp.Variable((N, T+1))\n", - " u = cp.Variable((M, T))\n", - " \n", - " for t in range(T):\n", - "\n", - " # Tracking\n", - " cost += 50*cp.sum_squares( x[3, t]) # psi\n", - " cost += 1000*cp.sum_squares( x[4, t]) # cte\n", - "\n", - " # Actuation rate of change\n", - " if t < (T - 1):\n", - " cost += cp.quad_form(u[:, t + 1] - u[:, t], 10*np.eye(M))\n", - " \n", - " # Actuation effort\n", - " cost += cp.quad_form( u[:, t],10*np.eye(M))\n", - " \n", - " # Constrains\n", - " A,B,C=get_linear_model(x_bar[:,t],u_bar[:,t])\n", - " constr += [x[:,t+1] == A*x[:,t] + B*u[:,t] + C.flatten()]\n", - "\n", - " # sums problem objectives and concatenates constraints.\n", - " constr += [x[:,0] == x_sim[:,sim_time]] # starting condition\n", - " constr += [u[0, :] <= MAX_SPEED]\n", - " constr += [u[0, :] >= MIN_SPEED]\n", - " constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED]\n", - " \n", - " # Solve\n", - " prob = cp.Problem(cp.Minimize(cost), constr)\n", - " solution = prob.solve(solver=cp.OSQP, verbose=False)\n", - " \n", - " #retrieved optimized U and assign to u_bar to linearize in next step\n", - " u_bar=np.vstack((np.array(u.value[0, :]).flatten(),\n", - " (np.array(u.value[1, :]).flatten())))\n", - " \n", - " u_sim[:,sim_time] = u_bar[:,0]\n", - " \n", - " # Measure elpased time to get results from cvxpy\n", - " opt_time.append(time.time()-iter_start)\n", - " \n", - " # move simulation to t+1\n", - " tspan = [0,dt]\n", - " x_sim[:,sim_time+1] = odeint(kinematics_model,\n", - " x_sim[:,sim_time],\n", - " tspan,\n", - " args=(u_bar[:,1],))[1]\n", - " \n", - "print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n", - " np.max(opt_time),\n", - " np.min(opt_time))) " - ] - }, - { - "cell_type": "code", - "execution_count": 92, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAABDAAAALICAYAAACJhQBYAAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAADh0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uMy4xLjMsIGh0dHA6Ly9tYXRwbG90bGliLm9yZy+AADFEAAAgAElEQVR4nOzde3hU1b3/8c+aDAFCuCXDxQQRuQqxSBAEURQlosdai1RROdVa68/DD6uHwvERPfZyjtrDqQb5WaXao9VWe8G2ap9j1doUEQuGi0lQEpSAKHInCWAgCSSZ9fsDSYm5TZKZWXtm3q/n4WFm9p7ZH/eaicw3a323sdZaAQAAAAAAeJjPdQAAAAAAAIC2UMAAAAAAAACeRwEDAAAAAAB4HgUMAAAAAADgeRQwAAAAAACA51HAAAAAAAAAnud3HaAzdu/eHfVjBgIBlZWVRf24aBlj4i2Mh7cwHt7DmHgL4+E9rsYkIyMj6seMpPb+O9nLnwWytZ9Xc0lk6wiv5pIil62ln8nMwAAAAAAAAJ5HAQMAAAAAAHgeBQwAAAAAAOB5FDAAAAAAAIDnUcAAAAAAAACeRwEDAAAAAAB4HgUMAAAAAADgeRQwAAAAAACA51HAAAAAAAAAnkcBAwAAAAAAeB4FDAAAAAAA4HkUMAAAAAAAgOf5XQcAAAAAgEQSzF8p+8oLkrUdfxFjWtx0wOdTMBjs+GtHkLNsIZzrA0k+Beu9d95OnLN6hwlaea+1cc7MVdfLN3VG2JJQwAAAAACAKLG1tbIv/UrqkiwzfHQHX6T1L+PJ3brpWE1Nx147wpxma6XoI0nJ3brqWM2xKIUJXXK3rjp2zFGuNuo+bZ0z0zcQ1jieKmAEg0EtWrRIaWlpWrRokes4AAAAABBW9t0V0sEy+eb/h0xWdkSO0TsQUFlZWUReu7PI1n5ezSVFP5unemC89tpryszMdB0DAAAAAMLO1tfLvvFHacgIacw413GAmOOZAkZ5ebkKCgo0ffp011EAAAAAIOzs+nekA3vl++p1Mm0sZwDQlGeWkDz33HP65je/qerq6hb3ycvLU15eniRp8eLFCgTCu54mFH6/38lx0TLGxFsYD29hPLyHMfEWxsN7GBPEKxsMyr72eynzDGnsea7jADHJEwWM9957T71799bQoUNVXFzc4n45OTnKyclpuO9iHVDAw+uPEhVj4i2Mh7cwHt7DmHgL4+E9rsYkIyMj6sdEginKl/Z8JnPbQhmfZybCAzHFEwWMjz76SBs2bFBhYaGOHz+u6upqPfbYY7rrrrtcRwMAAACATrHWKvjn30v9M2QmXug6DhCzPFHAmDNnjubMmSNJKi4u1v/+7/9SvAAAAAAQH4oLpB3bZL51p4wvyXUaIGYxdwkAAAAAIuTE7IsXpbSAzORpruMAMc0TMzBOlZWVpaysLNcxAAAAAKDzthRLWzfL3Hi7jL+L6zRATGMGBgAAAABESPC1F6VefWQuvMx1FCDmUcAAAAAAgAiw27dIJUUyM2bKJHd1HQeIeRQwAAAAACACgn9+UUpJlbn4CtdRgLhAAQMAAAAAwszu/ETauE5m+tdkuqW4jgPEBQoYAAAAABBm9rXfS926y0y/ynUUIG5QwAAAAACAMLJ7d8luWC0z7UqZHj1dxwHiBgUMAAAAAAgj+8YfJL9f5rKrXUcB4goFDAAAAAAIE1u+XzZ/pczUGTK9+rqOA8QVChgAAAAAECb2Ly9JMjKXX+M6ChB3KGAAAAAAQBjYwwdl3/mrzJRLZdL6uY4DxB0KGAAAAAAQBvbNV6T6epkrZrmOAsQlChgAAAAA0En2yOeyb78uM3GqTP8M13GAuEQBAwAAAAA6yf7tVelYjcyV17qOAsQtChgAAAAA0Am2ukp2xf9K2ZNlMs9wHQeIWxQwAAAAAKAT7MrXpKqj8n11tusoQFyjgAEAAAAAHWSPHZP965+krGyZM4a7jgPENb/rAAAAAEAiWrZsmQoKCtS7d2/l5uY22f7OO+/oT3/6k6y16t69u2677TYNGTIk+kHRKvv3N6XKw/JdyewLINKYgQEAAAA4MG3aNN13330tbu/fv79+9KMfKTc3V9/4xjf085//PIrpEApbe1z2jZekkVkyI7NcxwHiHgUMAAAAwIExY8YoNTW1xe2jRo1q2D5ixAiVl5dHKxpCVP3W69KhcmZfAFHCEhIAAADA41asWKHs7OwWt+fl5SkvL0+StHjxYgUCgXa9vt/vb/dzosWr2Wx9ncpffkH+4Wcp7aIcGWNcR2rg1XMmka0jvJpLin42ChgAAACAh23atElvvfWW/vM//7PFfXJycpSTk9Nwv6ysrF3HCAQC7X5OtHg1WzB/pezeXfLNu89zs2O8es4ksnWEV3NJkcuWkZHR7OMsIQEAAAA86tNPP9VTTz2lu+++Wz179nQdB1+w1sq+/gf5Bw+VzjnPdRwgYVDAAAAAADyorKxMjzzyiL773e+2+NtIOFK2T9q9Q90vnynj4ysVEC0sIQEAAAAcWLp0qUpKSlRZWam5c+dq9uzZqqurkyTNmDFDf/jDH3TkyBE9/fTTkqSkpCQtXrzYZWR8wZYWS5K6ZLXclwRA+FHAAAAAAByYP39+q9vnzp2ruXPnRikN2qW0REpJlf/0M6WKCtdpgITBfCcAAAAAaAdbWiINH83yESDK+MQBAAAAQIjs5welfbtkRoxxHQVIOBQwAAAAACBUpZslSWZEluMgQOKhgAEAAAAAIbKlxVJysnTGMNdRgIRDAQMAAAAAQmRLS6QzR8n4u7iOAiQcChgAAAAAEAJbXSV9tp3lI4AjFDAAAAAAIBTbNks2SANPwBEKGAAAAAAQAltaIvl80tBRrqMACYkCBgAAAACEwJYWS4OHyXTr7joKkJAoYAAAAABAG2xtrbS9lOUjgEMUMAAAAACgLZ+USnW1NPAEHKKAAQAAAABtsKXFJ24MZwYG4AoFDAAAAABogy0tkU47XaZnL9dRgIRFAQMAAAAAWmGD9dK2zSwfARyjgAEAAAAArdn5iVRdJdHAE3CKAgYAAAAAtMKWlkgSMzAAxyhgAAAAAEArbGmxlNZPJr2f6yhAQqOAAQAAAAAtsNZKpSUyLB8BnKOAAQAAAAAt2b9H+vyQNJLlI4BrFDAAAAAAoAW2tFgS/S8AL6CAAQAAAAAtKS2RUntJAwe5TgIkPAoYAAAAANACW1osDR8jY4zrKEDCo4ABAAAAAM2wh8qlA3tp4Al4BAUMAAAAAGiGLS2RRP8LwCsoYAAAAABAc0qLpa7dpMFDXScBIAoYAAAAANAsW1oiDR0lk5TkOgoAUcAAAAAAgCZs1RFp16cyI1k+AngFBQwAAAAA+LKtmyVr6X8BeAgFDAAAAAD4EltaIiX5pTNHuo4C4AsUMAAAAADgS2xpsTRkuExyV9dRAHyBAgYAAAAAnMIePyZ9slVm+BjXUQCcggIGAAAAAJxq+xapvo7+F4DHUMAAAAAAgFPY0mLJGGn4aNdRAJyCAgYAAAAAnMKWlkiZZ8j0SHUdBcApKGAAAAAAwBdsfb207SOZEfS/ALyGAgYAAAAAnPTZx9Kxaon+F4DnUMAAAAAAgC/Y0hJJYgYG4EEUMAAAAADgC7a0WOo3UKZPuusoAL6EAgYAAAAASLLWSls3ywxn9gXgRRQwAAAAAECS9u6SKg9LLB8BPIkCBgAAAABIsqWbJEmGBp6AJ1HAAAAAAABJKi2RevWRBmS4TgKgGRQwAAAAAEBfXIFkxBgZY1xHAdAMChgAAAAAEp6tOCCV72f5COBhFDAAAAAAJDxbWiJJMjTwBDyLAgYAAAAAlBZL3VOkQUNcJwHQAgoYAAAAABKeLS2Rhp0l40tyHQVACyhgAAAAAEho9sjn0u4dMsNZPgJ4md91AAAAACARLVu2TAUFBerdu7dyc3ObbN+1a5eWLVum7du364YbbtDVV1/tIGWC2Hqy/wUNPAEvYwYGAAAA4MC0adN03333tbg9NTVV3/72t/W1r30tiqkSky0tkfxdpDNHuI4CoBUUMAAAAAAHxowZo9TU1Ba39+7dW8OHD1dSEj0ZIs2WlkhnjpDpkuw6CoBWUMAAAAAAkLDssRppxzaWjwAxgB4YAAAAQIzLy8tTXl6eJGnx4sUKBALter7f72/3c6Il0tmOvb9Bh+rr1fvc89U1Ts6bV3NJZOsIr+aSop+NAgYAAAAQ43JycpSTk9Nwv6ysrF3PDwQC7X5OtEQ6W3DDGsn49Hm/DJk4OW9ezSWRrSO8mkuKXLaMjIxmH2cJCQAAAICEZUtLpNOHyHRPcR0FQBuYgQEAAAA4sHTpUpWUlKiyslJz587V7NmzVVdXJ0maMWOGDh06pEWLFqm6ulrGGL322mtasmSJUlL4oh0utq5O+vgjmakzXEcBEAIKGAAAAIAD8+fPb3V7nz599OSTT0YpTYLasU06fowGnkCMYAkJAAAAgIRkS4tP3Bgx2m0QACGhgAEAAAAgIdnSEmlApkyvvq6jAAgBBQwAAAAACccGg1JpicyIMa6jAAgRBQwAAAAAiWfPZ1LVEYkCBhAzKGAAAAAASDh2y4n+FzTwBGIHBQwAAAAACceWFEqBASf+AIgJFDAAAAAAJBRbVyttfl8mK1vGGNdxAISIAgYAAACAxLLtI+lYtczZ410nAdAOFDAAAAAAJBRbXCAlJUmjxrqOAqAd/K4DSNLx48f1wx/+UHV1daqvr9fkyZM1e/Zs17EAAAAAxCFbXCANO0ume4rrKADawRMFjC5duuiHP/yhunXrprq6Ov3gBz/QuHHjNHLkSNfRAAAAAMQR+/lBacfHMtfc5DoKgHbyxBISY4y6desmSaqvr1d9fT3NdAAAAACEnS0ukiSZLPpfALHGEzMwJCkYDOqee+7R3r17dfnll2vEiBFN9snLy1NeXp4kafHixQoEAtGOKb/f7+S4aBlj4i2Mh7cwHt7DmHgL4+E9jAkirrhA6tlbOv1M10kAtJNnChg+n08PP/ywjh49qkceeUQ7duzQ4MGDG+2Tk5OjnJychvtlZWXRjqlAIODkuGgZY+ItjIe3MB7ew5h4C+PhPa7GJCMjI+rHRPTZYFC2pOjE5VN9npiMDqAdPPep7dGjh7KyslRUVOQ6CgAAAIB48tnHUuVhKSvbdRIAHeCJAsbnn3+uo0ePSjpxRZL3339fmZmZjlMBAAAAiCd2U4EkyYyhgAHEIk8sITl48KCeeOIJBYNBWWt1/vnn69xzz3UdCwAAAEAcscUF0uBhMr36uI4CoAM8UcA444wz9JOf/MR1DAAAAABxylZXSR9/JHP5LNdRAHSQJ5aQAAAAAEBEffi+VF8vQ/8LIGZRwAAAAAAQ9+ymAqlbd2noWa6jAOggChgAAAAA4pq19kT/i7POkfF7YhU9gA6ggAEAAAAgvu3bJZXvZ/kIEOMoYAAAAACIa7a4UJIoYAAxjgIGAAAAgLhmNxVIAzJl+g10HQVAJ1DAAAAAABC3bO1xacsHzL4A4gAFDAAAAADxq7REOn5c5uzxrpMA6CQKGAAAAADili0ukPx+aeTZrqMA6CSuIQQAAACE6PHHHw9pP7/fr7lz50Y4DUJhiwulEVkyXbu5jgKgk5iBAQAAAIRozZo1GjBgQJt/3n33XddRIclWlEm7PpXJYvkIEA+YgQEAAACEKD09Xdddd12b+61evToKadAWW8LlU4F4wgwMAAAAIEQ//elPQ9pv6dKlEU6CkBQXSn3SpMwzXCcBEAYUMAAAAIAw2Ldvn/bv3+86Br5gg/WyJUUyWdkyxriOAyAMKGAAAAAAHbB06VJ99NFHkqS33npLCxYs0MKFC7VixQrHySBJ2l4qVR2Rss51nQRAmFDAAAAAADpg06ZNGjZsmCTp1Vdf1fe//339+Mc/1iuvvOI4GaQvLp9qfDJjznEdBUCY0MQTAAAA6IC6ujr5/X5VVFToyJEjOuussyRJhw8fdpwM0heXTx0yXKZHT9dRAIQJBQwAAACgA4YMGaKXX35ZBw4c0PjxJy7TWVFRoe7duztOBnu0UtpeKnPVbNdRAIQRS0gAAACADpg7d6527Nih48eP64YbbpAkbdmyRRdeeKHjZLAlGyUblMka7zoKgDBiBgYAAADQDn/729+UnZ2tgQMH6l//9V8bbZs8ebImT57sKBkaFBdIKanSkBGukwAIIwoYAAAAQDts27ZNf/zjH9WjRw+NHz9e2dnZGjVqFJfq9AhrrWxxgczoc2SSklzHARBGFDAAAACAdrj99tslSTt27FBBQYF++9vfavfu3crKytL48eM1btw49erVy3HKBLZ7h3SoQsrKdp0EQJhRwAAAAAA6YPDgwRo8eLBmzpypqqoqFRUVqbCwUC+88IL69eun6667TuPGjXMdM+HYTQWSRP8LIA5RwAAAAAA6KSUlRVOmTNGUKVMkSVu3bnWcKHHZ4gIpY7BMWsB1FABhRgEDAAAA6KDNmzdr+/btqqmpafT4rFmzHCVKbPZYjVRaLHPpVa6jAIgAChgAAABAB/ziF7/Qu+++q7POOkvJyckNj9PM06Etm6S6Ohn6XwBxiQIGAAAA0AHvvPOOcnNzlZaW5joKvmCLC6XkZGlElusoACLA5zoAAAAAEIsCgYC6dOniOgZOYTcVSCO/ItMlue2dAcQcZmAAAAAAHTB37lw99dRTuuCCC9S7d+9G28aMGeMoVeKyZfukfbtkpv2T6ygAIoQCBgAAANABH3/8sQoLC7V58+ZGPTAk6Wc/+5mjVInLFhdKkszZXD4ViFcUMAAAAIAO+O1vf6t77rlHY8eOdR0F+mL5SHp/aUCm6ygAIoQCBgAAANABXbt27dRSkWXLlqmgoEC9e/dWbm5uk+3WWj377LMqLCxU165dNW/ePA0dOrQzkeOWrauTPtwoc95FXAUGiGM08QQAAAA64Prrr9dzzz2nQ4cOKRgMNvoTimnTpum+++5rcXthYaH27t2rxx57TLfffruefvrpcEWPPx9/KNVUy2SxfASIZ8zAAAAAADrgZJ+Lv/71r022LV++vM3njxkzRvv3729x+4YNG3TRRSdmFIwcOVJHjx7VwYMH1bdv346HjlO2uFDy+aSzWM4DxDMKGAAAAEAHPP744xF9/YqKCgUCgYb76enpqqiooIDRDFtcKA07Syalh+soACKIAgYAAADQAf369XMdoUFeXp7y8vIkSYsXL25U+AiF3+9v93Oipa1swUMVOvDpVvWYc7tSo/zf4NXz5tVcEtk6wqu5pOhno4ABAAAAhOh3v/udbrjhhjb3e/HFFzV79uxOHSstLU1lZWUN98vLy5WWltbsvjk5OcrJyWm4f+rzQhEIBNr9nGhpK1swf6UkqfrMUaqJ8n+DV8+bV3NJZOsIr+aSIpctIyOj2cdp4gkAAACE6LXXXtP+/fu1b9++Vv+8/vrrnT7WhAkTtGrVKllrtWXLFqWkpLB8pDnFBVJqL2nwMNdJAEQYMzAAAACAEB07dkx33nlnm/t16dKlzX2WLl2qkpISVVZWau7cuZo9e7bq6uokSTNmzFB2drYKCgp01113KTk5WfPmzet0/nhjg0HZ4kKZMdkyPn43C8Q7ChgAAABAiEK5ukio5s+f3+p2Y4xuu+22sB0vLn22Xao8LJ3N5VOBRECZEgAAAEBMssUFkiSTNc5xEgDRQAEDAAAAQEyyxYXS6WfK9KI3CJAIKGAAAAAAiDn2aKW0tUTm7HNdRwEQJRQwAAAAAMQcu3G9FAzKZJ/vOgqAKKGAAQAAAHRQTU2NysvLVVNT4zpKwrFF+VKfdGnIcNdRAEQJVyEBAAAA2mHHjh3Ky8tTQUGBDhw40PB4//79NW7cOF122WUaPHiww4Txzx47JhUXyFyQI2OM6zgAooQCBgAAABCipUuXaufOnZoyZYruvPNOZWZmqnv37qqurtauXbtUUlKixx57TIMGDWrzMqnohJJC6fhxlo8ACYYCBgAAABCiqVOn6txzmzaNTE1N1ahRozRq1Chdc801eu+99xykSxy2MF9KSZVGZLmOAiCK6IEBAAAAhOjU4kVpaWmz+2zdurXZIgfCw9bXy76/XmbsRBk/v48FEgkFDAAAAKADHnzwwWYff+ihh6KcJMFs2SQdrZTJnuw6CYAoo2QJAAAAtEMwGJQkWWsb/py0b98+JSUluYqWEGzRWqlLspSV7ToKgCijgAEAAAC0w4033thw+4Ybbmi0zefz6Zprrol2pIRhrT1x+dSsbJmu3VzHARBlFDAAAACAdnj88cdlrdWPfvQj/cd//EfD48YY9erVS8nJyQ7Txbkd26SKMpmr/9l1EgAOUMAAAAAA2qFfv36SpGXLljlOknhsQb5kfDLnTHQdBYADNPEEAAAAQvTLX/5Shw4danWfQ4cO6Ze//GWUEiUWW/iuNDJLJrWX6ygAHGAGBgAAABCijIwM3XvvvRo0aJBGjx6tjIwMde/eXdXV1dqzZ49KSkq0e/duzZo1y3XUuGP37pL2fCZz8RWuowBwhAIGAAAAEKLLLrtMl1xyiTZs2KDCwkKtX79eVVVV6tGjhwYPHqzLLrtM5557LlciiQBblC9JMuO4fCqQqChgAAAAAO3g9/s1efJkTZ7MF+loskVrpcHDZNL7uY4CwBF6YAAAAAAd8Nxzz2nr1q2uYyQEe6hC2vahTDZFIyCRMQMDAAAA6ABrrR5++GF17dpVF154oS688EJlZGS4jhWXbNFaSaKAASQ4ChgAAABAB3z729/Wt771LW3atEl///vf9e///u/q37+/pk6dqquuusp1vLhii/Kl/qdJGYNdRwHgEEtIAAAAgA7y+XwaO3as5s2bp9zcXPXs2VPPP/+861hxJXj0iPThBzLZk2WMcR0HgEPMwAAAAAA6qKamRuvWrdPq1atVUlKiMWPG6I477nAdK64cK1gj1ddx9REAFDAAAACAjliyZIkKCws1dOhQXXDBBbrjjjvUq1cv17HizrH8VVKvPtLQUa6jAHCMAgYAAADQAcOGDdPNN9+sQCDgOkrcsrXHdbwgX+a8qTI+Vr8DiY4CBgAAANABX//6111HiH+bN8rWVMnH1UcAiCaeAAAAADzKFubLpPSQzhrrOgoAD6CAAQAAAMBzbLBeduM6JY8/X8bfxXUcAB5AAQMAAACA92z9UKo8rG6TL3adBIBHUMAAAAAA4Dm2MF/y+5VM/wsAX6CAAQAAAMBTrLWyRfnS6HHypfRwHQeAR1DAAAAAAOAtOz+RyvbJMPsCwCkoYAAAAADwFFuYLxkjc85E11EAeAgFDAAAAACeYgvzpWGjZXr1dR0FgIdQwAAAAADgGfbAXmnndpnsSa6jAPAYChgAAAAAPMMWrZUkmXH0vwDQGAUMAAAAAJ5hC9+VMs+Q6X+a6ygAPIYCBgAAAABPsJ8fkrZ+KJN9vusoADyIAgYAAAAAT7Ab10k2yOVTATSLAgYAAAAAT7CF+VJ6f+n0M11HAeBBFDAAAAAAOGdrqqTNG2WyJ8sY4zoOAA+igAEAAADAvU0FUl0tVx8B0CIKGAAAAACcs4VrpdRe0ojRrqMA8CgKGAAAAACcsnW1sh9skDnnPBlfkus4ADyKAgYAAAAAtz78QKo+ytVHALSKAgYAAAAAp2xRvtS1mzT6HNdRAHgYBQwAAAAAzthgULZonZQ1Xia5q+s4ADyMAgYAAAAAd7ZvkQ5XsHwEQJsoYAAAAABwxhbmS0lJMmMnuI4CwOP8rgMAAAAAiaioqEjPPvusgsGgpk+frpkzZzbafuDAAf3sZz/T559/rtTUVN15551KT093lDYyrLUnChijviKTkuo6DgCPYwYGAAAAEGXBYFDPPPOM7rvvPj366KNavXq1du7c2Wif559/XhdddJEeeeQRXXvttfrNb37jKG0E7flM2r+b5SMAQkIBAwAAAIiyrVu3auDAgRowYID8fr+mTJmi9evXN9pn586dOvvssyVJWVlZ2rBhg4uoEWXz35KMT2bcJNdRAMQATywhKSsr0xNPPKFDhw7JGKOcnBxdeeWVrmMBABB2OTl+/e53rlMAcK2ioqLRcpD09HSVlpY22ueMM87QunXrdOWVV2rdunWqrq5WZWWlevbs2eT18vLylJeXJ0lavHixAoFAu/L4/f52P6ezbG2tytasUPKEKeozfFSL+7nIFiqvZvNqLolsHeHVXFL0s3migJGUlKSbbrpJQ4cOVXV1tRYtWqSxY8dq0KBBrqMBABBW77zD5EcAobnpppv0i1/8QitXrtTo0aOVlpYmn6/5nyE5OTnKyclpuF9WVtauYwUCgXY/p7Pshr8rePigas+/tNVju8gWKq9m82ouiWwd4dVcUuSyZWRkNPu4JwoYffv2Vd++fSVJ3bt3V2ZmpioqKihgAAAAIC6lpaWpvLy84X55ebnS0tKa7PNv//ZvkqSamhqtXbtWPXr0iGrOSAqu+ouU1k/KynYdBUCM8EQB41T79+/X9u3bNXz48CbbOjs1Lhy8PH0nUTEm3sJ4eAvj4Q05Of5GMy8yM0/8VmHq1KDy8upcxYL4jHhRoozJsGHDtGfPHu3fv19paWlas2aN7rrrrkb7nLz6iM/n08svv6xLLrnEUdrws/t3S5s3ynx9jowvyXUcADHCUwWMmpoa5ebm6pZbblFKSkqT7Z2dGhcOXp6+k6gYE29hPLyF8fCGU3teZGZmaNeu3Q33GR63+Ix4j6sxaWm6cqQkJSXp1ltv1UMPPaRgMKhLLrlEp59+upYvX65hw4ZpwoQJKikp0W9+8xsZYzR69Gh95zvfiWrGSLKr3pR8PpkLL3MdBUAM8UwBo66uTrm5uZo6daomTaILMQAgceXm9tTChZWuYwCIsPHjx2v8+PGNHrv++usbbk+ePFmTJ8ff5UVtXa3smr9JY8+T6ZPe9hMA4Aue6CRmrdWTTz6pzMxMXXXVVa7jAAAQMVOnBtvcZ8mSplcYAIB4YQvzpcrD8l18uesoAGKMJ2ZgfPTRR1q1apUGDx6su+++W5J04403NqlIAwAQ6/Ly6lg2AiCh2bffkNL7S2No3gmgfTxRwDjrrLP04osvuo4BAIAzubk9G828ONnoczUVhZAAACAASURBVMGCSpaTAIgbdu8u6aMPZGZ+U6aFS8ICQEv4qQEAQITk5oa+FGThwkrt2rW7ocHnydutFS/a8/oA4AX2nTelpCSZC3La3hkAvoQCBgAAERLpXhb0ygAQS2ztF807zzlPpk+a6zgAYhAFDAAAPGbBApaMAIg/tmCNdORz+S66wnUUADGKAgYAAGGUm9tTmZkZDT0sTt5u73KSSL4+ALhgV/1F6jdQGn2O6ygAYpQnmngCABAvFi78R9PNzMyMhp4WsfL6ABAJds9OacsmmVk307wTQIfx0wMAgDjGzAwAXmDf+cuJ5p1TpruOAiCGUcAAACBCIt3LIpTXp9EnANds7XHZNSukcZNkevd1HQdADKOAAQBAhLTWyyIWXh8AwsG+t0Y6WknzTgCdRgEDAIA4Q6NPAF5iV71xonnnWWNdRwEQ42jiCQBAnKHRJwCvsLt3SKUlMt/4Fs07AXQaP0UAAAiDWJ/dEOv5AXiTfedNKclP804AYUEBAwCAMPBqs8xQG4l6NT+A2GWPH5Nds0Ime7JMrz6u4wCIAxQwAACIYzT6BOCKfW+NVHVE5qLLXUcBECcoYAAA0EGx3iwz1vMD8Da76g2pfwbNOwGEDU08AQDooFhvlhnr+QF4l921Q9q6Webab8sY4zoOgDjBDAwAABAyZmcACIVd9Ybkp3kngPCigAEAQBiE2izTq2j2CSBc7LFjsvlvyYyfItOzl+s4AOIIBQwAAMIg1ptlxnp+AN5h3/u7VHWU5p0Awo4CBgAAaBXNPgG0h131F2lgpjTybNdRAMQZChgAALRTon1xX7iwUrt27W5o8nnydkuzNhLt/AD4B7vzE2nbhzJTL6d5J4Cwo4ABAEA70QeidZwfIHGdaN7ZRWbKpa6jAIhDFDAAAEDIYr1ZKYDIOdG8c6XMuVNkUmneCSD8KGAAABAC+kCc0NqyEc4PkNjshnek6iqZi65wHQVAnPK7DgAAQCxYuLCy4ct7ZmZGQz8InMD5AWDffkM67XRpxBjXUQDEKWZgAAAAJ5idAcQP+9l2afsWmYtm0LwTQMRQwAAAoJ3oA9G6UM8PzT6B+NHQvPN8mncCiBwKGAAAtFNLfSBwAucHSCy2pvpE884JF8r0oDAJIHIoYAAAgKih2ScQf+z6d6SaapmLL3cdBUCco4knAACIGpp9AvHHrs6TMgZLw0a7jgIgzjEDAwCANjA7wB3OPeBt9lC5tO1DmfMuonkngIijgAEAQBtoNhkZoTT75NwD3maL1kmSTPZkx0kAJAIKGAAAwAmafQKxzxblS/1Pk0473XUUAAmAAgYAAM2g2aQ7nHsgNtiqo9KHH8iMm8zyEQBRQRNPAACaQbNJdzj3QGywxQVSfZ1M9iTXUQAkCGZgAACAmMfsDMCBwnypZ29p6CjXSQAkCAoYAAC0IZRmk4iMUM89zT6B6LK1tbIfbJAZN0nGl+Q6DoAEQQEDAIA20GzSHc494FEffSDVVMuMY/kIgOihgAEAAGISzT4Bd2xRvtS1mzT6HNdRACQQmngCAICYRLNPwA0bDMoWrZOyxst0SXYdB0ACYQYGAACn4Lf38YuxBcLkk1LpcAVXHwEQdRQwAAA4Bc0gY1MozT4ZWyA8bNFayeeT+cpE11EAJBgKGAAAIObR7BOIHlu0Vhr1FZkeqa6jAEgwFDAAAAmPZpDxi7EFwsvu3Snt+YyrjwBwgiaeAICERzPI+NWRsc3N7cmMDqAFtmitJFHAAOAEMzAAAABOQa8MoGW2aK10xnCZtH6uowBIQBQwAAA4RSjNIBGbGFugc+yhCunjj2TGnec6CoAExRISAABOwdKB+NXa2Obm9mw08+Jkz4wFCyp5TyBiioqK9OyzzyoYDGr69OmaOXNmo+1lZWV64okndPToUQWDQc2ZM0fjx493lFay76+TrJUZN9lZBgCJjQIGAABIePRBQbQFg0E988wzuv/++5Wenq57771XEyZM0KBBgxr2+eMf/6jzzz9fM2bM0M6dO/Vf//VfbgsYReukfgOlzDOcZQCQ2FhCAgBIWFyJAp3B+wedsXXrVg0cOFADBgyQ3+/XlClTtH79+kb7GGNUVVUlSaqqqlLfvn1dRJUk2ZoqaXORzLhJMsY4ywEgsTEDAwCQsJYs4WoTaCrUXhm8f9AZFRUVSk9Pb7ifnp6u0tLSRvtcd911evDBB/XGG2/o2LFj+v73v9/i6+Xl5SkvL0+StHjxYgUCgXbl8fv9rT6nZvUKHa6rU59plyu5na/dWW1lc8mr2byaSyJbR3g1lxT9bBQwAAAATkFRAl6xevVqTZs2TV/72te0ZcsW/fSnP1Vubq58vqaTqHNycpSTk9Nwv6ysrF3HCgQCrT4nuOqvUmovHQ6cJtPO1+6strK55NVsXs0lka0jvJpLily2jIyMZh9nCQkAIKHk5vZUZmZGQ5PGk7dZDoBQ8P5BuKSlpam8vLzhfnl5udLS0hrts2LFCp1//vmSpJEjR6q2tlaVldEvsNm6WtkPNsicc56MLynqxweAkyhgAAASysKFldq1a3dDk8aTt/mtO0LB+wfhMmzYMO3Zs0f79+9XXV2d1qxZowkTJjTaJxAIaNOmTZKknTt3qra2Vr169Yp+2C2bpOqjMuMmRf/YAHAKlpAAAABESG4ufTLQvKSkJN1666166KGHFAwGdckll+j000/X8uXLNWzYME2YMEE333yznnrqKf35z3+WJM2bN89JA01btFZK7iqNGRf1YwPAqShgAAASVqjNGoHmhPL+odEnWjN+/Pgml0W9/vrrG24PGjRIDzzwQLRjNWKtlS1cK2VlyyR3dZoFAFhCAgBIWHyxRGfw/kFC+HSrdKhcZtxk10kAgAIGAABAONHoE/HEFq6VfD6ZsRPa3hkAIowlJAAAAGG0cGFlw+yMzMyMhoafQCyyRfnSiCyZVAfNQwHgS5iBAQBICPz2G17G+xNeZPftlnbvkMlm+QgAb6CAAQBICEuW8AUR0Rdqo1jen/AiW7RWkrh8KgDPoIABAAAQITT6RCyzRWul08+USe/vOgoASKKAAQCIYzRThJfx/oSX2c8PSds2c/URAJ5CE08AQNyimSK8rL3vz9zcnszoQNTYjeska+l/AcBTmIEBAAAQA+iTgWiyRWul9P7SoCGuowBAAwoYAICEEGozRcAF3p/wEltTLZUUyWRPljHGdRwAaEABAwCQEJh6Dy9r6f1Jnww4UVwo1dXS/wKA59ADAwAAwKPo4wIXbFG+1KOnNHy06ygA0AgzMAAAcYnfUCNR8d5HZ9i6Otn3N8iMnSiTlOQ6DgA0QgEDABCXaHiIeBNqnwze++iU0mKp6ghXHwHgSRQwAAAAYgB9XBANtmitlJwsjcl2HQUAmqCAAQCIGzQ8RKLivY9wsNae6H8xJluma1fXcQCgCZp4AgDiBg0Pkah47yMsdnwsVZTJXP3PrpMAQLOYgQEAAJBgmJmB5tiifMn4ZMZOdB0FAJpFAQMAEJdCbXgIxJtQ3vs0+kRzbGG+NGK0TM9erqMAQLMoYAAA4hIND5GoeO+jI+r27pJ2fSozjquPAPAuChgAAAAJgEafaM2xde9Iksy4SY6TAEDLaOIJAACQAGj0idYcW7tKGjREpt9A11EAoEXMwAAAxDx+gwxEBp+txGArD6v2w/dZPgLA8yhgAABiHg0JgfYJtcktn60EseNjyZckk83yEQDexhISAACABEOjT5zKZGWr369eU/mRKtdRAKBVzMAAAMQkGhICkcFnKzH5uveQMcZ1DABoFTMwAAAxiYaEQGTw2QIAeBUzMAAAANApzM4AAEQDBQwAQMwLtSEhgPah2ScAwEsoYAAAYl5HGxLawnwFX/u9bG1tmBMB8YFmnwAAL6GAAQBISDYYVPDl52XzV0pJSa7jADGHZp8AgGijgAEAiClh+3JU+K605zOZq66X8fG/Q6C9Fi6s1K5duxuafJ683dKsDQobAIDO4l9sAICYEo619jYYVPDV5dLATJkJF4QhFYC20CcDANBZFDAAAIln4zpp5ycyV86W8bF8BOgsGukCAKKBAgYAwPPCudbeWqvgq7+T+g2UOe+icEcFElJry0bokwEACBe/6wAAALRl4cLKhi9ImZkZDWvuO+SDDdKOj2VuuUuG5p1ARIX1swsASHiemYGxbNky3XbbbVq4cKHrKACAOHVi9sVyKb2/zKRpruMAaMYDD1BYBAA0zzMFjGnTpum+++5zHQMA4HGdWmtfXCht3yJz5bUyfiYhAtEU6mf3wQcpYAAAmueZf72NGTNG+/fvdx0DAOBxLa21b0tD74u0gMz508OcCkBbOvrZRcdkZGRE5TnRQrb282ouiWwd4dVcUnSzeaaAEYq8vDzl5eVJkhYvXqxAIBD1DH6/38lx0TLGxFsYD29hPP7h+PsbdHDbh+p5+0KlnHaasxyMibcwHt7wwANJjWZenGz6ef/99fr+9+tdxUooixYt0uLFi13HaBbZ2s+ruSSydYRXc0nRzxZTBYycnBzl5OQ03C8rK4t6hkAg4OS4aBlj4i2Mh7cwHv9Q/+ufS33SdHTc+apyeE4YE29hPLzh//7fE3+kps0+ozU8Xv7tJgDgBM/0wAAA4MvCdalF+9EmacsmmctnyXRJDstrAgAAILooYAAAPGvJkvAUMIJ/Xi716iMz9fKwvB6AyLn/fpaMuHDqLGevIVv7eTWXRLaO8GouKfrZjLXWRvWILVi6dKlKSkpUWVmp3r17a/bs2br00ktbfc7u3dG/ljhTTb2HMfEWxsNbYn08vjyVvCPs1s0K/vc9Mtd9W74Z14QpWcfF+pjEG8bDe1yNCUtIAMD7PNMDY/78+a4jAAA8IDe3Z6OZFyeb+S1YUNmhqxgE/7xcSu0lc/E/hS0jAAAAos8zBQwAAKQTl1o8Wajo7AwMu32LtKlAZta3ZLp2C1dEAAAAOEABAwAQt4KvLpd69JS5hNkXACBJRUVFevbZZxUMBjV9+nTNnDmz0fba2lo9/vjj+vjjj9WzZ0/Nnz9f/fv3j3iusrIyPfHEEzp06JCMMcrJydGVV17ZaJ/i4mL95Cc/acgzadIkXXvttRHPJkl33HGHunXrJp/Pp6SkpCaXjbTW6tlnn1VhYaG6du2qefPmaejQoRHNtHv3bj366KMN9/fv36/Zs2frq1/9asNj0Txny5YtU0FBgXr37q3c3FxJ0pEjR/Too4/qwIED6tevn773ve8pNTW1yXNXrlypl156SZI0a9YsTZs2LeLZnn/+eb333nvy+/0aMGCA5s2bpx49ejR5bltjH+5cL774ov72t7+pV69ekqQbb7xR48ePb/Lctj7Lkcj26KOPNrRxqKqqUkpKih5++OEmz43kOaOAAQDwrAUL2r9k5CS7Y5v0/nqZr/+zTLeUMKYCgNgUDAb1zDPP6P7771d6erruvfdeTZgwQYMGDWrYZ8WKFerRo4d++tOfavXq1fr1r3+t733vexHPlpSUpJtuuklDhw5VdXW1Fi1apLFjxzbKJkmjR4/WokWLIp6nOT/84Q8bvlR+WWFhofbu3avHHntMpaWlevrpp/XjH/84onkyMjIavjwGg0H9y7/8i84777wm+0XrnE2bNk1XXHGFnnjiiYbHXnnlFX3lK1/RzJkz9corr+iVV17RN7/5zUbPO3LkiP7whz80fMldtGiRJkyY0GyhI5zZxo4dqzlz5igpKUkvvPCCXn755SbZTmpt7MOdS5K++tWv6uqrr27xeaF8liOR7dSfBb/61a+UktLyv68idc64CgkAwLM60vPipOCry6XuPWQuvSqMiQAgdm3dulUDBw7UgAED5Pf7NWXKFK1fv77RPhs2bGj47ffkyZO1adMmRaPnf9++fRtmLHTv3l2ZmZmqqKiI+HHDZcOGDbroootkjNHIkSN19OhRHTx4MGrH/+CDDzRw4ED169cvasf8sjFjxjQpOqxfv14XX3yxJOniiy9u8n6TTswkGDt2rFJTU5WamqqxY8eqqKgo4tnOOeccJSUlSZJGjhzp5P3WXK5QhPJZjmQ2a63effddXXDBBWE9ZiiYgQEAiDt253apMF/mazfIpDSdDgoAiaiiokLp6ekN99PT01VaWtriPklJSUpJSVFlZWVEfpPakv3792v79u0aPnx4k21btmzR3Xffrb59++qmm27S6aefHrVcDz30kCTpsssua3LpyIqKCgUCgYb76enpqqioUN++faOSbfXq1S1+mXR5zg4fPtxwDvr06aPDhw832efL78u0tLSoFxNWrFihKVOmtLi9tbGPhL/85S9atWqVhg4dqptvvrlJISGUz3Ikbd68Wb1799Zpp53W4j6ROmchFzCee+45TZs2TUOGDAnbwQEAOCk3t2enZlycyr76otStu8z0lqdfAgC8p6amRrm5ubrllluaTE8/88wztWzZMnXr1k0FBQV6+OGH9dhjj0Ul1wMPPKC0tDQdPnxYDz74oDIyMjRmzJioHLstdXV1eu+99zRnzpwm21yesy8zxsgY4+TYrXnppZeUlJSkqVOnNrs92mM/Y8aMhj4ly5cv169+9SvNmzcvYsfriNYKZlJkz1nIS0iCwaAeeughLVy4UK+88orKy8vDEgAAAEmNLp3aGXb3DtmCNTKXXiXTI3zrZwEg1qWlpTX6N3x5ebnS0tJa3Ke+vl5VVVXq2TM8P5/bUldXp9zcXE2dOlWTJk1qsj0lJUXdup24otT48eNVX1+vzz//PCrZTp6n3r17a+LEidq6dWuT7WVlZQ33mzu3kVJYWKgzzzxTffr0abLN5TmTTpyvk0tpDh482OxMni+/LysqKqJ27lauXKn33ntPd911V4vFlbbGPtz69Okjn88nn8+n6dOna9u2bc1mauuzHCn19fVat25dqzNWInnOQi5g3HrrrXrqqac0Z84cffLJJ/re976nBx54QG+//bZqamrCFggAgM6wf/69lNxVJufrrqMAgKcMGzZMe/bs0f79+1VXV6c1a9ZowoQJjfY599xztXLlSklSfn6+srKyovJbc2utnnzySWVmZuqqq5rvXXTo0KGGfhxbt25VMBiMSnGlpqZG1dXVDbfff/99DR48uNE+EyZM0KpVq2St1ZYtW5SSkuKJ5SOuztlJEyZM0Ntvvy1JevvttzVx4sQm+4wbN04bN27UkSNHdOTIEW3cuFHjxo2LeLaioiL96U9/0j333KOuXbs2u08oYx9up/ZOWbduXbNLfkL5LEfKBx98oIyMjEZLWE4V6XNmbAe78nz22Wd67LHHtGPHDiUnJ+uCCy7Q7Nmzo1b5kdRwCZdoCgQCjaqrcI8x8RbGw1u8Ph65uT2bnXmxYEFlh5aT2L07FfzBd2VmzJTv2lvCkDD8vD4miYbx8B5XY5KRkRH1Y7pQUFCgX/7ylwoGg7rkkks0a9YsLV++XMOGDdOECRN0/PhxPf7449q+fbtSU1M1f/58DRgwIOK5PvzwQ/3gBz/Q4MGDGwomN954Y8N7YcaMGXrjjTf05ptvKikpScnJybr55ps1atSoiGfbt2+fHnnkEUknfvt84YUXatasWXrzzTcbsllr9cwzz2jjxo1KTk7WvHnzNGzYsIhnq6mp0bx58/T44483LLk5NVc0z9nSpUtVUlKiyspK9e7dW7Nnz9bEiRP16KOPqqysrNFlVLdt26a//vWvmjt3rqQTPShefvllSScuo3rJJZdEPNvLL7+surq6hv4SI0aM0O23366Kigo99dRTuvfee1sc+0jmKi4u1ieffCJjjPr166fbb79dffv2bZRLav6zHE7NZbv00kv1xBNPaMSIEZoxY0bDvtE8Z+0qYFRVVSk/P1/vvPOOPv30U02aNEkXX3yxAoGAXn31VW3atKkhbDRQwIDEmHgN4+EtsTQemZkZ2rWrcz/Xg794VPa91fL919MyvZpOpfWCWBqTRMB4eA8FDABAS0Ju4pmbm6uNGzdq9OjRuuyyyzRx4kR16dKlYfvNN9+sW265JRIZAQBok92/R3bt2zKXfs2zxQsAAAB0XMgFjBEjRug73/lOs81hJMnn8+l//ud/whYMAJBYFizo3BVI7Ot/kHxJMpdfE6ZEAAAA8JKQCxhXX932pehaan4CAEBbOnMJVVu2T/bdFTIX/5NMn+j1YgIAAED0hHwVEgAAvMjW1yv47P+TkpJkLg9vAysAAAB4BwUMAEBMs396QdqySeabd8ikBVzHAQAAQIRQwAAAOJGb2/nr0NuN62Vf/6PMRZfLd354L7kGAAAAb6GAAQBwYsmSzhUw7IG9Cv5iiTR4qMwN/ydMqQAAAOBVFDAAADHH1tYq+NRPJCv55i6S6ZLsOhIAAAAijAIGACBqcnN7KjMzQ5mZGZLUcLu9y0nsi09Ln26V79Z/lek3MBJRAQAA4DEhX0YVAIDOWriwsuFyqZmZGdq1a3e7XyOYv1J25esyl18jM25yuCMCAADAo5iBAQCIGXb3Dtnnn5BGjJGZeZPrOAAAAIgiChgAACcWLKhs1/62plrBJ/9b6tpNvtvvlvEziRAAACCR8K8/AIATJ5eShMJae2Lmxd5d8i34T5k+6RFMBgCxb/fu9i3RCwQCKisri1CaziFb+3k1l0S2jvBqLily2TIyMpp9nBkYAADPs2+/LrtulczX58icNdZ1HAAAADhAAQMAEHHtvcrIqez2UtnlT0tfmSDzT9eGMRUAAABiCQUMAEDELVnSsQKGPVqp4FP/LfXqK9+t82V8/G8LAAAgUfEvQQCAJ9lgUMFnHpUOVcg39x6Z1F6uIwEAAMAhChgAgIjIze2pzMwMZWaeaMJ08naoy0nsX16SPtggc/13ZM4cGcmoAAAAiAFchQQAEBELF1Y2XGkkMzNDu3aF3hHffvSB7MsvyEycKjPtykhFBAAAQAxhBgYAwFPsoQoFf/6wNCBD5uY7ZIxxHQkAAAAeQAEDABBxCxZUhrSfra9X8H8elmqq5Zu7SKZbSoSTAQAAIFZQwAAARNzJpSRtsa+8IG0plrnpDpnMwRFOBQAAgFhCAQMA4Am2aK3sG3+UufgK+SZPcx0HAAAAHkMBAwDgnD2wV8Fnl0qDh8lcf5vrOAAAAPAgrkICAAir3NyeIS8ZkSRbe1zBJ/9bkuSbe49Ml+RIRQMANMN+UqqKR78ve913ZAYNcR0HbbC1x2V//6xs+f4W9zmYnKz648cjFMB26ukHu3TpRDbbOINtZVvDwy083oyKLl1UX1vbwr6dOHYnVfj9qq+ra3mHUI5zsil6o7+NZPSl+83tp6a3v3jiweQvzlmTfU787bvocpnsyW3nCxEFDABAWC1Z0s4CxvKnpR3b5Lvj32X6DYxgMgBAs2prVVuyUb7PD0oa4joN2mD/9GvZt/4snX6mZJqfUB/0+6XWvvB2VieuEBbs4pfq6sN37Ba/YKvJl2m1FPvkfsGgZINqfucvvtybZp4XyrE7wXTxS7VtjGdrh7Gn3Di1oHNq4cPaE9uDweb3b/R6/3jM1vmlUwsYX95+/FgYzsA/UMAAADgTzH9L9u03ZK74hsy4Sa7jAEBi6t79xN/V1W5zoE22tET2zVdkps6Q7+bvtrhfeiCgsrKyKCYLnZezpXk0W1+P5pKif87ogQEA6LTc3J7KzMxQZmaGJDXczs3t2eJz7I5tss8vk0Zmycz8ZrSiAgC+rOuJAoatqXIcBK2xNdUn+kWl95eZfavrOIATzMAAAHTawoWVDctGMjMztGvX7lb3tyVF/5+9O4+Puj7wP/7+TBIyMyEkhHCYIFHCHUEwcnnUK4Wqu21tXWtZtPrQtvZQW6wVty20pV3xgG61tttHbX9eu1vrbi+PXtEeXihHwn1IVJAjQEIgkEwSZubz++ObBJAAmWRmvt+ZvJ6Ph4+ZTOb7/b6HMZC88zkU/cl9Uk6ufJ+9WyYjIxkxAQBdCQSd2xZGYHiZffb/SXV75Pva92X8QbfjAK6gwAAAJFX09Zdln3xEGjZcvjsWyuQXuB0JAPo2f8cUEkZgeJVdt1L2H3+UmfVxmTHnuB0HcA0FBgAgrubN63oBT2ut7Au/kv3df0njJsn3hXtlgjlJTgcA+CCTmSVl9ZOYQuJJtumwok88Ip1xJlMu0edRYAAA4qqrHUhsJCL7Xz+RfeXPMjMulfnM7c43zAAATzCBIFNIPMr+90+lQwfl+/I32WocfR4FBgAgoWxLSNGfPiCtWylz1b/IfHyuTC+2XwMAxJ8vmKMou5B4jl3xquxbf5f56ByZklFuxwFcR4EBAEgYe7BB0Ye/K73/rswNX5TvQx9xOxIAoAsmEGQXEo+xBxsU/a+fSCWjZK681u04gCewjSoAoMdOuU3q7h2K3ne3VLtDvi9/g/ICADzMBHKYQuIh1lpFn/yR1Noq3y1flcnk986ARIEBAOiFpUu7LjDslvWKLv661NYq393/LjNpapKTAQBiYYI5LOLpIfbVv0hrlst84gaZM850Ow7gGVR5AIC4siteVfTnP5AKhzjbpA4e5nYkAMBp+AJBtlH1CFu3R/aZn0tjJ8pc/s9uxwE8hREYAICYLFmSq+LiIhUXF0lS5/0lD/VX9M+/dRbsPGuUfPfcT3kBACmCKSTeYKNRRf/fDyUj+W66Q8bHj2vAsRiBAQCIyV13HercKrW4uEg7d+6SjUZkf/UL2Wefk8ovkO+WeWz1BgApxJlCQoHhNvvSc9KWdc5244VD3Y4DeA4FBgCgV2xbq6KPLZGqlslUfEzmX27mN0YAkGJMICgdaZMNh1kw0iV29/uyv35SmjRV5sIKt+MAnsTfTgCAHvu3O3YouuSb0rtbZD51q3wVH3U7EgCgB3yBoHOnNSRlnnyHKSSGDYed9aP8fvlu/LKMMW5HAjyJX5EBAHrE7t2t2xq/KL3/rnyfv4fyAgDiIBqN6utf/7oWL1583OO/jjpE9QAAIABJREFU+MUvdMMNNyTsuiaY49xhIU9X2BeflbZtlW/uF2XyBrodB/AsRmAAAGJm392i6COLpGhUvnmLZEaNdzsSAKSFF198UcXFxQqFjq5HUVNTo6ampoRe13SMwGAr1aSz27bKvvgrmWmXyJRf6HYcwNMYgQEA6JYlS5whxbb6TUUf+jcp2y/f/PspLwAgTurr67Vq1SpdccUVnY9Fo1E9/fTTmjt3bkKv3TkCg4U8k8q2tTpTR3LzZOZ83u04gOdRYAAAumXp0lxF//qioj++TzpjhHz3PiAzbLjbsQAgbTz++OOaO3fucesf/PGPf1R5ebkGDkzstAIT6JhCQoGRTPa3T0u735fvM3fI5PR3Ow7geUwhAQCclo1GNX/sI7L//YQ0aap8n7tbJtvvdiwASBsrV65UXl6eRo4cqfXr10uS9u/frzfeeEPf/va3T3t8ZWWlKisrJUmLFy9WYWFhTNe3rc4UldysDPljPDbRMjMzY349ydKbbG3rqtRQ+XsFZl+jAZfO8kyuRCNb7LyaS0p+NgoMAMBJLVmSqx/9R7YemvQdfbH0T3pq2ye14A936862kO6665Db8QAgbWzevFkrVqxQVVWV2traFAqFdNdddykzM1N33HGHJKmtrU233367HnnkkROOr6ioUEXF0a036+rqYrr+wPZSunHfXh2O8dhEKywsjPn1JEtPs9mWZkX/4ztS4VC1/tP1cX996fhnlgxezebVXFLishUVFXX5OAUGAOCk5n1ht75i75M2r9XiTV/Wv/3jw7rJ7HU7FgCknTlz5mjOnDmSpPXr1+u5557T/Pnzj3vODTfc0GV5EQ9Hp5CwiGcy2L/8Xtq/T76v3yfjD7gdB0gZrIEBAOiSXV+l6Pe/Jm3dKHPLPP34nZvYlx4A0lTnD9HsQpIUdvNaaUSpzKgJbkcBUgojMAAAx7F7dyn6q19Iq9+SBg+T76vfkRk7UfPmMWUEAJKhrKxMZWVlJzz+1FNPJeyaJiNDyvaziGcS2HBYeneLzMXxXfcC6AsoMAAAkpz5uPb5X8lW/l7KzJL55GdkrvioTFaWJLHmBQCkO39QaqXASLgd70ptrVIp25ADsaLAAIA+zkajsm/8VfY3T0oHG2QuuELmmhtk8gvcjgYASKZAgDUwksDWbJIkmdJxLicBUg8FBgD0YbZmk6K//Jn03tvSyLHyfembMmePdjsWAMAN2QFZ1sBIvK0bpYJCmQJvbosJeBkFBgD0QbahXvbXT8gu+5uUXyBzy1dlpl0i4zu6tvOSJblMGwGAviQQlFqYQpJotmaTzCimjwA9QYEBAH2IPdIm++ffyv7hf6VIROaqf5G58tout3BbupQCAwD6FH9Q2rfb7RRpzdbvkxrqWP8C6CEKDADoA6y1UtUyRZ/9hVS3RzpvpnzX3iwzeJjb0QAAHmH8AVlGYCSUrdkoSYzAAHqIAgMA0pzduc1Z52LTGqm4RL55i2TGn9vlc5csydXSpbmdHxcXF0mS5s07xGgMAEh3gQBTSBKtZpOzXe3ws9xOAqQkCgwASFO26ZAaf/2Eon/8jRQIysz5vMyHPiKTkXHSY+6662hRUVxcpJ07dyUrLgDAbf6g1NIsa62MMW6nSUt260bp7DGn/LcYwMlRYABAmrGRiOw//ij7u/9WKNQsc+mVMh/9tEz/AW5HAwB4mT8gRSLSkTapX7bbadKObQlJO96VufJat6MAKYsCAwDSiN24WtFnHpN2bpPGTdKg2+7WgZy8Hp1r3jymjABAnxIIOrctIQqMRHh3ixSNsv4F0AsUGACQBuy+WmeBzqplUuFQ+b5wrzRlhjIHD5bq6np0Tta8AIA+xt9RYDRLA/LdzZKGbM0myRhp5Fi3owApiwIDAFKYbQnJ/uF/Zf/8WykjQ+aaG2Q+/DGZrH5uRwMApBjjD8hKUoiFPBPB1myUikbIBPu7HQVIWRQYAJCCbDQq+9bfZf/vCenAfpkZl8l84kaZgYN6dL4lS3IZcQEAfZ0/4NyyE0nc2WhUqtksM/Uit6MAKY0CAwBSiLVWemezor/6ufTOZums0fLdNl+mdFyvzrt0KQUGAPR5gWOmkCC+dr8vhZqkUta/AHqDAgMAUoCt3SH71iuyK151vgnKGyhz853OyAufz+14AIB00D4Cw4aaxSaq8WVrNkqSzKje/cIB6OsoMADAo+y+WtkVr8q+9Yq0411n4a/RZTKXXy0z41KZjsXWemjJklwtXZrb+XFxcZEkZ/cRRmMAQB/kP2YXEsTX1o1Sbp40+Ay3kwApjQIDADzE7q9zSosVrzrbrUlS6TiZT90qc/6FMvk9W+OiK3fddbSoKC4u0s6du+J2bgBACmIKScLYmk1S6XgZw9gWoDcoMADAZfZgg+zK12SXvypt3eA8OKJU5tqbZM6/SGbQEHcDAgD6hn7ZkvGxC0mc2cYGae9umQ/NdjsKkPIoMADABfZwo+yqN2SXvyJtXifZqFRcIvOxf5WZerHM0KKk5pk3jykjANDXGWOcdTBaKTDiqmazJMmwgCfQaxQYAJAktrlJtnqZM9JiY7UUiUhDimSu/heZ8y+WKR7hWjbWvAAASJICASnEFJJ4sls3SpmZUkmp21GAlEeBAQAJZFtCsqvfcta0WLdSCoelQUNkPvxxZy/4M0cyHxYA4B3ZAVnWwIgrW7NRKhklk9XP7ShAyqPAAIA4s22t0rqVzrana5dLbW1SfoHMpVfJTL1YOnsMpQUAwJsCQXYhiSN75Ii0bavM5f/sdhQgLVBgAEAc2PARaX217IpXZKvedOYP5+bJXFDhjLQYNUHG53M7piRn+1SmjAAAuuQPSqEmt1Okj21bpXBYZhTrXwDxQIEBAD1kw2Fpy1pnpEXVG1JzkxTsLzP1ImekxdiJMhkZbsc8wdKlFBgAgJPwB6SGOrdTpA1bs8m5UzrW3SBAmqDAAIBusocbpXc2y9Zscr4heXeL1NYq+QMyk2c4Iy0mTJbJzHI7KgAAPWICAVmmkMSN3bpRGnKGzICBbkcB0gIFBgB0wUajUu0Op6joKCxqdzif9PmcxTcvniUzdqJ0znmeX5hryZJcLV2a2/lxcbGzTeu8eYcYjQEAOMoflFjEMy6stVLNRplzznM7CpA2KDAAQM5uIXp3y9HRFe9scqaESFJOrlQ6TmbmZc4e7meNksn2uxs4RnfddbSoKC4u0s6du1xOBADwJH9AagnJWsuC0721b7d06KDE+hdA3FBgAOhzrLVS3Z5jRldslHZsk2zUeULRCJnyC6XS8TKl46ShRXwTBwDoGwJByVqptcUpM9Bjdquz/oUppcAA4oUCA0Das4cbpffeln3vbdn3tjprVzQecD6ZHZBGjpG5+l+csuLssTI5/d0NnGDz5jFlBABwEv6gc9vSTIHRWzUbpUCOdMaZbicB0gYFBoC0YltC0vYa2ffelt7b6tzuqz36hGHDZSZMkUaOdQqL4hJP7hSSSKx5AQA4qY7SIhSS8t2NkupszSapdKxntlEH0gEFBoCUZcNHpJ3bZN/d0j7CYqu06/2jU0EKBktnjZa5eLbMWaOkklEywRxXMwMA4GXGH5SVJHYi6RXbfFjatV3m/AvdjgKkFc/UgdXV1brzzjt1++2367e//a3bcU5q0aLu/aZ2yZLc0z8pxue6eU5ej7fP2ReubaMR2d3vK/r6y4r+938q8u9fU/T2Tyn6vXmy//WfsquXSwMLZa6+Tr7bvyXfkieUcf/PlfGF+fJd+UktffGibpUX6fb/RkUFPTUApIpoNKqvf/3rWrx4sSTp4Ycf1p133qm77rpLP/7xjxUOhxMfItA+AoOdSHrnnc2Stax/AcSZsdZat0NEo1Hdeeed+uY3v6lBgwbp3nvv1Z133qnhw4ef8rhdu5K/in53V++PZZX/VDinl19PYWGh6urqXLm2V87ppWsf+3709Jwjzxykmn8sk33/Hen9d2Tff1fa8Z6zoJjkrFtRUipz1mjdtni6fvqnQdKgIadcaDMV/iwTcU52HPGeU32NIPl4P7zHrfekqKgo6df8oOeff141NTUKhUKaP3++Vq1apSlTpkiSfvjDH2rChAmaNWtWt84V6/fJHX/udnuNoou+Kt8X7pU5b2bMryERvPx1erJs0d8+LfuH/5Xvh/8j48JaIqn4Z+YFXs3m1VxS4rKd7O9kT/xqbuvWrRo2bJiGDh0qSbrgggu0fPny0xYYAFKfbTokbX+nvax4V3b7O9o4a6ei/x5xnhAISmeeLXPRh6URI2XOGi0NK5bxOaOhXvhKkUwhP6ADAFJbfX29Vq1apU984hN6/vnnJUnnnXde5+dHjRql+vr6xAdpX8TTtoTE/ls9Z2s2ScPPdqW8ANKZJ0ZgLFu2TNXV1brtttskSf/4xz/09ttv65ZbbjnueZWVlaqsrJQkLV68WG1tbUnJt2hRhr73vROnjnzzmxF961uRmJ+XKudMldfz/e9n6bvfPfGf2FR9Pal+7e98xxw3xPXoc62K/bWaMGCzzsnbrGvO36SR/bYoum9P53N3h4Zow6ExWndwrNY3jtWGxjG6cd4wfWtB1LXXk4r/b1RUZOqVV06cIXjxxVFVViZh+DFOKTMzMznDwNEtvB/e49Z70q9fv6Rf81hLlizRNddco1AopOeee07z58/v/Fw4HNY3vvEN3XTTTRo/vuspCb39Prnjzz16sEH7brpauZ+dp+BV1/b8BcWRl79Ou8pmI2Htmztb/suv1oDPzvNMLq8gW+y8mktKXLaT/Z2cUgXGBzGFJHnn9PLrYQqJt65dWFiofTt3SLu2y+7cJu3c3jm6Qs2HnScZIw0tlhkx0hldMWKkdOZImdw8z72eVD8nU0i8x8vDQPsi3g/v6YtTSFauXKmqqirdeuutWr9+/QkFxn/+53/K7/frpptu6vY5ezyF5Eibol+8Vubjc+W7+rqYzpEoXv467Sqb3Vaj6Pe+KvPZr8k37UOeyeUVZIudV3NJfXQKSUFBwXFD4urr61VQUOBiIgDdYcNHNDZ3q6JvLu8sLOpqdyi655hvmrL6OVuVnn+h7v3xFC1+ukAafpZMtt+94AAAeMjmzZu1YsUKVVVVqa2tTaFQSA8//LDuuOMOPfvss2psbNTnPve55ITJzJIyMqVWdiHpKbt1oySxgCeQAJ4oMEpLS7V7927t3btXBQUFev3113XHHXe4HatL3/xm5PRPkjRv3qFun7O7z3XznLweb58z0de20YhUt8cZTbFzm7N16c5t0t5d+svFEdnHJPl80tBiZY4ar+iMy2SKS6TiEVLh0M71KobszZUpPf310/nPMtnnvPji6OmfBABw1Zw5czRnzhxJ6hyBcccdd+ill17S6tWrtWDBAvl8ydk80Bjj7EQSosDosZqNzs5ogwa7nQRIO56YQiJJq1at0hNPPKFoNKrLLrtMn/jEJ057jBtTSLw8fKev4j2JHxuNSPX7pNodsrved4qKXdul3dulY+fSDh4mFY1wSoqO26HFMllZvB8ew/vhPbwn3sL74T19cQrJsY6dQnL99ddr8ODB8vudUYvTp0/Xtdd2b12Knk4hkaTI/FtlRk+Q7xZ31m/4IC9/nXaVLXLPLTIjx8r3+a+7lCr1/sy8wqvZvJpL6qNTSCRnleVjV1oGkDi2tUXas1N29w6pdqdTWOx+X9qzSwofOfrEvAKpeITMh650bovPks4YzoraAAAkSFlZmcrKyiRJv/zlL90JEQjKtjACoyfs/jpp/z5p1sfdjgKkJc8UGADiy1orNR44Wk7UdhQWO5x/WDsYnzR4qDRsuEzZec4WpWcMdz7uP8C9FwAAANzhD0qhZrdTpCRbs0mSZErHuZwESE8UGECKs60t0t7d0t7dsnt3Sbt3yNa2j6wINR19YrbfKSXGlDm3w5ySQkPOkMnKcu8FAAAAbwkEnV+CIHY1G6V+2dLws91OAqQlCgwgBdiWkLSvVtq7S3bvbmnPLtl9u6U9u6WD+49/cv4gZ5rHjEuOLyoGDnIW5gIAADgF4w84328gZnbrRunsMTKZ/JgFJAJfWYBH2JaQM5Ji327ZPbuOjqjYW3tiSZE3UBp8hsw5U5zboUXSkCJpyDAZf9CdFwAAANKDPyC1MIUkVra1RXr/HZmPfNLtKEDaosAAksRGI1LDfqluj2zdHmdb0rpa5/6+Wulgw/EHUFIAAAA3BFgDo0fee1uKRmVGjXc7CZC2KDCAOLHWSocPHVNQ1B5fVtTvkyLhowcYIw0cJBUOdRbPHEJJAQAAPCA7ILW1ykYiMhkZbqdJGXbrRufOyLHuBgHSGAUG0E3WWqn5sFNE7N8nW7/3+IJi3x6p9QNbjvUf4BQUI0ql8y5w7hcOdXb9KBgsk8nimQAAwGMC7b9EaQ1Jwf7uZkkhtmaTdMaZMjm5bkcB0hYFBtDOhsPSgXqnnNi/72hR0Xm/7sSCol+2VDjUKSbGTpQKhzgFRcdjjKIAAACpxh9wbkMUGN1lo1GpZqNM+YVuRwHSGgUG+gRn9EST1LBPqq9zSon9x4yk2F8nHdgv2ejxB+bmSQWDpWHFMmVTnFETBYOdxwYNlnLz2NkDAACkl45fwLCQZ/fV7nC+1yxl/QsgkSgwkPKstbKHG6WGeml/nWxDnXO/oU72gPOYGuqkttbjD8zIlAoKnVJi3CSnkCgYLNN+q4GDZbKz3XlRAAAALjGBgKwktYRO91S061j/wpSOczkJkN4oMOBpNhqVDje2T+2ok20vJtRQ315U1GnvgXqpre34A30+Kb9AGlgoM/wsaeL5zoKZAwtlCgqlQUOkAfkyPp8rrwsAAMCzOkZgsBNJ99VsctY+G1rkdhIgrVFgwBXWWucfxYP7pQP7ZQ/sd0qKD9zXwYbjd+6QpIwMKX+QNHCQTMkoBWZeppA/KDOwsLOkUF6+jI9VswEAAGLWsQYGU0i6zW7dKJWOY2oxkGAUGIg729rqFBMHG44vIw7sd6Z0HNjvfL615cSDAznOyIn8AmdRzI77x5YTuXnHjZzILSxUa11dEl8hAABAGmvfhcS2hMSP46dnDx2U9u6SufjDbkcB0h4FBrrFWisdPiQ1NkgH98sePNBZUuhgg2z7rRobuh5umNXvaBlRUirlTZUGFkh5BTL5g47ez/Yn/8UBAADgKBbxjE3NJkmSYQFPIOEoMPo429oiNR7o/M82dhQTB2Q7CorGBunggROnckhSdkDKy5fyBjprTeSfJ+UNlAYMlMkb6IyayC+Qgv0ZUgcAAJAKjt1GFadlt250FocvKXU7CpD2KDDSkG0JOaXDsaVEF/fVeFBqPck/TLl5R4uIM86U8p37yitwion2/0zHP3AAAABICyYjQ+rXj11IusnWbJJKSmX6sXsdkGgUGCnARiJSU6NTOBw66JQQhzs+PuDMuzu2mPjgdqGSZIyUkysNyHd23zh7TOd9DciXGTDw6Me5eTKZ/K8BAADQZ/mDTCHpBnukTXrvbZnLrnI7CtAn8FNqktlo1CkY2lqlpsPSoQNOKXHo4NGC4tAB6VCjdMgpKNR0WLL2xJP5fM5Iif4DnBKidNwxpcRAmWMKCuXmOW06AAAAcDr+ANuodsORd7ZI4SMyo1j/AkgGCowY2Hc2q2VjlaL1dVJrewnR1uLsptHWKrW2ynY81v5x5+c6HmtrO/VF+udK/fOkAXlS0ZkyuROdkiI3T2ZAXvv9fCl3gLOuxDG7cQAAAABx4Q8605JxSkc2rXHusIAnkBQUGDGI/uk3Orjq9RM/0S9byvY7tx33s/3OqIjjHss+/rnB/s4oidwBTimRk8vUDQAAALgvwBSS7jiyaZ00eJizRhyAhOOn5Rj4rr1JA2/6khqaQ1K/jsKiH7trAAAAIL34A1L9PrdTeJq1Vkc2rZEZN8ntKECfQYERAzN4mDILC2Xq6tyOAgAAACSM8QdkT7ZbHRx1exQ9sF+G6SNA0rCAAgAAAIDjBYIs4nkadutGSZIZNc7lJEDfQYEBAAAA4HjZAdbAOJ2ajTLBHKlohNtJgD6DAgMAAADA8QJBKRyWPXLE7SSeZbduVNaYMhlfhttRgD6DAgMAAADA8fxB55atVLtkDx2Udm1X1vhz3Y4C9CkUGAAAAACO5w84t0wj6ZJdu1KyVtnlM92OAvQpFBgAAAAAjmMCHQUGIzC6tGa5lDdQmWePcTsJ0KdQYAAAAAA4XscUEnYiOYENh2U3VMlMPF/Gx49TQDLxFQcAAADgeEwhObmajVKoWWbi+W4nAfocCgwAAAAAxws4IzAsU0hOYNcslzIzpQks4AkkW6bbAQAAAAA4otGo5s+fr4KCAs2fP1979+7Vf/zHf+jQoUMaOXKkbr/9dmVmJuFb+M5dSBiB8UF2zQppzDkyHX9GAJKGERgAAACAR7z44osqLi7u/Pjpp5/W1VdfrUceeUQ5OTl6+eWXkxOkYwpJiBEYx7J7d0u1O2QmTXU7CtAnUWAAAAAAHlBfX69Vq1bpiiuukCRZa7V+/XrNmDFDknTppZdq+fLlyQmT7XdumUJyHLt2hSSx/gXgEqaQAAAAAB7w+OOPa+7cuQq1j3o4dOiQgsGgMjIyJEkFBQXav39/l8dWVlaqsrJSkrR48WIVFhbGdO3MzMwTjtkbCCpgrHJjPFe8dZXNLQ0bqxUpLlHhhImSvJXtWF7NJZGtJ7yaS0p+NgoMAAAAwGUrV65UXl6eRo4cqfXr18d8fEVFhSoqKjo/rquri+n4wsLCE46x2X6F9terNcZzxVtX2dxgW5oVXV8lc/k/debxSrYP8mouiWw94dVcUuKyFRUVdfk4BQYAAADgss2bN2vFihWqqqpSW1ubQqGQHn/8cTU3NysSiSgjI0P79+9XQUFB8kL5g0whOdaG1VI4zPoXgIsoMAAAAACXzZkzR3PmzJEkrV+/Xs8995zuuOMOLV26VMuWLdOFF16ov/3tbzr//CSuvRAIyrILSSe7doUUyJFKx7sdBeizWMQTAAAA8Kh//dd/1fPPP6/bb79dhw8f1uWXX568i/sDjMBoZ6NR2bUrZMqmyCRjG1sAXeKrDwAAAPCQsrIylZWVSZKGDh2q++67z50g/oDUeMCda3vN++9IBxskdh8BXMUIDAAAAAAnMP6gFGIKiSTZNSskY2QmlrsdBejTKDAAAAAAnCgQlFgDQ5Jk1yyXzh4jk5vndhSgT6PAAAAAAHCi9jUwrLVuJ3GVbWyQ3nub3UcAD6DAAAAAAHAif1CKRqW2NreTuMquXSlJMqx/AbiOAgMAAADAiQIB57aPTyOxa1ZI+YOkM892OwrQ51FgAAAAADiRv6PA6LtbqdrwEWlDlcyk82WMcTsO0OdRYAAAAAA4gfEHnTt9eQTG2xuklhDTRwCPyHQ7AAAAAJCK1q1b163n+Xw+TZgwIcFpEiDQXmD04a1U7ZrlUmaWNP5ct6MAEAUGAAAA0COLFi3S4MGDT7tLR2Njo5566qkkpYojppA461+MmyiT7Xc7CgBRYAAAAAA9kp2drR/96Eenfd7NN9+chDQJ0D6FxLY0qy+u/mBrd0p7d8lU/LPbUQC0Yw0MAAAAoAfuvvvubj3vrrvuSnCSBOnYhSTUN0dg2LUrJLF9KuAlFBgAAABAD0ycOLFbzzvnnHMSnCRBsvv2Ip527QqpaIRM4VC3owBoxxQSAAAAoJdeffVVnXXWWRo+fLh27dqln/70p/L5fLr11ltVXFzsdrye6ddP8vn65BoYNtQsbVknU/Ext6MAOAYjMAAAAIBeeuaZZ9S/f39J0pNPPqnS0lKNHz9ejz32mMvJes4Y46yD0Rd3IdlQLUUiMpOmup0EwDEoMAAAAIBeamxsVH5+vtra2rR582Z9+tOf1rXXXqv33nvP7Wi94w/0ySkkds1yKdhfKh3ndhQAx2AKCQAAANBLAwYMUG1trbZv367S0lJlZWWptbXV7Vi9FwjK9rEpJDYalV27Quac82QyMtyOA+AYFBgAAABAL33yk5/UPffcI5/Pp69+9auSpLVr16qkpMTlZL3kD/S9NTC2bZUOHZTYfQTwHAoMAAAAoIdaW1uVnZ2tSy+9VDNnzpQkZWdnS5JGjx6tr3zlK27G6z1/QGo67HaKpLJrVkjGJ3POeW5HAfABFBgAAABAD33xi1/U2WefrSlTpqi8vFzDhg3r/FxeXp6LyeLD+IOy9fvcjpFUds1yqXSsTP8BbkcB8AEUGAAAAEAP/fSnP9XGjRtVVVWl+++/X9FoVJMnT9aUKVN0zjnnKDMzxb/dDgT71CKe9kC9tL1G5hM3uh0FQBdS/G9UAAAAwD2ZmZmaOHGiJk6cqBtvvFF79uxRVVWV/vCHP+iRRx7RmDFjNGXKFE2bNk35+flux42dPyCF+s4aGHbtSkmSYf0LwJMoMAAAAIA4GTp0qD7ykY/oIx/5iNra2rR27VpVVVUpIyNDV1xxhdvxYucPSq0h2WhUxudzO03C2TUrpIJCqTjFF18F0hQFBgAAANBL0Wj0hMcyMzNVXl6u8vJyFxLFSSDg3La2ONNJ0pg9ckTaWC0z8zIZY9yOA6ALFBgAAABAL33605/u8vGMjAwNHDhQ06dP13XXXSe/35/kZL3kby8wQs1pX2BoyzqptYXpI4CHUWAAAAAAvXTzzTdr+fLl+vjHP65Bgwaprq5Ov//973XeeeepqKhIzz77rB5//HHddtttbkeNjb+9tGhN/3Uw7NoVUr9+0rhJbkcBcBIUGAAAAEAvvfDCC7r//vsVDDo/8BcVFam0tFTz58/XI488ohEjRuiee+5xOWXsTCAoKzkjMNKYtdbZPnXsJJl+2W7HAXAS6b8SDwAAAJBgzc3Nam1tPe6x1tZWNTc7P/jn5+erra3NjWi9k90+hSTdt1Kt3Sntq5WZNNXtJABOgREYAAAAQC9dcskl+t73vqcrr7xShYWFqq+v14v10tmTAAAgAElEQVQvvqhLLrlEkrR69WoVFRW5nLIHOta9aEnvKSR2zXJJbJ8KeB0FBgAAANBLc+fO1bBhw/T666+roaFB+fn5mj17tioqKiRJZWVl+s53vuNyyh5oX8TThkJK53057NoV0vCzZAYNdjsKgFOgwAAAAAB6yefzadasWZo1a1aXn+/Xr1+SE8VJxyKeaTyFxDYflt5eLzP7E25HAXAaFBgAAABAL1lr9dJLL+n1119XY2OjHnroIW3YsEEHDhzQBRdc4Ha8nuvYRjWNp5DY9dVSNMr6F0AKoMAAAAAAeumZZ57R2rVrddVVV+lnP/uZJGnQoEF64oknulVgtLW1aeHChQqHw4pEIpoxY4auu+46rV27Vk8//bSi0aj8fr++9KUvadiwYYl+OZ1MVpaUmZXeu5CsWS71z5VGjnE7CYDToMAAAAAAeunvf/+77r//fg0YMECPPfaYJGnIkCHau3dvt47PysrSwoUL5ff7FQ6HtWDBAk2ePFmPPfaY7r77bg0fPlx/+tOf9H//93/60pe+lMiXciJ/IG2nkNhoRHbdSplzymV8GW7HAXAabKMKAAAA9FLHCIljtbS0nPDYyRhjOp8biUQUiURkjLNsZijkTN9obm7WwIED45i6mwLB9J1C8u7b0uFGid1HgJTACAwAAACgl6ZMmaInn3xSn/nMZyQ5a2I888wzKi8v7/Y5otGo7rnnHtXW1mr27NkaPXq0brvtNt13333q16+fAoGAvv/973d5bGVlpSorKyVJixcvVmFhYUz5MzMzT3pMff9c+aIRDYzxnPFyqmy9dfhP69Xky1Dhhyrk6z8g5uMTma03vJpLIltPeDWXlPxsFBgAAABAL91444169NFHddNNNykcDuvGG2/UpEmT9OUvf7nb5/D5fHrwwQfV1NSkhx56SNu3b9cLL7yge++9V6NHj9bvf/97Pfnkk7rttttOOLaioqJzy1ZJqquriyl/YWHhSY+JZGZJBw/EfM54OVW23oq8+Q9p1Djtb2mTWmK/RiKz9YZXc0lk6wmv5pISl62oqKjLxykwAAAAgF4KBoO6++67deCA84N+YWGh8vPze3SunJwclZWVqbq6Wtu2bdPo0aMlSRdccMFJR2AklD8oHWxI/nUTzO6vk95/V+bam9yOAqCbWAMDAAAA6IFoNHrCfwMGDNDIkSM1YMCAzse6o7GxUU1NTZKcHUnWrFmj4uJiNTc3a9euXZLU+ViymUAwLRfxtGtXSJIM618AKYMRGAAAAEAPfPrTn+7W85555pnTPqehoUGPPvqootGorLWaOXOmysvL9fnPf15LliyRz+dTTk6OvvCFL/Q2duz8wbTcRtVWvykNHiadcabbUQB0EwUGAAAA0AM/+tGPOu+vWrVKy5Yt0zXXXNM5J/x3v/udpk+f3q1zlZSU6IEHHjjh8WnTpmnatGlxy9wj/oDUml67kNhQs7Rptczl/9S52wsA76PAAAAAAHpg8ODBnfeff/55LV68WDk5OZKcBehGjhype++9V7NmzXIrYnwEAlJbm2w4LJOZHj8+2HWrpHBYZvIMt6MAiAFrYAAAAAC91NzcrNbW1uMea2trU3NzGky98Aed23QahVG9TMrNk0rHup0EQAzSo0IFAAAAXHTJJZdo0aJFuvrqqzVo0CDV19frD3/4gy655BK3o/WeP+DctoSknFx3s8SBDR+RXbtSpvwCGV+G23EAxIACAwAAAOiluXPnatiwYXr99dfV0NCg/Px8zZ49WxUVFW5H6zUTCMpK6bOQ55Z1UqiJ6SNACqLAAAAAAHrJ5/Np1qxZqb/eRVc6ppCkyVaqtupNKdsvjZ/kdhQAMWINDAAAAKAHVq9e3a3nrVmzJsFJEuzYKSQpzkajzvapZVNk+mW7HQdAjCgwAAAAgB5YunRpt573gx/8IMFJEqx9BIYNpX6BoW010oF6po8AKYopJAAAAEAPtLS06Atf+MJpnxcOh5OQJoECHSMwUn8Kia1eJvl8MpPOdzsKgB6gwAAAAAB6YOHChd16njEmwUkSLJ2mkFQtk8acI5MGu6kAfREFBgAAANADEyZMcDtCcnQUGCm+C4mt3Sntfl/mkivdjgKgh1gDAwAAAMBJGV+Gs2tHik8hsavflCSZydNdTgKgp1wvMN544w3NmzdPn/rUp1RTU+N2HAAAAAAf5A+k/BQSW7VMGlEqM2iw21EA9JDrBcaZZ56pr33taxo/frzbUQAAAAB0xR9M6QLDNjZI72yWmcLoCyCVub4GxvDhw92OAAAAAOBU/AHZFF4Dw65eLlnL9qlAinO9wAAAAABSVSQS0YoVK7Rq1Spt27ZNTU1NysnJUUlJiaZMmaKpU6cqIyPD7Zi9l+JTSGzVMmnwMKm4xO0oAHohKQXGokWLdODAgRMev/766zV16tRun6eyslKVlZWSpMWLF6uwsDBuGbsrMzPTlevi5HhPvIX3w1t4P7yH98RbeD+8J5Xekz//+c/6zW9+o+HDh2v8+PEqLy+X3+9XS0uLduzYoZdeeklPPPGErrnmGs2aNcvtuL0TCEp1e9xO0SO2pVnauFrmsqtSf0tboI9LSoHxrW99Ky7nqaioUEVFRefHdXV1cTlvLAoLC125Lk6O98RbeD+8hffDe3hPvIX3w3vcek+KiopiPqa2tlb33Xef8vPzT/jctGnTJEkNDQ167rnnep3PbcYfTN0pJOurpPARdh8B0gBTSAAAAIAeuPHGG0/7nIEDB3breZ6XwlNIbNUyqf8AqZRNA4BU5/ouJG+99ZZuu+02bdmyRYsXL9b3v/99tyMBAAAAMbn55pu7fPzWW29NcpIECTgFhrXW7SQxseGw7JoVMudOlUmHtUiAPs71ERjTpk3rHGIHAAAApKJIJHLCY+FwWNFo1IU0CeAPSpGwFD4iZfVzO033bVknhZrYfQRIE64XGAAAAECqWrBggYwxOnLkiBYuXHjc5+rr6zVmzBiXksWZP+DchppTqsCw1cukftnShMluRwEQBxQYAAAAQA9dfvnlkqStW7fqsssu63zcGKO8vDydc845bkWLL3/QuW0JSQNOXLTUi6y1stVvSWVTZPplux0HQBxQYAAAAAA9dOmll0qSRo8ereLiYnfDJJAJBGUlqSWFdiLZXiM11Ml8fK7bSQDEieuLeAIAAACpaMWKFZ33T1VeHPu8lNU5hSR1diKxVcskn09m0vluRwEQJ4zAAAAAAHrgtdde0//8z//ooosu0oQJE1RUVKRAIKBQKKTdu3drw4YNeuWVV1RSUqLzz0/xH6KPnUKSImz1m9LoMpn+A9yOAiBOKDAAAACAHrjzzju1fft2/eUvf9GPfvQj7d27t/Nzw4YN05QpU/SVr3xFZ555posp4yTgjMCwLc0yLkfpDrt3l7Rzm8z1n3U7CoA4osAAAAAAemjEiBG65ZZbJEmtra1qampSTk6OsrPTbNHIY3chSQG2+k1Jkpk83eUkAOKJNTAAAACAXtq2bZuys7NVUFCQfuWFdHQKSWtqTCGxVW9KZ54tM2iI21EAxBEjMAAAAIBeWrx4sVpbWzVu3DhNmDBBEyZM0Nlnny1jUmHCRTdk+yVjUmIEhm08INVslPmn692OAiDOKDAAAACAXvrJT36iPXv2aOPGjdqwYYP+9Kc/6dChQxo3bpzmz5/vdrxeM8Y400hSYBFPu/otyVqZKTPcjgIgzigwAAAAgDgYOnSoIpGIwuGwwuGwqqurdfDgQbdjxY8/KLWkwAiM6jelQUOk4We5HQVAnFFgAAAAAL30gx/8QFu2bFFBQYEmTJigiy66SJ/97GcVaN+943Ta2tq0cOFChcNhRSIRzZgxQ9ddd52stfrlL3+pZcuWyefz6cMf/rCuuuqqBL+ak/AHZEPeHoFhW0LShmqZS69Mn+k7ADpRYAAAAAC99O6778rn86mkpEQlJSU666yzul1eSFJWVpYWLlwov9+vcDisBQsWaPLkydq5c6fq6+v1gx/8QD6fz90RHf6A90dgbKiSwkdkJjN9BEhHFBgAAABALz388MNqaGjoXAPjd7/7ndra2jR+/Hjddtttpz3eGCO/3y9JikQiikQiMsboz3/+s+688075fM7mgXl5eQl9HacUCHp+DQxb9abUP1caNd7tKAASgAIDAAAAiIOBAweqqKhI+/fv1/79+7V+/XpVVVV1+/hoNKp77rlHtbW1mj17tkaPHq09e/bo9ddf11tvvaUBAwbo5ptv1hlnnHHCsZWVlaqsrJTk7IhSWFgYU/bMzMzTHnMgL1/hQwdjPndvdSebJNlwWPvWrZB/2sXKGzo0Ccm6ny3ZvJpLIltPeDWXlPxsFBgAAABAL91///3atGmTAoGAJkyYoPLyct1www1dlg0n4/P59OCDD6qpqUkPPfSQtm/friNHjigrK0uLFy/Wm2++qZ/85Cf67ne/e8KxFRUVqqio6Py4rq4upvyFhYWnPSZqMmQPH4r53L3VnWySZDeulj18SG3jJyctY3ezJZtXc0lk6wmv5pISl62oqKjLxykwAAAAgF6aPn26br75Zg0ZMqTX58rJyVFZWZmqq6s1aNAgTZ8+XZI0bdo0/fjHP+71+XvM41NIbPWbUr9+0vgpbkcBkCA+twMAAAAAqe7SSy/tVXnR2NiopqYmSc6OJGvWrFFxcbGmTp2qdevWSZI2bNhw0t9KJkX7Ip7WWvcynIS1VrZ6mTRhikx2tttxACQIIzAAAAAAlzU0NOjRRx9VNBqVtVYzZ85UeXm5xo0bp4cfflgvvPCC/H6/Pv/5z7sXMhCUrJVaW5wyw0u2vyPtr5P56L+6nQRAAlFgAAAAAC4rKSnRAw88cMLjOTk5uvfee11I1IXs9tKiJeS5AsNWL5OMT2bSVLejAEggppAAAAAAOL1A0LltaXY3Rxds1TJp9ASZ3AFuRwGQQBQYAAAAAE7L+NsLjJC3FvK0+2qlndtkpkx3OwqABKPAAAAAAHB6HdNGPDYCw1a/KUky51JgAOmOAgMAAADA6QWOWQPDQ2z1Mmn42TKDh7kdBUCCUWAAAAAAOL32KSQ25J0RGPbQQentjUwfAfoICgwAAAAAp9cxhaTVOyMw7Jrlko3KTJ7hdhQASUCBAQAAAOD0OnYh8dIIjKpl0qAh0plnux0FQBJQYAAAAAA4vcwsKSPTM4t42qZD0vpVMlNmyBjjdhwASUCBAQAAAOC0jDHONBKPLOJp3/y7FA7LXHCF21EAJAkFBgAAAIDu8QekkEcKjNcqpZJRMkwfAfoMCgwAAAAA3RMIynpgCondXiNtf0fmwgq3owBIIgoMAAAAAN3jkSkk9rWXpMwsmWkfcjsKgCSiwAAAAADQPf6g67uQ2CNtssv+JnPeTJmc/q5mAZBcFBgAAAAAusUEgq6PwLDVb0nNh5k+AvRBFBgAAAAAuscDU0jsa3+RCgZL4ya5mgNA8lFgAAAAAOgef0BycRFPu3+ftKFa5sIrZHz8KAP0NXzVAwAAAOgef1BqbZGNRly5vH39ZclamQuucOX6ANxFgQEAAACge/wB57alJemXttGo7OsvSePPlSkcmvTrA3AfBQYAAACA7gkEnVs3ppG8vV7aV8vinUAfRoEBAAAAoHv87QVGKPkLedpXK6VAjsyUGUm/NgBvoMAAAAAA0C2mcwpJckdg2OYm2VWvyUz/kEy/7KReG4B3UGAAAAAA6J5AR4GR3BEYdvkrUlsb00eAPo4CAwAAAED3+N1ZA8O+VikVl0glo5J6XQDeQoEBAAAAoHvap5DYUPIKjPC2GundLTIXVcgYk7TrAvAeCgwAAAAA3dO5C0nyppCEXn5BysiUmX5p0q4JwJsoMAAAAAB0T3ZyF/G04SMK/e2P0rnTZHLzknJNAN5FgQEAAACgW0xmppTVL3nbqK5ZIdt4QL6LWLwTAAUGAAAAgFj4A0mbQhJ9rVK+gkJpwpSkXA+At1FgAAAAAOi+QDApU0jsgXpp7Ur5L7tKJiMj4dcD4H0UGAAAAAC6zx9Iyi4k9o2/STaqwOVXJ/xaAFJDptsBAAAAgL6ura1NCxcuVDgcViQS0YwZM3Tdddd1fv4Xv/iF/vrXv+qpp55yMWU7f1BqTewUEmut7GuV0ugJyiw6U6qrS+j1AKQGCgwAAADAZVlZWVq4cKH8fr/C4bAWLFigyZMna8yYMaqpqVFTU5PbEY8KBKX9+xJ7jZqN0p6dMldem9jrAEgpTCEBAAAAXGaMkd/vlyRFIhFFIhEZYxSNRvX0009r7ty5Lic8ymQnfhFP+2qllB2QKb8godcBkFoYgQEAAAB4QDQa1T333KPa2lrNnj1bo0eP1osvvqjy8nINHDjQ7XhHBRJbYNiWkOyKV2WmXizjDyTsOgBSDwUGAAAA4AE+n08PPvigmpqa9NBDD2nDhg1644039O1vf/u0x1ZWVqqyslKStHjxYhUWFsZ07czMzG4fc6hgkJpbQjFfo7tCLz2vxtYW5V99rfoVFsaULdm8ms2ruSSy9YRXc0nJz0aBAQAAAHhITk6OysrKtH79etXW1uqOO+6Q5Cz0efvtt+uRRx454ZiKigpVVFR0flwX46KXhYWF3T4mao10pE37anfLZGbFdJ3uiPzxt9KwYh0cNEymri6mbMnm1WxezSWRrSe8mktKXLaioqIuH6fAAAAAAFzW2NiojIwM5eTkqK2tTWvWrNHHPvYx/exnP+t8zg033NBleZF0HdM6WkJS//gWGLZ2p7R1g8wnPyNjTFzPDSD1UWAAAAAALmtoaNCjjz6qaDQqa61mzpyp8vJyt2N1zR90bkPNUv8BcT21fb1S8vlkZlwW1/MCSA8UGAAAAIDLSkpK9MADD5zyOU899VSS0pyaCQRkpbgv5GkjEdnX/ypNPF8mvyCu5waQHthGFQAAAED3HTuFJJ7Wr5IO7pfvoorTPxdAn0SBAQAAAKD7OqaQtDTH9bTR1yql3DzpnPPjel4A6YMCAwAAAED3BZwCw4biV2DYxgPS6rdkZl4uk8ksdwBdo8AAAAAA0H3Z8Z9CYpf9TYpEZC68Im7nBJB+KDAAAAAAdF8gvlNIrLWyr/5FGjlWpmhEXM4JID1RYAAAAADovmy/cxuK0wiM996Wdr8vcyGLdwI4NQoMAAAAAN1mfD5nGkmcppDYVyulfv1kpl4cl/MBSF8UGAAAAABiEwjEZQqJbW2VXf4PmfILZTqmpgDASVBgAAAAAIiNPyjFYRcSu+YtKdTM9BEA3UKBAQAAACA2/oBsaxymkKxfJQX7S6Mn9P5cANIeBQYAAACA2AR6PwLDWiu7vlpm/Lkyvow4BQOQzigwAAAAAMTGH4dFPHe/Lx2ol8qmxCcTgLRHgQEAAAAgJiYOBYbdUOWca8LkeEQC0AdQYAAAAACITRwW8bQbVktDi2UGDYlTKADpjgIDAAAAQGwCQamlWdbaHh1ujxyRNq9l9AWAmFBgAAAAAIiNPyBFo9KRtp4dX7NRamuVYf0LADGgwAAAAAAQG3/QuW3p2TQSu6FKysiQxp4Tx1AA0h0FBgAAAIDYBALObahnC3naDaulkWNlOooQAOgGCgwAAAAAMTH+9gKjBzuR2EMHpe01MhOYPgIgNhQYAAAAAGLTiykkduNqyVrWvwAQMwoMAAAAALEJtBcYPdlKdUOVFOwvlZTGNxOAtEeBAQAAACA22c4UEhvjFBJrrbP+xfhJMr6MRCQDkMYoMAAAAADEJtDDKSS1O6SGOta/ANAjFBgAAAAAYtOxBkaMu5DY9VWSJDNhcrwTAegDKDAAAAAAxKZfP8n4Yt6FxG6oloYUyRQOTVAwAOmMAgMAAABATIwxUiAQ0xQSe+SItHmtTBmjLwD0DAUGAAAAgNj5g7HtQvLOJqmtlfUvAPQYBQYAAACA2PkDsrGMwFhfJWVkSGMnJjAUgHRGgQEAAAAgdoFgTGtg2A3V0sixMh07mABAjCgwAAAAAMTOH+h2gWEPNUrba9h9BECvUGAAAAAAiJ0/0O01MOym1ZK1rH8BoFcy3Q4AAAAA9HVtbW1auHChwuGwIpGIZsyYoeuuu04PP/ywampqlJmZqdLSUn3uc59TZqY3voU3/qBsd6eQrK+SgjnSWaMSGwpAWvPG334AAABAH5aVlaWFCxfK7/crHA5rwYIFmjx5si666CLdfvvtkqQf/vCHevnllzVr1iyX07YLBLu1jaq11ln/Yvy5Mr6MJAQDkK5cLzCeeuoprVy5UpmZmRo6dKi++MUvKicnx+1YAAAAQNIYY+T3+yVJkUhEkUhExhidd955nc8ZNWqU6uvr3Yp4ovY1MGw0KuM7xcz02p1SQ53MhOuSlw1AWnK9wJg0aZLmzJmjjIwMPf300/rNb36juXPnuh0LAAAASKpoNKp77rlHtbW1mj17tkaPHt35uXA4rFdeeUU33XRTl8dWVlaqsrJSkrR48WIVFhbGdO3MzMyYj2kaNFiHJQ3KzZEvcPJfQDYve1mHJA268HJlxHiNnmZLFq9m82ouiWw94dVcUvKzuV5gnHvuuZ33x4wZo2XLlrmYBgAAAHCHz+fTgw8+qKamJj300EPavn27RowYIUl67LHHNH78eI0fP77LYysqKlRRUdH5cV1dXUzXLiwsjPmYaDQqSarfsUNm4KCTPi/y1qvSkCI1ZPSTYrxGT7Mli1ezeTWXRLae8GouKXHZioqKunzc9QLjWC+//LIuuOCCk36+t81yPHi5/eqreE+8hffDW3g/vIf3xFt4P7yH90TKyclRWVmZqqurNWLECD377LNqbGzU5z73ObejHc8fdG5bmiV1XWDY8BFpyzqZCy5PXi4AaSspBcaiRYt04MCBEx6//vrrNXXqVEnSr3/9a2VkZOjiiy8+6Xl62yzHg5fbr76K98RbeD+8hffDe3hPvIX3w3vcek9O9tu+ZGlsbFRGRoZycnLU1tamNWvW6GMf+5heeuklrV69WgsWLJDvVOtMuMD4A7KSdKqdSGo2S60tMhMmJysWgDSWlALjW9/61ik//7e//U0rV67UggULZIxJRiQAAADAMxoaGvToo48qGo3KWquZM2eqvLxc119/vQYPHqxvfOMbkqTp06fr2muvdTltu44RGKGT70RiN1RJPp80dlKSQgFIZ65PIamurtbvfvc7fec731F2drbbcQAAAICkKykp0QMPPHDC47/85S9dSNNNgWOnkHTNrq+SRo6T6XguAPSC6wXGz3/+c4XDYS1atEiSNHr0aO/N7wMAAABwPH9AkmRbQupqDLU93Chtr5H56KeTmwtA2nK9wHjkkUfcjgAAAAAgVp1TSLpeA8NuXCNZKzOe9S8AxIe3VgICAAAAkBraR2CcdArJhiopmCOdNTp5mQCkNQoMAAAAADEzWVlSZmaXu5BYa50FPMedK5OR4UI6AOmIAgMAAABAz/iDXY/AqN0p7a+TKWP6CID4ocAAAAAA0DOBYJfbqNoN/7+9e42Nqur3OP7bbYG2FFqmlCIgPhSLOdQHOVBCAZGrYMQXhhiiqIg3gkUJGg1wXoCJEpCLNA8UC4lB5I1IQiX4AhEJ4I0AhXIpWKQUJAdrhYHSCxVmZp0XhTlIBygjM2vTfj9v2rnszC9rt3uv/Z+11t4vSax/AeCuooABAAAAIDxtEmRCTSE5Uix1uk9OWmcLoQA0VxQwAAAAAIQnIaHRGhjGd0UqPSSn939bCgWguaKAAQAAACA88SGmkJSVSn/Vs/4FgLuOAgYAAACAsDjxIUZgHNkvxcRIvf5tKRWA5ooCBgAAAIDwJDS+C4k5UixlPCQnsa2lUACaKwoYAAAAAMJzw21UTc1F6dRx1r8AEBEUMAAAAACEJz5BunxZxu+XJJmjByVj5PRm/QsAdx8FDAAAAADhSUho+HltHYwj+6WEttK/Mu1lAtBsUcAAAAAAEJ74xIaf9XUyxjSsf/FffeTExtrNBaBZooABAAAAICxO/HUjMP74X8n7J+tfAIiYONsBAAAAANyjro3AuFQnc6pMklj/AkDEMAIDAAAAQHgSrptCcmS/lNZZTlpnu5kANFsUMAAAAACE5+oUElNTLZUelpPF9BEAkUMBAwAAAEB4rk0hObJf+usS618AiCgKGAAAAADCc/U2qqZ4txQTIz30b8uBADRnFDAAAAAAhKfN1buQXKqVevSSk9jWbh4AzRoFDAAAAABhcWJjpdZtGn5n+giACKOAAQAAACB8V+9EwgKeACItznYAAAAAAPewNglSwmXpX5m2kwBo5ihgAAAAAAhfl/vlJGU1TCcBgAiigAEAAAAgbDG5/yMZYzsGgBaAAgYAAACAsDmOIzmO7RgAWgAW8QQAAAAAAK5HAQMAAAAAALgeBQwAAAAAAOB6rIEBAAAAWHb58mXNnTtXPp9Pfr9fOTk5mjBhgiorK5WXl6fq6mplZGTorbfeUlwcXXgALRNHPwAAAMCyVq1aae7cuYqPj5fP59OcOXPUt29fff311xo3bpyGDBmiVatWadu2bRozZoztuABgBVNIAAAAAMscx1F8fLwkye/3y+/3y3EclZSUKCcnR5I0fPhw7dmzx2ZMALCKERgAAACACwQCAc2cOVMVFRUaO3as0tPTlZiYqNjYWEmSx+OR1+sNue3WrVu1detWSdKCBQvUsWPHO/rsuLi4O94mWsh259yaSyJbONyaS4p+NgoYAAAAgAvExMRo0aJFqq2t1eLFi3XmzJkmbzt69GiNHj06+Pjs2bN39NkdO3a8422ihWx3zq25JLKFw625pMhl69KlS8jnmUICAAAAuEjbtm2VlZWlY8eOqa6uTn6/X5Lk9Xrl8XgspwMAeyhgAAAAAJZdvHhRtbW1khruSHLw4EF17dpVWVlZ2rVrlyRp+/btys7OthkTAKxiCgkAAABg2fnz55Wfn69AICBjjAYNGqT+/furW7duysvL0xdffHxVOw8AAAuWSURBVKEePXpo5MiRtqMCgDUUMAAAAADLHnjgAS1cuLDR8+np6Zo/f76FRADgPo4xxtgOAQAAAAAAcCusgXGHZs2aZTsCbsA+cRf2h7uwP9yHfeIu7A/3YZ/Y4eZ2J9udc2suiWzhcGsuKfrZKGAAAAAAAADXo4ABAAAAAABcL/b9999/33aIe01GRobtCLgB+8Rd2B/uwv5wH/aJu7A/3Id9Yoeb251sd86tuSSyhcOtuaToZmMRTwAAAAAA4HpMIQEAAAAAAK5HAQMAAAAAALhenO0A95Li4mKtXr1agUBAo0aN0tNPP207Uou1YsUK7du3T8nJyVqyZIntOC3e2bNnlZ+frwsXLshxHI0ePVpPPvmk7Vgt2uXLlzV37lz5fD75/X7l5ORowoQJtmO1eIFAQLNmzZLH43H1LdFaimnTpik+Pl4xMTGKjY3VggULbEdq0Wpra1VQUKDTp0/LcRy98cYb6tWrl+1Yzc7t+rNXrlzR8uXLdeLECbVr104zZsxQp06dIp6rKX2JkpISLVy4MJhn4MCBeuaZZyKeTbr98cIYo9WrV2v//v1q06aNcnNzI74uwJkzZ7R06dLg48rKSk2YMEHjxo0LPhfNNgvVP6+pqdHSpUv1559/Ki0tTW+//baSkpIabbt9+3Zt2LBBkjR+/HgNHz484tnWrl2roqIixcXFKT09Xbm5uWrbtm2jbSN5rgiV68svv9R3332n9u3bS5Kee+459evXr9G2kb42DZVt6dKlOnPmjCSprq5OiYmJWrRoUaNtI3p+NWgSv99v3nzzTVNRUWGuXLli3n33XXP69GnbsVqskpISU1ZWZt555x3bUWCM8Xq9pqyszBhjTF1dnZk+fTr/H5YFAgFz6dIlY4wxV65cMbNnzzalpaWWU2HTpk0mLy/PzJ8/33YUGGNyc3NNVVWV7Ri4atmyZWbr1q3GmIbjVk1NjeVEzU9T+rObN282K1euNMYY88MPP5iPP/44Ktma0pc4fPiwtePn7Y4XRUVFZt68eSYQCJjS0lIze/bsKKZr2Levvfaaqays/Nvz0WyzUP3ztWvXmsLCQmOMMYWFhWbt2rWNtquurjbTpk0z1dXVf/s90tmKi4uNz+cL5gyVzZjInitC5Vq3bp3ZuHHjLbeLxrXp7a631qxZY9avXx/ytUi2GVNImuj48ePq3Lmz0tPTFRcXp8GDB2vPnj22Y7VYvXv3Dlm9hR0dOnQIfsuQkJCgrl27yuv1Wk7VsjmOo/j4eEmS3++X3++X4ziWU7Vs586d0759+zRq1CjbUQDXqaur09GjRzVy5EhJUlxcXMhvQvHPNKU/u3fv3uC33zk5OTp8+LBMFNb8v9f7Env37tVjjz0mx3HUq1cv1dbW6vz581H7/EOHDqlz585KS0uL2mfeKFT/fM+ePRo2bJgkadiwYSGvn4qLi9WnTx8lJSUpKSlJffr0UXFxccSzPfLII4qNjZUk9erVy8rfW7jXNNG4Nr1VNmOMfv75Zw0ZMuSufmZTMIWkibxer1JTU4OPU1NT9euvv1pMBLhTZWWlysvL9eCDD9qO0uIFAgHNnDlTFRUVGjt2rDIzM21HatE+++wzvfDCC7p06ZLtKLjOvHnzJEmPP/64Ro8ebTlNy1VZWan27dtrxYoVOnXqlDIyMjR58uRgIRZ3R1P6s9e/JzY2VomJiaqurg4OZ4+GW/Uljh07pvfee08dOnTQiy++qPvvvz9quW51vPB6verYsWPwcWpqqrxerzp06BCVbD/++ONNLyZttllVVVWwDVJSUlRVVdXoPTf+XXo8nqgXE7Zt26bBgwff9PVonyu++eYb7dy5UxkZGZo0aVKjQoLta9OjR48qOTlZ9913303fE6k2o4AB4K6pr6/XkiVLNHnyZCUmJtqO0+LFxMRo0aJFqq2t1eLFi/Xbb7+pe/futmO1SEVFRUpOTlZGRoZKSkpsx8FVH3zwgTwej6qqqvThhx+qS5cu6t27t+1YLZLf71d5ebleeeUVZWZmavXq1frqq6/07LPP2o6GKLtVX6JHjx5asWKF4uPjtW/fPi1atEj/+c9/opLLzccLn8+noqIiTZw4sdFrNtvsRo7juHI06IYNGxQbG6uhQ4eGfD3a+37MmDHBdUrWrVunzz//XLm5uRH7vHDcqmAmRbbNmELSRB6PR+fOnQs+PnfunDwej8VEgLv4fD4tWbJEQ4cO1cCBA23HwXXatm2rrKysuz4cE01XWlqqvXv3atq0acrLy9Phw4etdSDx/66dx5OTkzVgwAAdP37ccqKWKzU1VampqcGRYjk5OSovL7ecqvlpSn/2+vf4/X7V1dWpXbt2Ucl3u75EYmJicFROv3795Pf7dfHixahku93xwuPx6OzZs8HH0bxW2L9/v3r06KGUlJRGr9lsM6mhva5NpTl//nzIkTw3/l16vd6otd327dtVVFSk6dOn37S4Eu1zRUpKimJiYhQTE6NRo0aprKwsZCZb16Z+v1+7d+++5YiVSLYZBYwm6tmzp37//XdVVlbK5/Ppp59+UnZ2tu1YgCsYY1RQUKCuXbvqqaeesh0Hki5evKja2lpJDXckOXjwoLp27Wo5Vcs1ceJEFRQUKD8/XzNmzNDDDz+s6dOn247VotXX1wen89TX1+vgwYOMULIoJSVFqampwdXtDx06pG7dullO1fw0pT/bv39/bd++XZK0a9cuZWVlReVb86b0JS5cuBBcj+P48eMKBAJRKa405XiRnZ2tnTt3yhijY8eOKTEx0RXTR2y12TXZ2dnasWOHJGnHjh0aMGBAo/f07dtXBw4cUE1NjWpqanTgwAH17ds34tmKi4u1ceNGzZw5U23atAn5HhvniuvXTtm9e3fIKT82r00PHTqkLl26/G0Ky/Ui3WaOicaqPM3Evn37tGbNGgUCAY0YMULjx4+3HanFysvL05EjR1RdXa3k5GRNmDAhuPAXou+XX37RnDlz1L1792An52a3fEJ0nDp1Svn5+QoEAjLGaNCgQVG71RxuraSkRJs2beI2qpb98ccfWrx4saSGb5MeffRRzuuWnTx5UgUFBfL5fOrUqZNyc3NZsDsCQvVn161bp549eyo7O1uXL1/W8uXLVV5erqSkJM2YMUPp6ekRz3WzvsS1UQ1jxozR5s2btWXLFsXGxqp169aaNGmSHnrooYhnu9nxYsuWLcFsxhh9+umnOnDggFq3bq3c3Fz17Nkz4tnq6+uVm5ur5cuXB6fcXJ8rmm0Wqn8+YMAALV26VGfPnv3bbVTLysr07bffaurUqZIa1qAoLCyU1HAb1REjRkQ8W2FhoXw+X/A4k5mZqSlTpsjr9WrlypWaPXt2xM8VoXKVlJTo5MmTchxHaWlpmjJlijp06PC3XFLkr01vdr2Vn5+vzMxMjRkzJvjeaLYZBQwAAAAAAOB6TCEBAAAAAACuRwEDAAAAAAC4HgUMAAAAAADgehQwAAAAAACA61HAAAAAAAAArkcBAwAAAAAAuB4FDAAAAAAA4HoUMAAAAAAAgOtRwACAZqaiokIvv/yyTpw4IUnyer169dVXVVJSYjkZAAAAED4KGADQzHTu3FnPP/+8li1bpr/++kuffPKJhg0bpqysLNvRAAAAgLA5xhhjOwQA4O776KOPVFlZKcdxNH/+fLVq1cp2JAAAACBsjMAAgGZq1KhROn36tJ544gmKFwAAALjnUcAAgGaovr5ea9as0ciRI7V+/XrV1NTYjgQAAAD8IxQwAKAZWr16tTIyMjR16lT169dPq1atsh0JAAAA+EcoYABAM7Nnzx4VFxfr9ddflyS99NJLKi8v1/fff285GQAAABA+FvEEAAAAAACuxwgMAAAAAADgehQwAAAAAACA61HAAAAAAAAArkcBAwAAAAAAuB4FDAAAAAAA4HoUMAAAAAAAgOtRwAAAAAAAAK5HAQMAAAAAALje/wFcNImG5lJ0qwAAAABJRU5ErkJggg==\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "#plot trajectory\n", - "grid = plt.GridSpec(2, 3)\n", - "\n", - "plt.figure(figsize=(15,10))\n", - "\n", - "plt.subplot(grid[0:2, 0:2])\n", - "plt.plot(track[0,:],track[1,:],\"b+\")\n", - "plt.plot(x_sim[0,:],x_sim[1,:])\n", - "plt.axis(\"equal\")\n", - "plt.ylabel('y')\n", - "plt.xlabel('x')\n", - "\n", - "plt.subplot(grid[0, 2])\n", - "plt.plot(u_sim[0,:])\n", - "plt.ylabel('v(t) [m/s]')\n", - "\n", - "plt.subplot(grid[1, 2])\n", - "plt.plot(np.degrees(u_sim[1,:]))\n", - "plt.ylabel('w(t) [deg/s]')\n", - "\n", - "plt.tight_layout()\n", - "plt.show()" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.6.9" - } - }, - "nbformat": 4, - "nbformat_minor": 4 -} diff --git a/notebook/MPC_scipy_v2.ipynb b/notebook/MPC_scipy_v2.ipynb new file mode 100644 index 0000000..a74a033 --- /dev/null +++ b/notebook/MPC_scipy_v2.ipynb @@ -0,0 +1,616 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "plt.style.use(\"ggplot\")\n", + "import time\n", + "from scipy.interpolate import interp1d\n", + "from scipy.integrate import odeint\n", + "from scipy.optimize import minimize" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "differential drive kinematics model equations" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [], + "source": [ + "#Preliminaries\n", + "def compute_path_from_wp(start_xp, start_yp, step = 0.1):\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", + " return np.vstack((final_xp,final_yp))\n", + "\n", + "def get_nn_idx(state,path):\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", + " return target_idx\n", + "\n", + "def road_curve(state,track):\n", + " \n", + " #given vehicle pos find lookahead waypoints\n", + " nn_idx=get_nn_idx(state,track)\n", + " LOOKAHED=6\n", + " lk_wp=track[:,nn_idx:nn_idx+LOOKAHED]\n", + "\n", + " #trasform lookahead waypoints to vehicle ref frame\n", + " dx = lk_wp[0,:] - state[0]\n", + " dy = lk_wp[1,:] - state[1]\n", + "\n", + " wp_vehicle_frame = np.vstack(( dx * np.cos(-state[2]) - dy * np.sin(-state[2]),\n", + " dy * np.cos(-state[2]) + dx * np.sin(-state[2]) ))\n", + "\n", + " #fit poly\n", + " return np.polyfit(wp_vehicle_frame[0,:], wp_vehicle_frame[1,:], 3, rcond=None, full=False, w=None, cov=False)\n", + "\n", + "def f(x,coeff):\n", + " return round(coeff[0]*x**3 + coeff[1]*x**2 + coeff[2]*x**1 + coeff[3]*x**0,6)\n", + "\n", + "def df(x,coeff):\n", + " return round(3*coeff[0]*x**2 + 2*coeff[1]*x**1 + coeff[2]*x**0,6)" + ] + }, + { + "cell_type": "code", + "execution_count": 58, + "metadata": {}, + "outputs": [], + "source": [ + "from math import cos\n", + "# Define process model\n", + "def kinematics_model(xt,ut,K,dt=0.1):\n", + "\n", + " #current state\n", + " xp = xt[0]\n", + " yp = xt[1]\n", + " theta = xt[2]\n", + " etheta = xt[4]\n", + "\n", + " vt = ut[0]\n", + " wt = ut[1]\n", + "\n", + " #next state\n", + " xtp = xp + vt*cos(theta)*dt\n", + " ytp = yp + vt*np.sin(theta)*dt\n", + " thetatp = theta + wt*dt\n", + " ctetp = f(xp,K) - yp + vt*np.sin(etheta)*dt\n", + " ethetatp = theta - np.arctan(df(xp,K)) + wt*dt\n", + " \n", + " dqdt = [xtp,ytp,thetatp,ctetp,ethetatp]\n", + " return dqdt" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "simulate" + ] + }, + { + "cell_type": "code", + "execution_count": 63, + "metadata": {}, + "outputs": [], + "source": [ + "# time points\n", + "t = np.arange(0, 40, 0.1)\n", + "\n", + "#fake inputs\n", + "# u = [v(t),\n", + "# w(t)]\n", + "u = np.zeros((2,len(t)))\n", + "u[0,100:]=0.4\n", + "u[1,200:]=0.1\n", + "u[1,300:]=-0.0" + ] + }, + { + "cell_type": "code", + "execution_count": 64, + "metadata": {}, + "outputs": [], + "source": [ + "track = compute_path_from_wp([0,5,10],[0,0,2])\n", + "\n", + "# initial conditions\n", + "q0 = np.array([0,0,0,0,0])\n", + "K = road_curve(q0,track)\n", + "q0[3] = f(q0[0],K)\n", + "q0[4] = - np.arctan(df(q0[0],K))\n", + "\n", + "# store solution\n", + "x = np.empty_like(t)\n", + "y = np.empty_like(t)\n", + "theta = np.empty_like(t)\n", + "cte = np.empty_like(t)\n", + "psi = np.empty_like(t)\n", + "\n", + "# record initial conditions\n", + "x[0] = q0[0]\n", + "y[0] = q0[1]\n", + "theta[0] = q0[2]\n", + "cte[0] = q0[3]\n", + "psi[0] = q0[4]\n", + "\n", + "# solve ODE\n", + "for i in range(1,len(t)):\n", + " # span for next time step\n", + " q_t = kinematics_model(q0,u[:,i-1],K,dt=0.1)\n", + "\n", + " # store solution for plotting\n", + " x[i] = q_t[0]\n", + " y[i] = q_t[1]\n", + " theta[i] = q_t[2]\n", + " cte[i] = q_t[3]\n", + " psi[i] = q_t[4]\n", + " # next initial condition\n", + " q0 = q_t" + ] + }, + { + "cell_type": "code", + "execution_count": 65, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAagAAAEYCAYAAAAJeGK1AAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAADh0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uMy4xLjMsIGh0dHA6Ly9tYXRwbG90bGliLm9yZy+AADFEAAAgAElEQVR4nOzdeXxU1f3/8deZJCwhQJgJJGxRiCwFTAGDQlgEEi1VC4gIihuiVQvKV9sq4A+rYkEqIhYBNyJQsEpFqGJdICISiGgCJGwKREARCCEJSxZClnt+f4yMxCRkm8y9M/k8Hw8fj8zce2feM+H6yTn33HOU1lojhBBCWIzN7ABCCCFEeaRACSGEsCQpUEIIISxJCpQQQghLkgIlhBDCkqRACSGEsCR/swPUxrFjxyrdJyQkhMzMTA+kqZxkKZ83ZmnTpo0H0nhWReeTlX4/YL08YL1MVssDl85U0fnk1QVKCF+1aNEitm/fTvPmzZk7d26Z7VprlixZwo4dO2jYsCETJ06kY8eOAGzcuJHVq1cDMGrUKAYPHuzJ6EK4jXTxCWFBgwcP5sknn6xw+44dO0hPT2f+/Pk88MADLF68GIDc3FxWrVrFrFmzmDVrFqtWrSI3N9dTsYVwK2lBiXrFeGMO/Oa32AZeb3aUS+rWrRsZGRkVbk9OTmbQoEEopejcuTN5eXmcOnWKPXv2EBkZSVBQEACRkZGkpKQwYMAAT0UXJtM/fM/pN+dQUlBgdpRSjCf+Xu1jpECJekN/txOdlIDq2MXsKLWWnZ1NSEiI67HD4SA7O5vs7GwcDofrebvdTnZ2drmvER8fT3x8PACzZ88u9XoX8/f3r3CbGayWB6yV6fSbcyhMTcK/7WVmRynF32ar9nckBUrUC1prjA/ehmAH6tphZsexhNjYWGJjY12PK7qAbbUL7lbLA9bJpE9nYyRvIXDE7Zy/YazZcUoxGjep9iAJuQYl6oc9OyDtW9SNt6ICGpidptbsdnupkz0rKwu73Y7dbicrK8v1fHZ2Nna73YyIwgT6qw1gGDSOHW52FLeQAiV8ntYa478rwNEKNeA6s+O4RVRUFJs2bUJrzf79+wkMDKRFixb07NmT1NRUcnNzyc3NJTU1lZ49e5odV3iANgx0wjro3AP/Nu3NjuMW0sUnfF/qN/BDGuqeR1D+AWanqZKXX36ZvXv3kpOTw0MPPcSYMWMoLi4G4Prrr6dXr15s376dyZMn06BBAyZOnAhAUFAQt9xyC9OmTQNg9OjRrgETwsft3w0n01HDbzc7idtIgRI+TRsGxgf/hlatUf2Gmh2nyh599NFLbldKcf/995e7bejQoQwd6j2fVbiHTlgPgU1QvaPNjuI20sUnfNv2RPjpEOoPt6P8/MxOI0Sd0Hk56O2JqGsGoxo0NDuO20iBEj5LGyUYH74Drdujrh5odhwh6ozeuhGKi1AWv7+vuqRACZ+lv0mA40ewDb8dZZPWk/BNWmvn4IjLrkC172B2HLeSAiV8ki4pQa99B9p1AB/qkxeijMMH4OgPPtd6AilQwkfprzZAxnFsI8ahbPLPXPgunbAOGjREXT3I7ChuJ2eu8Dm6uAj90Uq4vBP89mqz4whRZ3TBOfQ3Cag+A1CNA82O43ZSoITP0ZvXQ1YGthF3oJQyO44QdUYnJcD5c6gBvte9B1KghI/RRYXo/70HV/wGuvcyO44QdUpvXg+t20NEV7Oj1AkpUMKn6C8/hdNZ0noSPk8f/QEO7kMNuM5n/61LgRI+Q58vQH/8HnSNRHWNNDuOEHVKb14Pfv5eNUNKdUmBEj5Df/E/yDmDbcQdZkcRok7poiL0V1+gevVFNW1mdpw6Y6kCZRgGTzzxBLNnzzY7ivAy+lw++rPV0KM36orfmB1HiDqld3wFeTmogb4xO39FLFWgPv74Y9q2bWt2DOGF9OcfQm4OtuHSehK+T29eD45W0PW3ZkepU5YpUFlZWWzfvp2YmBizowgvo/Ny0es+gJ7XoDp0MjuOEHVKn0yHb1NRA2J9/iZ0yyy3sXTpUu68807OnTtX4T7x8fHEx8cDMHv27Cqtb+/v71+l/TxBspSvtlly160m71we9nsmEVDLz2SV7yUlJYUlS5ZgGAYxMTGMHDmy1PalS5eyZ88eAAoLCzlz5gxLly4FYOzYsYSHhwPOpcinTJni0eyibunN8aBsqOhYs6PUOUsUqG3bttG8eXM6duzoOunKExsbS2zsL7+Uita3v1hISEiV9vMEyVK+2mTROWcxPlyJuqo/Z4KCoZafqapZ2rRpU6v3uRTDMIiLi2P69Ok4HA6mTZtGVFQU7dq1c+0zfvx418+ffPIJhw4dcj1u0KABc+bMqbN8wjy6pASdGO+81mo3/w+pumaJArVv3z6Sk5PZsWMHhYWFnDt3jvnz5zN58mSzowmL05+9D4XnUSPGmR3FbdLS0ggLCyM0NBSA6OhokpKSShWoi23ZsoUxY8Z4MqIwy+5tcDob27iHzE7iEZYoUOPGjWPcOOf/YPbs2cPatWulOIlK6TOn0F/8D3XNIFTr9mbHcZvs7GwcDofrscPh4MCBA+Xue/LkSTIyMujRo4fruaKiIqZOnYqfnx8jRozg6qvLn4+wql3mVun2vMBqecBzmU5/vZGiYDshQ4ah/Cv+37evfEeWKFBC1IT+ZBUUF6P+cJvZUUyzZcsW+vbti+2ii+WLFi3Cbrdz4sQJZsyYQXh4OGFhYWWOrWqXuZW6g8F6ecAzmfTpLIxtiajf3UzW6dOm56muS2WqqMvccgWqe/fudO/e3ewYwuJ0dib6y09Q0TGoVnV3PcgMdrudrKws1+OsrCzsdnu5+yYmJnLfffeVOR4gNDSUbt26cfjw4XILlPAuOnEDGAaqv2/f+3Qx3x6jKHyW/vg/oEHdNNbsKG4XERHB8ePHycjIoLi4mMTERKKiosrsd/ToUfLy8ujcubPrudzcXIqKigA4e/Ys+/btq/DalfAe2jCc9z51uRIV6lt/kF2K5VpQQlRGn0xHb16PGng9ytHK7DilnD17lk2bNrF9+3Z++OEH8vPzCQwM5LLLLqNnz54MHjyYZs0uPTWNn58fEyZMYObMmRiGwZAhQ2jfvj0rV64kIiLCVay2bNlCdHR0qYlCjx49yhtvvIHNZsMwDEaOHCkFyhfs2wUn01HDfWcwUFVIgRJeR/9vpfM+kBusNXLt7bffZvPmzfTq1YuhQ4fStm1bGjduzLlz5zh69Ch79+5lypQpDBgwgDvuuPSMF71796Z3796lnhs7tnRrsbyRe126dGHu3Lm1/zDCUvTm9RDYBNW7n9lRPEoKlPAqOv2oc5LMoTehWjgqP8CDHA4H8+fPJyAgoMy2Dh06MGDAAAoLC9mwYYMJ6YS30rln0dsTUYOGoRo0NDuOR8k1KOFV9Np3wT8A9ftbzI5SxrBhw1zF6XQFo6zy8/MZNmyYJ2MJL6e//tI5WtXHJ4YtjxQo4TX00R/RSZucradmLcyOc0n/93//V+7zjz32mIeTCG+mtUYnrIPLO6HadTA7jsdJgRJew1j7b2jYCPW7m82OUimtdZnn8vPzS92vJESlDu2Hoz/Uy9YTyDUo4SX0jwdhWyLqprGoIOsu0PanP/0JcE7geuHnC3Jzc+nfv78ZsYSX0pvXO/8ou3qQ2VFMIQVKeAXjw387RzFdN8LsKJf0yCOPoLXm+eef55FHHim1LTg4uE4nmRW+RRfko7/ZhIoagGoUaHYcU0iBEpanD+2H1G9QI+9EBQaZHeeSunXrBkBcXBwNG9avEVfCvXTSZjhfgBp4vdlRTCMd4sLyjP++DUFNUTE3mR3lkj7++GPXLA4VFaeioiI+/vhjT8YSXkonrIPW7aFjF7OjmEZaUMLS9IG9sHcHavS9lu/mOH36NJMnT6ZXr15069aNNm3a0KhRIwoKCjh27Bh79+5lx44dXHvttWZHFRanfzoMh/ajxt5XaqaQ+kYKlLAsrTXGf1dA8xaowTeYHadS48aN46abbmLjxo1s2LCBH3/8kby8PIKCgggPD6dXr17cfvvtNG3a1OyowuL05vXg74+6ZojZUUwlBUpY13c7Yf9u1G1/RHnJ9ZxmzZoxfPhwhg8fbnYU4aV0USF660ZUr36optYdseoJcg1KWJLWGuODt6FFCGrQ78yOI4TH6O1fQV4OakD9vPfpYtKCEta0ezt8/x3qzomogAZmp6m2/Px83nvvPfbu3UtOTk6pG3dfffVVE5MJq9Ob10NIKHSNNDuK6aQFJSzH1XpytEL1jzE7To0sXryYQ4cOMXr0aHJzc5kwYQIhISHceOONZkcTFqYzjsN3O1EDrkPJrCPSghIWlPI1/JCGGj8Z5V92ZnBvsHPnTubNm0fTpk2x2Wz06dOHiIgI/vGPf3DTTZUPl09JSWHJkiUYhkFMTAwjR44stX3jxo0sX77ctXrusGHDiImJcW1bvXo1AKNGjWLw4MHu/XCizugt8c6lZKK98w8zd5MCJSxFG4az9dSqDaqv945g0loTGOgcFt+oUSPy8/MJDg4mPT290mMNwyAuLo7p06fjcDiYNm0aUVFRZRYejI6OLrPce25uLqtWrWL27NkATJ06laioKIKCrH2DswBdUoLe8jlceZXllpIxi9vakEuXLuXw4cPuejlRT+ltic7JMYffjvLzMztOjV122WXs3bsXgK5du7J48WIWL15M69atKz02LS2NsLAwQkND8ff3Jzo6mqSkpCq9b0pKCpGRkQQFBREUFERkZCQpKSm1+izCQ3Ylw5lsbPV0YtjyuK0FZRgGM2fOpFmzZgwcOJCBAwficMhfAaLqtFGC/vDf0Lo9qs8As+PUyoMPPugaGHHvvffyzjvvkJeXx8MPP1zpsdnZ2aXOHYfDwYEDB8rs9/XXX/Ptt9/SunVr7rnnHkJCQsoca7fbyc7OdsMnEnXN2Lwemtvhyj5mR7EMtxWoCRMmMH78eHbs2EFCQgKrV6+mU6dODBo0iGuuuYZGjRq5662Ej9Jfb4L0n7A9NBVl897WE8DZs2fp1KkTAM2bN+ehhx4CnK0jd7jqqqvo378/AQEBrF+/noULF/L0009X6zXi4+OJj48HYPbs2YSEhJS7n7+/f4XbzGC1PFD7TCVZJ8nclUzgzXfSNDTU9Dx1oSaZ3HoNymazcdVVV3HVVVdx5MgR5s+fz6JFi1i8eDH9+/dnzJgxrou6QlxMFxej174D7TtAr75mx6m1v//97yxbtqzM8zNnzmTJkiWXPNZut5OVleV6nJWVVea8uXg2ipiYGFasWOE69kLXIjhbYxcmsP212NhYYmNjXY8zMzPL3S8kJKTCbWawWh6ofSbjf++BYVDQO5rzbvhs3vYdVTTLv1vHMebn57NhwwaeffZZnn76aa644gqeffZZ5s2bR6NGjZg1a5Y73074EP3VBjiZjm3EHV49vNYwDAzDcK6EqrXrsWEYHD9+HL8qXFeLiIjg+PHjZGRkUFxcTGJiIlFRUaX2OXXqlOvn5ORk1wCKnj17kpqaSm5uLrm5uaSmptKzZ0/3fkjhVtownKP3ulyJaiXLsVzMbS2ouXPnkpqaym9+8xuuu+46+vTpQ0DAL0OE7777bsaPH++utxM+RBcVoj9aCR06Q6R397/ffvvtrp9vu+22UttsNhs331z5asB+fn5MmDCBmTNnYhgGQ4YMoX379qxcuZKIiAiioqL45JNPSE5Oxs/Pj6CgICZOnAhAUFAQt9xyC9OmTQNg9OjRMoLP6vbtgpPpqBF3mJ3EcpQub23qGvjwww8ZNGgQwcHBFe5z/vx5t66Rc+zYsUr3sVJTV7KULzDpS3LemIvt0WdR3XuZmqWq30tFXRInT55Ea80zzzzDs88+i9YapRRKKZo1a0aDBtadFaOi88lK/1bAenmgdpmMN+ag9+zA9uJSt82a4m3fUUXnk9taUFWZHLOi4pSZmcnChQs5ffo0SiliY2O54Qbrz14tak8XnifvvWVwRTfoZl5XlHEyHT54m+y8HIwmTWHEHdhahlX7dVq2bAnAokWLnK9rGJw5c4YWLVq4Na/wDTr3LHrHV6hrf++VU3rVNUvcqOvn58ddd91Fx44dOXfuHFOnTiUyMrLMjYnC9+gvP0WfysR23589vu6NcTIdvXIxHNgL5/JAa4oubDy4D+OxGTUqUgB5eXksXryYrVu34u/vz/Lly0lOTiYtLa1M15+ov/TWjVBcjBoQW+m+9ZElrka3aNGCjh07AtC4cWPatm0r927UA7rgHPqTVTSIjEJ16eHR9y75bhf66Ych9RvIz4Vf93T/3KKqqTfffJPAwEAWLVqEv7/z78DOnTuTmJhYm9jCh2itnRPDduiMatfB7DiWZIkW1MUyMjI4dOgQV1xxRZltVb1v42JWuh9AspSW9/6/yM05Q7O7HsLPA1mK04+R89bLFH67E3LPVrq/f14O9hrm2rVrF6+//rqrOIFzragzZ87U6PWEDzq4zzlryt2V37xdX1mqQBUUFDB37lzGjx/vmsfsYlW9b+NiVrpYKFl+ofNzMVavgB5X4XdFtzrPUvLdLpj/LBQVVvmY4iZNq31R94LAwEBycnJKXXvKzMyUa1HCRW9eDw0bef2sKXXJMgWquLiYuXPnMnDgQK655hqz44g6pj/7L+TnYrv5zjp7j1LXmPJzq3dwyzCoxbDfmJgY5s6dy2233YbWmv379/POO+9w3XUyz5oAXZCPTkpA9RmIalT2j3HhZIkCpbXmtddeo23btlVaikB4N33mFDr+A+fJGR5RJ+9RkxYTAP4B0L0Xauz9NR4gATBixAgaNGhAXFwcJSUlvPrqqzI6VbjopM1wvkBWza2EJQrUvn372LRpE+Hh4Tz++OOA84bH3r17m5xM1AX9v/9AcVGd3JjoajXtTCo78OFSlIIukTj+7ylO+9d+uK9SihtuuEEKkiiXTlgHbcKhYxezo1iaJQpU165d+c9//mN2DOEBOv0n9KbPnCuGhrpnWpcL9zDpoz/AsR/BMKp+sL8/dO/tajH5h4SAm66HHTt2jMOHD1NQUFDq+aFDh7rl9YV30j8dgkP7UWPv9/itFd7GEgVK1A9aa4x33oAGDd3Weir5bhcseA7OF1S+88V+bjGpuyfVqiuvIqtXr+b999/nsssuK3ODuhSo+k1vjgd/f1TfwWZHsTwpUMJztifC3hTUuAdRzSqeEqsypVpMPx2u3sG/ajHVlY8//phZs2Zx2WWX1dl7CO+jiwrRX32B6tUPFdTM7DiWJwVKeIQ+l4+xMg7CO6KuHVbj17Fqi+nXGjRoQNu2bev8fYR30du/gvxc1MDrzY7iFaRACY/QKxfD6WxsD02p9mKEtWoxKQWRfeq8xQTOefcuGDt2LG+99Ra33norzZs3L7WfzYuXExG1oxPWOW9h6HKl2VG8ghQoUed06jfoLfGoG25FVXPUUo1bTAANG8HDT+HX1TP/M7h4qY0LPv/88zLPrVy50hNxhMXojGOwbxdq5J1eveaZJ0mBEnVK55zB+NcCaHc56g9VmyS1Vi0mgPYdUG3CazwjeU0tWLAAcA4G2bp1K/369Su1XWvN119/7bE8wlr05nhQNlT/GLOjeA0pUKLOaKMEY/FcyM/D9tizKP+ASo/xphbTr11YagPg/fffL3cJmtWrV/OHP/yh0tdKSUlhyZIlGIZBTEwMI0eOLLX9o48+4vPPP8fPz49mzZrxpz/9yfX+Y8eOJTw8HHBOaTVlypTafCzhBrqkBJ34OURGoYIdZsfxGlKgRJ3Ra1c6R+3d/fAlZ2suTj+GsfQVr2sxlWf37t0AlJSUuH6+4MSJEzRu3LjS1zAMg7i4OKZPn47D4WDatGlERUWVWn7m8ssvZ/bs2TRs2JB169axYsUKHnvsMcA5QGPOnDlu/FSi1nYlw5lT2GTmiGqRAiXqhN61Df2/lajomEtO51Ly3S6yFv4dCs5V/01MbjGV59VXXwWgqKjI9TM4Z5YIDg5mwoQJlb5GWloaYWFhhIaGAhAdHU1SUlKpAtWjxy/Lk3Tq1ImEhAR3fQRRB4yEddDcDldGmR3Fq0iBEm6njxzCeOMF53WncQ+VuVveW68xVcXChQsB5/Wohx+u2TIK2dnZOBy/dAM5HA4OHDhQ4f4bNmygZ89fViMuKipi6tSp+Pn5MWLECK6++upyj6vq8jVWWJrlYlbLA5fOVJJ1kszd22hy850E/fxHh5l5zFKTTFKghFvpU1kY82dAo0Bsj/wN9atZFLz5GlN11LQ4VdemTZs4ePAgzzzzjOu5RYsWYbfbOXHiBDNmzCA8PJywsLKFvKrL15i9NMuvWS0PXDqT8b/3wDA417s/BR7K7W3fUUXL10iBEm6j83KdxelcPrYps1EtnK0AX24x1QW73U5WVpbrcVZWFna7vcx+O3fuZM2aNTzzzDMEBASUOh4gNDSUbt26cfjw4XILlKh72jCc6z51jUS1am12HK8jBUq4hc7Pw3j5aUg/gm3SdFR756CI+tJicqeIiAiOHz9ORkYGdrudxMREJk+eXGqfQ4cO8eabb/Lkk0+WuhE4NzeXhg0bEhAQwNmzZ9m3bx8jRozw9EcQF3y3EzJPoG6+y+wkXkkKlKg1XZCPMf9ZOHIQ25+moUPboBfPlRZTDfn5+TFhwgRmzpyJYRgMGTKE9u3bs3LlSiIiIoiKimLFihUUFBTw0ksvAb8MJz969ChvvPEGNpsNwzAYOXJkqcEVwrP05vXQpCmqV1+zo3glKVCiVnTOWYxXZsAPadgefAKjYWN4drK0mGqpd+/eZdZDGzt2rOvnp556qtzjunTpwty5c+s0m6ganXMWveMr1LW/RwXUfo2x+kgKlKgxnZXh7NbLzICI32CsfbdGLSa/Dp0xWrWuty0m4Zv0119AcbGsmlsLUqBEjegfvsdY8Bycy3dOyHpgT/Vf5OcWU8iAIZYbcSREbWit0QnroUNnVLvLzY7jtaRAiWor+Ww1vL8MbDYoKan+C9Tza0yiHji4D479iLrbM7cb+CopUKLKdFEhxhtzIOXnCU+rW5zkGpOoJ3TCOmjYGNVnoNlRvJoUKFEp42Q6+t+vO4fMFhdV/wWkxSTqEX0uH52UgLrmWlSjyudeFBWTAiUuqWRPCrwyA0qKq3+wtJhEPaSTEqDwvAyOcAMpUKIM18wP338HmSeq/wLSYhL1mN68HtpeBh06mx3F60mBEqWUfLcL5j8LRYXVP1haTKKe0z8dgkP7Ubf9scwkyaL6pECJX1pMP6RB+tHqv4C0mIQAcA4t9w9A9R1sdhSfIAWqniv5die88iwU1WDwg7SYhHDRhefRW79A9e6HatLU7Dg+QQpUPWScTOfUGy9Qsn8PnDlV/ReQFpMQZegdWyE/TwZHuJFlClRKSgpLlizBMAxiYmIYOXJkrV7vQrdVZnYmJRnHnXPDFReBfwAEBIBhgNbg5+dsPVS0zY37nfAPcI6Gq8rruTtTYSEUFzofGwY1uMIkLSYhLkEnrIOWYdBFzg93sUSBMgyDuLg4pk+fjsPhYNq0aURFRdV4FmbjZDp63t/gZDplbiUtLoKK5jG91Daz9nP3e9WEtJiEuKTiY0dg3y7UzXehbDaz4/gMSxSotLQ0wsLCCP15OeTo6GiSkpJqvkzAB2/DyXQ3JqynpMUkRJWc+/wjsNlQ0UPNjuJTLFGgsrOzcTgcrscOh4MDBw6U2S8+Pp74+HgAZs+eXeH69tl5OdTgkr8AQOHXoRMB7S+nye0P4B9W/lLM7uTv71/h79LTrJKlsi7voqIiFixYwMGDB2natCmPPvoorVq1AmDNmjVs2LABm83GvffeS8+ePc34CPWGLi6m4IuP4cooVLCj8gNElVmiQFVVbGwssbGxrscVzYBtyAiamvm5xUTXKykCTgN4YJbxkJAQy8xmXtUsbdrUXeGuSpf3hg0baNKkCa+88gpbtmzh7bff5rHHHuOnn34iMTGRl156iVOnTvHcc8/xz3/+E5t0O9Wd3ckYp7Kw3THR7CQ+xxIFym63k5WV5XqclZWF3W6v+QuOuMM5m7B081VN6/ao8I5yjckiqtLlnZyczK233gpA3759eeutt9Bak5SURHR0NAEBAbRq1YqwsDDS0tLo3LlmsxoYH7/HqSMHKSms0bCaOnGqQQNL5eHoD9jsIdCjd+X7imqxRIGKiIjg+PHjZGRkYLfbSUxMZPLkyTV+PVvLMIzHZsAHb2O7MIqvsMA54u3CaDdtgPHzCLfiooq3uXM//wAwiqv2enWVyWZzjuTz94fAIBj/f3KNyWKq0uV98T5+fn4EBgaSk5NDdnY2nTp1cu1nt9vJzs4u932q0mWeow2KTmXhr3WtP5e7aKUslYfmLQi66VYa/vwHhRVYpav6YjXJZIkC5efnx4QJE5g5cyaGYTBkyBDat29fq9e0tQyD+//ild1HnmClLMIcVeoyv3EsIfdMstS/FYcF/+02tFgmK57fl8pUUZe5JQoUQO/evendW5rIQlSly/vCPg6Hg5KSEvLz82natGmZY7Ozs2vXXS6EieTKqRAWc3GXd3FxMYmJiURFRZXa56qrrmLjxo0AbN26le7du6OUIioqisTERIqKisjIyOD48eNcccUVJnwKIWrPMi0oIYRTRV3eK1euJCIigqioKIYOHcqCBQt45JFHCAoK4tFHHwWgffv29OvXjz//+c/YbDbuu+8+GcEnvJbS2kpXG4UQQggnn//TaurUqWZHcJEs5ZMs1ma178RqecB6mayWB2qWyecLlBBCCO8kBUoIIYQl+T3zzDPPmB2irnXs2NHsCC6SpXySxdqs9p1YLQ9YL5PV8kD1M8kgCSGEEJYkXXxCCCEsyWfug6rN8gTulJmZycKFCzl9+jRKKWJjY7nhhhtK7bNnzx5eeOEF1/tfc801jB492u1ZACZNmkSjRo2w2Wz4+fkxe/bsUtu11ixZsoQdO3bQsGFDJk6cWCddA8eOHWPevHmuxxkZGYwZM4Ybb7zR9Vxdfi+LFi1i+/btNG/enLlz5wKQm5vLvHnzOHnyJC1btuSxxx4jKCiozLEbN25k9erVAIwaNYrBgwe7JZM3cPdK19VVm3HiT9MAACAASURBVN9bXajo/DYzU2FhIU8//TTFxcWUlJTQt29fxowZQ0ZGBi+//DI5OTl07NiRRx55BH9/z/0v3zAMpk6dit1uZ+rUqTXLo31ASUmJfvjhh3V6erouKirSf/3rX/WRI0dK7fPpp5/q119/XWut9ebNm/VLL71UJ1mys7P1999/r7XWOj8/X0+ePLlMlt27d+vnn3++Tt7/1yZOnKjPnDlT4fZt27bpmTNnasMw9L59+/S0adPqPFNJSYm+//77dUZGRqnn6/J72bNnj/7+++/1n//8Z9dzy5cv12vWrNFaa71mzRq9fPnyMsfl5OToSZMm6ZycnFI/1wdVOa/qWk1/b3WlovPbzEyGYehz585prbUuKirS06ZN0/v27dNz587Vmzdv1lpr/frrr+vPPvvMY5m01nrt2rX65Zdfdp3TNcnjE118Fy9P4O/v71qe4GLJycmuv3z79u3L7t270XVw+a1FixauFkjjxo1p27ZthbNJW0FycjKDBg1CKUXnzp3Jy8vj1KlTdfqeu3btIiwsjJYtW9bp+1ysW7duZf6iTUpK4tprrwXg2muvLfNvBpwtiMjISIKCgggKCiIyMpKUlBSPZDZbVc6rulbT31tdqej8NjOTUopGjRoBUFJSQklJCUop9uzZQ9++fQEYPHiwRzNlZWWxfft2YmJiAGdPTU3y+EQXX22WJ2jWrFmd5crIyODQoUPlzoW2f/9+Hn/8cVq0aMFdd91V69nbL2XmzJkAXHfddaVmrwbn93LxFPgOh4Ps7GxatGhRZ3m2bNlC//79y93mye/lzJkzrs8ZHBzMmTNnyuzz639bl1q+wtdUdaVrT6vK780TLj6/zc5kGAZTpkwhPT2d3/3ud4SGhhIYGIifnx/g+X+3S5cu5c477+TcuXMA5OTk1CiPTxQoKyooKGDu3LmMHz+ewMDAUts6dOjAokWLaNSoEdu3b2fOnDnMnz+/TnI899xz2O12zpw5w9///nfatGlDt27d6uS9qqK4uJht27Yxbty4Mts8+b38mlIKpZRH3ku4j1m/t0ud32ZkstlszJkzh7y8PF588UWOHTvm0fe/2LZt22jevDkdO3Zkz549tXotn+jiq87yBECp5QnqQnFxMXPnzmXgwIFcc801ZbYHBga6muS9e/empKSEs2fP1kmWC99D8+bN6dOnD2lpaWW2X7xGS61XM67Ejh076NChA8HBwWW2efJ7Aed3cqE789SpU+W2puvz8hVuX+naTarye6tL5Z3fZme6oEmTJnTv3p39+/eTn59PSUkJ4Nl/t/v27SM5OZlJkybx8ssvs3v3bpYuXVqjPD5RoGqzPIG7aa157bXXaNu2LTfddFO5+5w+fdp1/SstLQ3DMOqkWBYUFLia2AUFBezcuZPw8PBS+0RFRbFp0ya01uzfv5/AwEDTuvc89b1cEBUVxZdffgnAl19+SZ8+fcrs07NnT1JTU8nNzSU3N5fU1FR69uxZZ5mspCrnlRmq8nurKxWd32ZmOnv2LHl5eYBzRN/OnTtp27Yt3bt3Z+vWrYBzJKqnfnfjxo3jtddeY+HChTz66KP06NGDyZMn1yiPz9you337dpYtW+ZanmDUqFGllicoLCxkwYIFHDp0yLU8QWgdLNH83Xff8be//Y3w8HBXAbz99ttdrZTrr7+eTz/9lHXr1uHn50eDBg24++676dKli9uznDhxghdffBFwthoHDBjAqFGjWLdunSuL1pq4uDhSU1Np0KABEydOJCIiwu1ZwFkkJ06cyIIFC1zdIhdnqcvv5eWXX2bv3r3k5OTQvHlzxowZQ58+fZg3bx6ZmZmlhgZ///33rF+/noceegiADRs2sGbNGsA5zHzIkCFuyeQNyjuvPKk6vzdPqOj87tSpk2mZfvjhBxYuXIhhGGit6devH6NHj+bEiRO8/PLL5Obm0qFDBx555BECAgI8kumCPXv2sHbtWqZOnVqjPD5ToIQQQvgWn+jiE0II4XukQAkhhLAkKVBCCCEsSQqUEEIIS5ICJYQQwpKkQAkhhLAkKVBCCCEsSQqUEEIIS5ICVY+kp6dz7733cvDgQcA5H9Z9991X6wkdhRCiLkiBqkfCwsK44447eOWVVzh//jyvvvoq1157Ld27dzc7mhBClCFTHdVD//jHP8jIyEApxfPPP+/x+bmEEKIqpAVVD8XExHDkyBGGDRsmxUkIYVlSoOqZgoICli1bxtChQ3nvvffIzc01O5IQQpRLClQ9s2TJEjp27MhDDz1E7969eeONN8yOJIQQ5ZICVY8kJSWRkpLCH//4RwDuueceDh06REJCgsnJhBCiLBkkIYQQwpKkBSWEEMKSpEAJIYSwJClQQgghLEkKlBBCCEuSAiWEEMKSpEAJIYSwJClQQgghLEkKlBBCCEuSAiWEEMKSpEAJIYSwJClQQgghLEkKlBBCCEuSAiWEEMKSpEAJIYSwJH+zA1yQkpLCkiVLMAyDmJgYRo4cWekxx44dK/f5kJAQMjMz3R2xVqyWSfJU7lKZ2rRpU6fvvWjRIrZv307z5s2ZO3dume1aa5YsWcKOHTto2LAhEydOpGPHjgBs3LiR1atXAzBq1CgGDx5cpff0lvPJannAepmslgdqdj5ZogVlGAZxcXE8+eSTzJs3jy1btvDTTz+ZHUsI0wwePJgnn3yywu07duwgPT2d+fPn88ADD7B48WIAcnNzWbVqFbNmzWLWrFmsWrWK3NxcT8UWwq0s0YJKS0sjLCyM0NBQAKKjo0lKSqJdu3bVfi29PZGz33+HUVDgfEJdtFGVelDuj6Wfr+Dn6rzez/vkNG6Mca6gmu9ZhX0qed+K9slt0gQjL9/5oFkwqu1l0O5yVONAhPm6detGRkZGhduTk5MZNGgQSik6d+5MXl4ep06dYs+ePURGRhIUFARAZGQkKSkpDBgwwFPRhcl0+lHOrlqCkZ9ndpRSjIcer/YxlihQ2dnZOBwO12OHw8GBAwfK7BcfH098fDwAs2fPJiQkpMw+uacyOffNJuf/hy9aLLjChYMvfr7UPrrsjxVuL2ffXz04p/Uvjyp7n1q+V8Wf6Re//qerAWx+BPwmkoZ9+tP42mHYgu3lHlsX/P39y/19msmKmS7Izs4ulc3hcJCdnV3mXLLb7WRnZ5f7GlU5n8B634PV8oC1Mp351yucS9yArVkLs6OU4qd1tb8jSxSoqoqNjSU2Ntb1uNz+zJjhtBw7ocy2cto/HmWlPmH98z+UzMxMZwE7nQVHf0Af2EvRrm0ULV1A7vLXUFdFo2641dm6qmNW+n4uMPMalCdU6XzCer8bq+UB62TSuWcxvvqCxsNupnDk3WbHKUU3Car2+WSJAmW328nKynI9zsrKwm733F/v9Y1SyvUfSoG9Jdhboq6MglF3o48fQX/5KXpLPDopAXXNYNTNd6Hs1vgLUTjPmYtP9gvnjN1uZ+/eva7ns7Oz6datmxkRhQn01o1QXEzj2OEUmh3GDSwxSCIiIoLjx4+TkZFBcXExiYmJREVFmR2r3lKt22O77Y/Ynn8Tdf1I9LYtGE9PwvjiY7RhmB1PAFFRUWzatAmtNfv37ycwMJAWLVrQs2dPUlNTyc3NJTc3l9TUVHr27Gl2XOEBWmv05vVweScCLr/C7DhuYYkWlJ+fHxMmTGDmzJkYhsGQIUNo37692bHqPRXUDDX6XvS1v8dYsQj979fQ2xOx3f8XVHNr9W/7mpdffpm9e/eSk5PDQw89xJgxYyguLgbg+uuvp1evXmzfvp3JkyfToEEDJk6cCEBQUBC33HIL06ZNA2D06NGuARPCxx3aD0d/QN010ewkbqN0haMHrM9b7tsA62Wqbp4Lf53pd9+Axk2w/fGvqC5XmpbHE3z9GtSvecv5ZLU8YI1Mxr8WoL/ZhO3FpbRsF256nl/z2vughPUppbANvB7bk3OhcROMeX/DSPzc7FhCCEAX5KO/2YSKGoBq5Du3ikiBEtWi2l6Gbdoc6NwDveSfGGvfrXgIvxDCI3TSZjhfgBp4vdlR3EoKlKg2FdgE2+S/ofoNRX/4b/S7b0qREsJEOmEdtG4PHbuYHcWtLDFIQngf5R8A9/4fNGmKjv/A+eRtf3QOXRdCeIz+6TAc2o8ac5/PnX9SoESNKaVgzARQoNd/4Lynauz9PneSCGFlevN68PdH9R1idhS3kwIlakUpBbdOAI2zJdW0OerGMWbHEqJe0EWF6K0bUb36oZo2MzuO20mBErXmLFL3Qu4Z9H9XYATbsfWPrfxAIUSt6O1fQV4OasB1ZkepE1KghFsomw3ueQR99gz6XwvQze2oHr3NjiWET9Ob10NIKHSNNDtKnZBRfMJtlH8Atj9NgTaXYbwxB32i/Bs/hRC1pzOOw3c7UQOuc/6B6IN881MJ06hGgdgmPQl+NoyFM9EF+WZHEsIn6S3xoGyo6Bizo9QZKVDC7VRIKLYHp8CJoxhx82SCWSHcTJeUoLd8DldehWrhqPwALyUFStQJ1TUSNeY+SPka/en7ZscRwrfsSoYz2dgG+ubgiAukQIk6o4behOozEP3B2+jvvzM7jhA+w9i8Hpq3gB6+vSyRFChRZ5RSqDsngr0lxpsvovNyzY4khNfTp7JgZzIqOgbl79sDsX370wnTqcAm2B54HOMfUzD+tQDbQ1NkpokqSElJYcmSJRiGQUxMDCNHjiy1fenSpezZsweAwsJCzpw5w9KlSwEYO3Ys4eHhgHOJgylTpng0u6hbOvFz0AZqgO/faygFStQ51aEz6ua70KuWorfE++xNhe5iGAZxcXFMnz4dh8PBtGnTiIqKol27dq59xo8f7/r5k08+4dChQ67HDRo0YM6cOZ6MLDxEG4bz3qcuV6Ja+d6aZL8mXXzCI9R1I6HLleiVi9FZJ82OY2lpaWmEhYURGhqKv78/0dHRJCUlVbj/li1bGDBggAcTCtPs2wWZJ3xuWY2KSAtKeISy2bDd8wjGs5Mxls3H9tgM6eqrQHZ2Ng7HL0OHHQ4HBw4cKHffkydPkpGRQY8ePVzPFRUVMXXqVPz8/BgxYgRXX311ucfGx8cTHx8PwOzZswkJCSl3P39//wq3mcFqecBzmU5/8yWFQU1ped1NqAYNTc9THTXJJAVKeIxqGYYafS/67VfRX36KGvx7syN5vS1bttC3b19sF80ksGjRIux2OydOnGDGjBmEh4cTFhZW5tjY2FhiY3+5jlHRctxWWM78YlbLA57JpHPPYmzdiLr292SdzQFyTM1TXbLku7A8de0w6NYTvWoJ+mS62XEsyW63k5WV5XqclZWF3W4vd9/ExET69+9f5niA0NBQunXrxuHDh+ssq/AcvfULKC6uF4MjLpACJTxKKYXtnkfAZsNYvlBW4i1HREQEx48fJyMjg+LiYhITE4mKKnu/y9GjR8nLy6Nz586u53JzcykqKgLg7Nmz7Nu3r9TgCuGdtNbohPXQoTOqXQez43iMdPEJj1P2lqib70b/+zX011+i+g42O5Kl+Pn5MWHCBGbOnIlhGAwZMoT27duzcuVKIiIiXMVqy5YtREdHl7qWd/ToUd544w1sNhuGYTBy5EgpUL7g4D449iPqrklmJ/EoKVDCFOra36G/2oD+Txz6yqvAYhd0zda7d2969y69XMnYsWNLPR4zpuzCkF26dGHu3Ll1mk14nt68Hho2Ql090OwoHiVdfMIUyuaH7a5JkJeDfn+Z2XGEsCxdkI9OSkD1GYhqFGh2HI+SAiVMo9p3QMWOQCeso3BvqtlxhLAk/U0CnC+olze4S4ESplLDbwd7S86+9gK6uMjsOEJYjt68HtqEQ8cuZkfxOClQwlSqYSNs4x6k5Mgh9OcfmR1HCEvRPx2CQ/tRA6+vlze2S4ESplO/vZoGUf3Ra99Fn86q/AAh6gm9OR78/evtSNcqjeI7c+YMqampHD58mPz8fAIDA7n88suJjIwkODi4VgGWL1/Otm3b8Pf3JzQ0lIkTJ9KkSZNavabwPk0n/B9Zk8eh31+Guu/PZscRwnS6qBD91ReoXv1QQc3MjmOKSxaon376iZUrV7Jnzx46duxI27ZtCQ4O5ty5c2zatImlS5fSvXt3xo4dW+N7LSIjIxk3bhx+fn6sWLGCNWvWcOedd9botYT38m/dDnX9KPTH/0EPGobq1M3sSLWWmZnJDz/8QF5eHk2aNOGyyy6z3Pxowrr09q8gP7feTAxbnksWqEWLFjF8+HAmT55MQEBAme1FRUUkJyfz6quvMnPmzBoF+O1vf+v6uXPnzmzdurVGryO8n7phNHrrBox/v47tqZdQNj+zI1VbcXEx8fHxrF+/noyMDMLCwmjUqBEFBQWkp6fTqlUrrrvuOmJjY/H38cXmRO3ohHUQEgpdrjQ7imkueYbMmjXrkgcHBATQr18/+vXr55YwGzZsIDo6usLt3jr7MlgvkxXztGzbjoIJj3Lmxek02baZwN/fYnqm6n5Hjz/+OD169OCBBx6gU6dOpSZxNQyDtLQ0EhISeOKJJ3jppZfcHVn4CJ1xDPbtQo28E2Wrv0MFqvwn3AsvvMATTzxR5vkXX3yRv/71r5c89rnnnuP06dNlnr/tttvo06cPAKtXr8bPz4+BAyu+U9pbZ18G62Wyah7d+UroGknOitfJ69oL1dS8vveazL78zDPP0Lx583K32Ww2OnfuTOfOnTl79qzbcgrfozfHg7Kh+seYHcVUVS5QF5aXrurzF3vqqacuuX3jxo1s27aNv/3tb/VyKKX4hVIK220PYMyYjP7vcq+be+zi4vThhx8yfPjwMvt89NFH3HTTTZ6MJbyILi52LuseGYUKdlR+gA+rtECtXLkScPatX/j5ghMnTtCyZctaBUhJSeGDDz7g2WefpWHDihfgEvWHahuOGvoH9Ocfogf9DnXZFWZHqpH333+/3AL1/vvvS4ESFdudDGdOYauHM0f8WqUF6sK6NIZhlFqjBpxdIOVNWFkdcXFxFBcX89xzzwHQqVMnHnjggVq9pvB+6g+3ob/50jlgYso/vKoffvfu3YDznLnw8wUnTpygcePGZsQSXsJIWA/N7XBl2SVW6ptKC9TEiRMB5wi7i6//uMsrr7zi9tcU3k8FNkHdcg96yT/RW79ARXtPX/yrr74KQGFhoetncHZfBgcHM2HCBLOiCYvTp7Jg1zbU729B+XnfKFZ3u2SBOn36tOtG3EsVp4v3E8JdVN8h6E2foVctRffsiwr0jhu4Fy5cCMCCBQt4+OGHa/QaKSkpLFmyBMMwiImJYeTIkaW2b9y4keXLl7tWzx02bBgxMTGubatXrwZg1KhRDB48uIafRHiaTvwctIHqX39Wzb2USxaoGTNm0K1bNwYNGsQVV1xR7pDZTZs28e2338oaNMLtlM2G7fYHMWb+Gb32XdTY+8yOVC01LU6GYRAXF8f06dNxOBxMmzaNqKioMjfDR0dHc999pb+T3NxcVq1axezZswGYOnUqUVFRBAUF1exDCI/RhuGcGLZrJKpVa7PjWMIlC9QLL7xAfHw8r7/+OhkZGbRq1YrGjRtz7tw5102I1113HePHj/dQXFHfqMsiUAN/h96wFj3gOlTbcLMjXdK0adMYPnw4ffr0KfdG3OLiYr755hs++uijCu8zTEtLIywsjNDQUMBZiJKSkqo0W0tKSgqRkZGughQZGUlKSgoDBgyoxacSHvHdTsg8gbr5LrOTWMYlC5S/vz/Dhg1j2LBhZGZm8uOPP5Kfn++atuVC94IQdUndfCc6eTPGu29g+/Nzlr4VYdKkSaxcuZLFixfToUMH2rRp45pJ4vjx4xw8eJAePXq4ru2WJzs7G4fjl+HFDoeDAwcOlNnv66+/5ttvv6V169bcc889hISElDnWbreTnZ3t3g8p6oTevB6aNEX16mt2FMuo8n1QISEhlpp5QNQfKqiZs0i9/Rps2wJR1m0NtGvXjr/85S+cPn2anTt38uOPP5KTk0OTJk0YNGgQDz/8cIU38lbHVVddRf/+/QkICGD9+vUsXLiQp59+ulqv4a0zs1gtD9Q+k3H2NCd3bCVw2M00bV3+TeCezFMXapKpygWqqKiIVatWsWXLFnJycli2bBmpqakcP36cYcOGVTusENWhBv0OvekzjP+8he3KKFTDRmZHuqTg4GAGDRpUo2PtdnupWzqysrLK9FY0bdrU9XNMTAwrVqxwHbt3717XtuzsbLp1K3/iXW+dmcVqeaD2mYz4D6C4iIKrBnDeDZ/N276jimZmqfLNJcuWLePIkSNMnjzZ1cXSvn171q1bV4OoQlSPsvlhG/cgnMpEf/ye2XEqdHFx2L17d4X/XUpERATHjx8nIyOD4uJiEhMTiYoqfU/MqVOnXD8nJye7rk/17NmT1NRUcnNzyc3NJTU1lZ49e7rxEwp301qjN62DDp1R7S43O46lVLkF9c033zB//nwaNWrkKlDSvy08SV3RzTn0fN0adP8YVKvad4W4W1xcnGtE68X3QF1MKcWCBQsqfA0/Pz8mTJjAzJkzMQyDIUOG0L59e1auXElERARRUVF88sknJCcn4+fnR1BQkOuaVlBQELfccgvTpk0DYPTo0TKCz+oO7oPjR1B312zUpy+rcoHy9/fHMIxSz509e7ZUV4MQdU3dcg86ZSvGyjj8Hrn0HI9muPh2iwv3Q9VE79696d27d6nnxo4d6/p53LhxjBs3rtxjhw4dytChQ2v83sKzdMI6aNgY1afiibLrqyp38fXt25cFCxaQkZEBOLsY4uLiLrk8hhDupoLtqD/cBjuT0DuTzI5TLbt37y7VBSiEPpePTkpAXT0Q1UimwPq1KheocePG0apVK/7yl7+Qn5/P5MmTadGiBaNHj67LfEKUoYbeBGHtMFYuRhcVmR2nQk8//TTfffcdAP/973/55z//yT//+U/XLA9C6KQEKDyPkolhy1WtLr7x48czfvx4V9eele9HEb5L+Qdgu/2PGPOeRq//L+qGW82OVK4jR47QuXNnAD7//HOefvppGjVqxFNPPcWoUaNMTiesQCesg7aXQYfOZkexpCq3oO69917Xz82aNXMVp/vvv9/9qYSohOrWC3r3Q//vP+jsk2bHKZfWGoD09HTAeY9USEgIeXl5ZsYSFqGPHILDB1ADr5c/9itQ5QJVUlJS5rni4uIyAyeE8BTbrRNAa/SqpWZHKVeXLl146623WL58uWvl6PT0dBlYJICfZ47wD0D1HWx2FMuqtIvvwiq3RUVFZe5Uz8rKcnVhCOFpKiQU9fvR6A//7VzYsGuk2ZFKmTRpEmvXrqVZs2auhQuPHTvGDTfcYHIyYTZdeN65jEzvfqgm8gdLRSotUBeGq6alpTFkyBDX80opmjdvzpVXXll36YSohPrdzegt8Rjvvolt+jxUORO0mqVx48bYbDYSEhJYu3YtLVq0IDo6Wq4/CfT2ryA/TwZHVKLSs/nCWjIJCQm0bt2aLl26uLbt27eP5cuXy2zmwjSqQUNst92PsXAWeuPHqNiyS6yb5c033+T48eNMmDCBli1bcvLkSdasWUN2dvYlJ4sVvk9vXg8tw6CL/IF/KVW+BnX48GEiIiJKPdexY0c2b97s9lBCVMtvr4HuvZxdfWdPVb6/hyQlJTFlyhR69epFu3bt6NWrF0888QRJSd51/5ZwL33iGOzbhRpwHcpW5f8F10tV/naUUmUGRBiG4RqpJIRZlFLYbvsjFBaiV//L7DguwcHBnD9/vtRzhYWFtGjRwqREwgr0lvVgs6GiZbaPylS5w75r1668++673HnnndhsNgzD4L333qNr1651mU+IKlFh7VCxw9GfrUYPGobq2KXyg+rYoEGDmDVrFsOGDcPhcJCVlcVnn33GoEGDSk0Y26NHDxNTCk/SxcXoxA1wZRQq2FH5AfVclQvUvffey+zZs3nwwQdd06a3aNGCKVOm1GU+IapM3TQG/fVGjH+/ju3JF03vPlm/fj0Aa9asKfP8hW2VTRwrfMyuZDhzCtvA35mdxCtUuUA5HA7+8Y9/kJaWRlZWFg6HgyuuuAKb9KEKi1CNAlGj70UvnoveEo8aeL2peWozWazwTUbCOgi2Q4/ele8sql6gAGw2m9z3JCxNXT0I/eUn6NX/QveORjWRpSaENejsTNi9HfX70Sg/P7PjeAVp/gifopTCdvuDkJeL/uBts+MI4aITPwdtoAbEVr6zAKrZghLCG6j2HVCDf4/e+Al64PWo9h3MjlRtKSkpLFmyBMMwiImJYeTIkaW2f/TRR3z++ef4+fnRrFkz/vSnP9GyZUvAuW5UeHg44FxmW64Tm08bhvPep9/8FtUyzOw4XkMKlPBJasQd6KQEjHdex/b48141GadhGMTFxTF9+nQcDgfTpk0jKirKtaw7wOWXX87s2bNp2LAh69atY8WKFTz22GMANGjQgDlz5pgVX5Tnu1TIykDdco/ZSbyKdPEJn6SaBKFG3Q0H9qK/2WR2nGpJS0sjLCyM0NBQ/P39iY6OLnNzb48ePWjYsCEAnTp1Ijs724yooop0wnpo0hTVs6/ZUbyKZVpQa9euZfny5SxevJhmzZqZHUf4ANU/Fv3lp+hVS9C/vdprVizNzs7G4fjlHhmHw8GBAwcq3H/Dhg307NnT9bioqIipU6fi5+fHiBEjuPrqq8s9Lj4+nvj4eABmz55NSEhIufv5+/tXuM0MVssDl85knD3NyZStBP7+Fpq2bm16HrPUJJMlClRmZiY7d+603BcqvJuy2bCNexDj+cfR//uPT3avbNq0iYMHD/LMM8+4nlu0aBF2u50TJ04wY8YMwsPDCQsre90jNjaW2NhfLthnZmaW+x4X7nu0CqvlgUtnMtZ/AMXFFFw1kPMeyu1t31GbNm3Kfd4SXXzLli3jjjvu8KrrBMI7qI5dUP1j0Os/QKf/ZHacKrHb7WRlZbkeZ2VlYbfby+y3c+dOSyE3BwAACrFJREFU1qxZwxNPPEFAQECp4wFCQ0Pp1q0bhw8frvPMonxaa+equRFdUW3DzY7jdUxvQSUlJWG327n88ssr3ddbuyTAepnqU56S+x8ja8dW/FcvI/ipl6r8h5BZ31FERATHjx8nIyMDu91OYmIikydPLrXPoUOHePPNN3nyySdp3ry56/nc3FwaNmxIQEAAZ8+eZd++fYwYMcLTH0Fc8P13cPwI6p5HzE7ilTxSoJ577jlOnz5d5vnbbruNNWvWMH369Cq9jrd2SYD1MtW7PH+4ncKVi8n8/H9VvlBdky4Jd/Dz82PChAnMnDkTwzAYMmQI7du3Z+XKlURERBAVFcWKFSsoKCjgpZdecmWdMmUKR48e5Y033nDNlzly5MhSo/+EZ+nN66BhY1TUALOjeCWlTZyO/Mcff2TGjBmu0UhZWVm0aNGC559/nuDg4EqPP3bsWLnPW+1/vmC9TPUtjy4uxnjuUSg8j+3ZBagGDWuVqS4LlFm85XyyWh4oP5M+l4/x13tQ11yL7e6HTc9jtpqcT6Z28YWHh7N48WLX40mTJvH888/LKD7hdsrfH9vtD2DMnY7+bA3qD7eZHUn4OJ20CQrPmz4npDezxCAJITxBdY1ERQ1Af7IKnXnC7DjCx+lN66Dd5XB5J7OjeC1LFaiFCxdK60nUKXXrvaAUxntvmR1F+DD940H4IQ014HoZnVwLlipQQtQ1ZW+JuuFW2P4Veu8Os+MIH6U3rwf/AFTfa82O4tWkQIl6R11/M7RqjfHOm+jiIrPjCB+jC8+jv96I6h2NatLU7DheTQqUqHdUQAC2sfdD+k/oDR+ZHUf4GL39K8jPQw2SwRG1JQVK1Esqsg9E9kF/+C76tEy0KtxHJ6yDVq2hcw+zo3g9KVCi3rKNvQ9KitDvLzM7ivAROv0o7N+NGnCdDI5wAylQot5Srdqgrh+F3voFOm2v2XGED9Bb4sFmQ/UbanYUnyAFStRr6obRYA/B+PfraKPE7DjCi+niYuey7pF9UMFlJ/cV1ScFStRrqmEjbLdOgCOHnDdWClFTO5Pg7GlsMnOE20iBEuKq/tDlSvR/V6Bzz5qdRngpY/N6CHZA995mR/EZUqBEvaeUwnb7g3AuD/3fFWbHEV6oJPME7N6O6h+D8vMzO47PkAIlBKDahqOG3oTe9Bn6h+/NjiO8zLkNH4M2UP1jK99ZVJnpCxYKYRXqD7ejv/4S453XsT0x29QsKSkpLFmyBMMwiImJYeTIkaW2FxUVsWDBAg4ePEjTpk159NFHadWqFQBr1qxhw4YN2Gw27r33Xnr27GnGR6g3tGFwLn4tdOuJahlmdhyfIi0oIX6mApugbhkP33+H3rrRtByGYRAXF8eTTz7JvHnz2LJlCz/9VHq5+g0bNtCkSRNeeeUVbrzxRt5++20AfvrpJxITE3nppZf4f//v/xEXF4dhGGZ8jPrj21SMk+moATI4wt2kBSXERVS/IehNn6LfX4oRe6MpGdLS0ggLCyM0NBSA6OhokpKSSq2Mm5yczK233gpA3759eeutt9Bak5SURHR0NAEBAbRq1YqwsDDS0tLo3LlzjbIYGz/5/+3dTWgTaRgH8P8kcW1jakxqEQmVtR8X42HBlLYHqR8BQTxJ6aIIK4qnNaUWwfSivYgFCc2CkXhZKj156qEnoYcWpFtQIwgRq2SldNe2sZnapia1ycyzh2LUTW2rxnnfDs/vljJh/pn04ZmvzIOF5L/Ql5a+/4OVyEJZmVR56O9xKBVOKL80io5iOtygGPuEYrGsDDb8oxv5iQRQZfzkXFVVUVlZWXhdWVmJly9ffnEZq9UKu92OdDoNVVVRX/9x/pDb7Yaqrv4op6GhIQwNDQEAenp6sHPnzqJlFmb+wfvYX1CEzd0u9l6BVHkUAI7W31C+e7foKAU2m23V71Okb8nEDYqx/1F+roel50/85PEAko3NLiW/3w+//+NF/VXHcf96AVW/d0k1PlzGceblkmWScRt9y8h3vgbF2CqUrVuFrdvtdiOVShVep1IpuN3uLy6jaRoymQwqKiqK3quqatF7GdssuEExJpna2lpMTU0hmUwin89jdHQUPp/vs2UOHDiA4eFhAMDY2Bi8Xi8URYHP58Po6ChyuRySySSmpqZQV1cn4FMw9v34FB9jkrFarTh37hyuX78OXddx+PBhVFdX4969e6itrYXP58ORI0dw69YtBAIBOBwOdHR0AACqq6vR3NyMzs5OWCwWnD9/HhYL74eyzUkhIokuNzLGGGMrTLlrFQwGRUcoIlsmzrM+GTOJINt2kC0PIF8m2fIA35bJlA2KMcbY5scNijHGmJSs3d3d3aJD/Ag1NTWiIxSRLRPnWZ+MmUSQbTvIlgeQL5NseYCvz8Q3STDGGJMSn+JjjDEmJW5QjDHGpGS6H+quN0fnR7t9+zZisRicTidCoRAAYHFxEb29vXjz5g2qqqpw6dIlOBwOQ/LMzs4iEong7du3UBQFfr8fx48fF5ppeXkZ165dQz6fh6ZpaGpqQltbG5LJJMLhMNLpNGpqahAIBGCzGfcvqus6gsEg3G43gsGg8Dwy4Hr6HNfTxpWknshENE2jixcv0vT0NOVyObp8+TJNTk4amiEej1MikaDOzs7C3/r7+2lgYICIiAYGBqi/v9+wPKqqUiKRICKiTCZD7e3tNDk5KTSTruuUzWaJiCiXy1FXVxeNj49TKBSiBw8eEBHRnTt36P79+4ZlIiIaHBykcDhMN27cICISnkc0rqdiXE8bV4p6MtUpvk/n6NhstsIcHSPt27evaM/p4cOHaGlpAQC0tLQYmsnlchXunCkvL4fH44GqqkIzKYqCsrIyACsPOtU0DYqiIB6Po6mpCQBw6NAhQzOlUinEYjEcPXoUAEBEQvPIgOupGNfTxpSqnkx1vmIjc3REmJ+fh8vlAgDs2LED8/PzQnIkk0m8evUKdXV1wjPpuo4rV65genoax44dw65du2C322G1WgGsPcfoR+jr68OZM2eQzWYBAOl0WmgeGXA9rY3r6ctKVU+mOoLaDBRFgaIohq93aWkJoVAIZ8+ehd1uF57JYrHg5s2biEajSCQSeP36taHr/9Tjx4/hdDql/N0IWxvX0wqz1pOpjqA2MkdHBKfTibm5ObhcLszNzWH79u2Grj+fzyMUCuHgwYNobGyUItMH27Ztg9frxYsXL5DJZKBpGqxWq6FzjMbHx/Ho0SM8efIEy8vLyGaz6OvrE5ZHFlxPq+N6Wlsp68lUR1AbmaMjgs/nw8jICABgZGQEDQ0Nhq2biBCNRuHxeHDixAkpMi0sLODdu3cAVu5Aevr0KTweD7xeL8bGxgAAw8PDhn13p0+fRjQaRSQSQUdHB/bv34/29nZheWTB9VSM62l9pawn0z1JIhaL4e7du4U5OidPnjR0/eFwGM+ePUM6nYbT6URbWxsaGhrQ29uL2dlZw29Bff78Oa5evYo9e/YUTjucOnUK9fX1wjJNTEwgEolA13UQEZqbm9Ha2oqZmRmEw2EsLi5i7969CAQC2LJliyGZPojH4xgcHEQwGJQij2hcT5/jevo631tPpmtQjDHGzMFUp/gYY4yZBzcoxhhjUuIGxRhjTErcoBhjjEmJGxRjjDEpcYNijDEmJW5QjDHGpPQfI17dkVbPllIAAAAASUVORK5CYII=\n", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#plot trajectory\n", + "plt.subplot(2, 2, 1)\n", + "plt.plot(x,y)\n", + "plt.scatter(track[0,:],track[1,:])\n", + "plt.ylabel('y')\n", + "plt.xlabel('x')\n", + "\n", + "#plot x(t)\n", + "plt.subplot(2, 2, 2)\n", + "plt.plot(t,theta)\n", + "plt.ylabel('theta(t)')\n", + "#plt.xlabel('time')\n", + "\n", + "\n", + "#plot y(t)\n", + "plt.subplot(2, 2, 3)\n", + "plt.plot(t,cte)\n", + "plt.ylabel('cte(t)')\n", + "#plt.xlabel('time')\n", + "\n", + "#plot theta(t)\n", + "plt.subplot(2, 2, 4)\n", + "plt.plot(t,psi)\n", + "plt.ylabel('psi(t)')\n", + "#plt.xlabel('time')\n", + "#plt.legend(loc='best')\n", + "\n", + "plt.tight_layout()\n", + "plt.show()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "mpc" + ] + }, + { + "cell_type": "code", + "execution_count": 75, + "metadata": {}, + "outputs": [], + "source": [ + "# Define Objective function\n", + "def objective(u_hat,*args):\n", + " \"\"\"\n", + " Computes objective function\n", + " \n", + " :param u_hat: array_like, input [v,w\n", + " v,w\n", + " ...]\n", + " \"\"\"\n", + " \n", + " #undo input flattening\n", + " u_hat = u_hat.reshape(2, -1).T\n", + " se = np.zeros(PRED_HZN) #squared_errors\n", + " \n", + " # Prediction\n", + " for k in range(PRED_HZN):\n", + " \n", + " # Initialize state for prediction\n", + " if k==0:\n", + " q_hat0 = args[0]\n", + " K=args[1] #road curve\n", + " \n", + " # Clamp control horizon\n", + " elif k>CTRL_HZN:\n", + " u_hat[k,:] = u_hat[CTRL_HZN,:]\n", + " \n", + " #DEBUG\n", + "# print(\"k : {}\".format(k))\n", + "# print(\"q_hat0 : {}\".format(q_hat0))\n", + "# print(\"ts : {}\".format(ts_hat))\n", + "# print(\"u_hat : {}\".format(u_hat[k,:]))\n", + " \n", + " q_hat = kinematics_model(q_hat0,u_hat[k,:],K,dt=0.1)\n", + " cte=q_hat[3]\n", + " psi=q_hat[4]\n", + " \n", + " q_hat0 = q_hat[:]\n", + "\n", + " if k >0:\n", + " delta_u_hat = np.sum(u_hat[k,:]-u_hat[k-1,:])\n", + " else:\n", + " delta_u_hat = 0\n", + "\n", + " se[k] = 100 * (cte)**2 + 15 *(psi)**2 + 15 * (delta_u_hat)**2\n", + "\n", + " # Sum of Squared Error calculation\n", + " obj = np.sum(se[1:])\n", + " return obj" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "TODO: add heading error" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "test optimization" + ] + }, + { + "cell_type": "code", + "execution_count": 76, + "metadata": {}, + "outputs": [], + "source": [ + "#PARAMS\n", + "v=1.5\n", + "vb=0.5\n", + "wb=0.5\n", + "\n", + "# Define horizons\n", + "PRED_HZN = 20 # Prediction Horizon\n", + "CTRL_HZN = 15 # Control Horizon\n", + "\n", + "delta_t_hat = 0.1 #time step" + ] + }, + { + "cell_type": "code", + "execution_count": 77, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + " fun: 84.46152413856359\n", + " jac: array([-1.65424156, -5.46248531, -4.66883278, -3.61091423, -7.25656319,\n", + " -9.97307396, -7.68648052, -5.46970558, -3.82968616, 0.67185783,\n", + " -1.15515804, -1.96808815, 1.28362656, -2.83778381, -0.42825508,\n", + " -0.31342316, 0. , 0. , 0. , 0. ,\n", + " 38.85329056, 29.67042637, 24.17370987, 19.24147987, 10.30806732,\n", + " 3.07283115, 1.61050224, 0.68769073, -0.09304619, 2.58471298,\n", + " -0.30147457, -1.62229347, 1.39114475, -2.71041679, -0.22286892,\n", + " 1.22416592, 0. , 0. , 0. , 0. ])\n", + " message: 'Iteration limit exceeded'\n", + " nfev: 5103\n", + " nit: 101\n", + " njev: 101\n", + " status: 9\n", + " success: False\n", + " x: array([ 1.64242978, 1.69757121, 1.81361202, 1.90182763, 1.90182763,\n", + " 1.90182763, 1.90182763, 1.90182763, 1.83511965, 1.84792843,\n", + " 1.68088567, 1.43951262, 1.44726228, 1.25067572, 1.25506942,\n", + " 1.37310177, 1.37310177, 1.37310177, 1.37310177, 1.37310177,\n", + " -0.5 , -0.5 , -0.49058099, -0.47680101, -0.47680101,\n", + " -0.47680101, -0.38569852, -0.26192364, -0.07803742, 0.00765328,\n", + " 0.14826226, 0.33421738, 0.29494089, 0.39434771, 0.37513876,\n", + " 0.25069961, 0.25069961, 0.25069961, 0.25069961, 0.25069961])\n", + "time elapsed: 3.1107125282287598\n" + ] + } + ], + "source": [ + "starting_pos=np.array([0,0.25,0.15])\n", + "track = compute_path_from_wp([0,5,10],[0,0,2])\n", + "K = road_curve(starting_pos,track)\n", + "\n", + "# initial conditions\n", + "q0 = np.array([0,0,0,0,0])\n", + "q0[3] = f(q0[0],K)\n", + "q0[4] = - np.arctan(df(q0[0],K))\n", + "\n", + "#starting guess\n", + "u_hat0 = np.zeros((PRED_HZN,2))\n", + "u_hat0[:,0]=v\n", + "u_hat0[:,1]=0.1\n", + "u_hat0=u_hat0.flatten(\"F\")\n", + "\n", + "bnds=((v-2*vb,v+vb),)\n", + "for i in range (PRED_HZN-1):\n", + " bnds=bnds+((v-2*vb,v+vb),)\n", + " \n", + "bnds=bnds+((-wb,wb),)\n", + "for i in range (PRED_HZN-1):\n", + " bnds=bnds+((-wb,wb),)\n", + "\n", + "# print(u_hat0)\n", + "# print(u_hat0.reshape(2, -1).T)\n", + "\n", + "start = time.time()\n", + "\n", + "solution = minimize(objective,u_hat0,args=(q0[:],K,),method='SLSQP',bounds=bnds,options={'maxiter':100})\n", + "\n", + "end = time.time()\n", + "\n", + "print(solution)\n", + "print(\"time elapsed: {}\".format(end-start))" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "check what the optimizer returns" + ] + }, + { + "cell_type": "code", + "execution_count": 78, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "u=solution.x.reshape(2,-1).T\n", + "x=[]\n", + "y=[]\n", + "theta=[]\n", + "x.append(starting_pos[0])\n", + "y.append(starting_pos[1])\n", + "theta.append(starting_pos[2])\n", + "\n", + "for i in range(1,np.shape(u)[0]):\n", + " \n", + " # store solution for plotting\n", + " x.append(x[-1]+u[i,0]*np.cos(theta[-1])*0.1)\n", + " y.append(y[-1]+u[i,0]*np.sin(theta[-1])*0.1)\n", + " theta.append(theta[-1]+u[i,1]*0.1)\n", + " \n", + "plt.plot(x,y)\n", + "plt.plot(track[0,:],track[1,:])\n", + "plt.ylabel('y')\n", + "plt.xlabel('x')\n", + "\n", + "plt.tight_layout()\n", + "plt.show()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "compute MPC on the whole path" + ] + }, + { + "cell_type": "code", + "execution_count": 83, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "SCIPY Optimization Time: Avrg: 0.2300s Max: 3.1533s Min: 0.0260s\n" + ] + } + ], + "source": [ + "curr_pos=np.array([0,0.25,0.15])\n", + "start_wpx=[0,5,7.5,8,10,15]\n", + "start_wpy=[0,0,5,10,10,12]\n", + "track = compute_path_from_wp(start_wpx,start_wpy)\n", + "x=[]\n", + "y=[]\n", + "theta=[]\n", + "x.append(curr_pos[0])\n", + "y.append(curr_pos[1])\n", + "theta.append(curr_pos[2])\n", + "\n", + "opt_time=[]\n", + "\n", + "# Initialize input for prediction horizon\n", + "# u=[v1,v2,...,vp\n", + "# w1,w2,...,wp]\n", + "\n", + "# Initial guess \n", + "# u_hat0=[v1,v2,..vp,w1,w2,...,wp]\n", + "# uhat0 -> u_hat=optimize(obj,u_hat0)\n", + "\n", + "u_hat0 = np.zeros((PRED_HZN,2))\n", + "u_hat0[:,0]=v\n", + "u_hat0[:,1]=0.01\n", + "u_hat0=u_hat0.flatten(\"F\")\n", + "\n", + "# Optimization Bounds\n", + "# bnds=((v1_min,v1_max),...,(vp_min,vp_max),(w1_min,w1_max),...,(wp_min,wp_max))\n", + "\n", + "bnds=((v-2*vb,v+vb),)\n", + "for i in range (1,PRED_HZN):\n", + " bnds=bnds+((v-2*vb,v+vb),)\n", + " \n", + "bnds=bnds+((-wb,wb),)\n", + "for i in range (1,PRED_HZN):\n", + " bnds=bnds+((-wb,wb),)\n", + "\n", + "#while np.sum(np.abs(q[-1,0:2]-path[-1,0:2]))>0.1:\n", + "for i in range(50): \n", + " \n", + " start = time.time()\n", + " K = road_curve(curr_pos,track)\n", + " \n", + " # initial conditions for opt.\n", + " q0 = np.array([0,0,0,0,0])\n", + " q0[3] = f(q0[0],K)\n", + " q0[4] = - np.arctan(df(q0[0],K))\n", + "\n", + " #MPC LOOP\n", + " u_hat = minimize(objective,\n", + " u_hat0,\n", + " args=(q0,K,),\n", + " method='SLSQP',\n", + " bounds=bnds,\n", + " options={'maxiter':100}\n", + " ).x\n", + " \n", + " end = time.time()\n", + " opt_time.append(end-start)\n", + " \n", + " # store solution for plotting\n", + " x.append(x[-1]+u[0,0]*np.cos(theta[-1])*0.1)\n", + " y.append(y[-1]+u[0,0]*np.sin(theta[-1])*0.1)\n", + " theta.append(theta[-1]+u[0,1]*0.1)\n", + " \n", + " next_pos = [x[-1],y[-1],theta[-1]]\n", + " \n", + " # next initial condition\n", + " curr_pos=next_pos\n", + " u_hat0=u_hat\n", + "\n", + "print(\"SCIPY 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": 84, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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\n", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "plt.figure(figsize=(15,10))\n", + "\n", + "plt.plot(x[:],y[:])\n", + "plt.plot(track[0,:],track[1,:])\n", + "plt.ylabel('y')\n", + "plt.xlabel('x')\n", + "\n", + "plt.tight_layout()\n", + "\n", + "plt.show()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.6.9" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/notebook/MPC_cvxpy.ipynb b/notebook/MPC_tracking_cvxpy.ipynb similarity index 50% rename from notebook/MPC_cvxpy.ipynb rename to notebook/MPC_tracking_cvxpy.ipynb index b262387..2ba65d1 100644 --- a/notebook/MPC_cvxpy.ipynb +++ b/notebook/MPC_tracking_cvxpy.ipynb @@ -343,8 +343,8 @@ "name": "stdout", "output_type": "stream", "text": [ - "CPU times: user 2.58 ms, sys: 3.15 ms, total: 5.73 ms\n", - "Wall time: 5.54 ms\n" + "CPU times: user 7.87 ms, sys: 0 ns, total: 7.87 ms\n", + "Wall time: 7.41 ms\n" ] } ], @@ -440,8 +440,8 @@ "name": "stdout", "output_type": "stream", "text": [ - "CPU times: user 3.07 ms, sys: 1.38 ms, total: 4.44 ms\n", - "Wall time: 2.86 ms\n" + "CPU times: user 1.8 ms, sys: 650 µs, total: 2.45 ms\n", + "Wall time: 1.79 ms\n" ] } ], @@ -873,15 +873,15 @@ }, { "cell_type": "code", - "execution_count": 15, + "execution_count": 28, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "CPU times: user 270 ms, sys: 109 µs, total: 270 ms\n", - "Wall time: 274 ms\n" + "CPU times: user 219 ms, sys: 3.99 ms, total: 223 ms\n", + "Wall time: 217 ms\n" ] } ], @@ -932,16 +932,21 @@ "\n", "for t in range(T):\n", " \n", - " # Cost function\n", - " cost += 10*cp.sum_squares( x[3, t]) # psi\n", - " cost += 10*cp.sum_squares( x[4, t]) # cte\n", - " \n", - " # Actuation effort\n", - " cost += cp.quad_form( u[:, t],10*np.eye(M))\n", - " \n", + " # Tracking\n", + " if t > 0:\n", + " idx,_,_ = calc_err(x_bar[:,t],track)\n", + " delta_x = track[:,idx]-x[0:3,t]\n", + " cost+= cp.quad_form(delta_x,10*np.eye(3))\n", + "\n", + " # Tracking last time step\n", + " if t == T:\n", + " idx,_,_ = calc_err(x_bar[:,t],track)\n", + " delta_x = track[:,idx]-x[0:3,t]\n", + " cost+= cp.quad_form(delta_x,100*np.eye(3))\n", + "\n", " # Actuation rate of change\n", " if t < (T - 1):\n", - " cost += cp.quad_form(u[:, t + 1] - u[:, t], 5*np.eye(M))\n", + " cost += cp.quad_form(u[:, t + 1] - u[:, t], 25*np.eye(M))\n", " \n", " #constrains\n", " A,B,C=get_linear_model(x_bar[:,t],u_bar[:,t])\n", @@ -955,94 +960,7 @@ "\n", "\n", "prob = cp.Problem(cp.Minimize(cost), constr)\n", - "solution = prob.solve(solver=cp.ECOS, verbose=False)" - ] - }, - { - "cell_type": "code", - "execution_count": 16, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "CPU times: user 411 ms, sys: 2.64 ms, total: 413 ms\n", - "Wall time: 404 ms\n" - ] - } - ], - "source": [ - "%%time\n", - "\n", - "track = compute_path_from_wp([0,10],[0,0])\n", - "\n", - "MAX_SPEED = 2.5\n", - "MIN_SPEED = 0.5\n", - "MAX_STEER_SPEED = 1.57/2\n", - "\n", - "#starting guess\n", - "u_bar = np.zeros((M,T))\n", - "u_bar[0,:]=0.5*(MAX_SPEED+MIN_SPEED)\n", - "u_bar[1,:]=0.01\n", - "\n", - "# Starting Condition\n", - "x0 = np.zeros(N)\n", - "x0[0] = 0\n", - "x0[1] = 1\n", - "x0[2] = np.radians(-0)\n", - "_,psi,cte = calc_err(x0,track)\n", - "x0[3]=psi\n", - "x0[4]=cte\n", - "\n", - "# Linearized Model Aprrox. Prediction\n", - "# x_bar=np.zeros((N,T+1))\n", - "# x_bar[:,0]=x0\n", - "\n", - "# for t in range (1,T+1):\n", - "# xt=x_bar[:,t].reshape(5,1)\n", - "# ut=u_bar[:,t-1].reshape(2,1)\n", - " \n", - "# A,B,C=get_linear_model(xt,ut)\n", - " \n", - "# xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", - " \n", - "# _,psi,cte = calc_err(xt_plus_one,track)\n", - "# xt_plus_one[3]=psi\n", - "# xt_plus_one[4]=cte\n", - "# x_bar[:,t]= xt_plus_one\n", - "\n", - "\n", - "#CVXPY Linear MPC problem statement\n", - "cost = 0\n", - "constr = []\n", - "\n", - "for t in range(T):\n", - " \n", - " # Cost function\n", - " cost += 10*cp.sum_squares( x[3, t]) # psi\n", - " cost += 10*cp.sum_squares( x[4, t]) # cte\n", - " \n", - " # Actuation effort\n", - " cost += cp.quad_form( u[:, t],10*np.eye(M))\n", - " \n", - " # Actuation rate of change\n", - " if t < (T - 1):\n", - " cost += cp.quad_form(u[:, t + 1] - u[:, t], 5*np.eye(M))\n", - " \n", - " #constrains -> approx linear model at xo\n", - " A,B,C=get_linear_model(x0,u_bar[:,t])\n", - " constr += [x[:,t+1] == A*x[:,t] + B*u[:,t] + C.flatten()]\n", - " \n", - "# sums problem objectives and concatenates constraints.\n", - "constr += [x[:,0] == x0]\n", - "constr += [u[0, :] <= MAX_SPEED]\n", - "constr += [u[0, :] >= MIN_SPEED]\n", - "constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED]\n", - "\n", - "\n", - "prob = cp.Problem(cp.Minimize(cost), constr)\n", - "solution = prob.solve(solver=cp.ECOS, verbose=False)" + "solution = prob.solve(solver=cp.OSQP, verbose=False)" ] }, { @@ -1054,7 +972,7 @@ }, { "cell_type": "code", - "execution_count": 17, + "execution_count": 29, "metadata": {}, "outputs": [ { @@ -1066,7 +984,7 @@ }, { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ "
" ] @@ -1125,126 +1043,7 @@ }, { "cell_type": "code", - "execution_count": 18, - "metadata": {}, - "outputs": [], - "source": [ - "\n", - "# track = compute_path_from_wp([0,5,7.5,10,12,13,13,10],\n", - "# [0,0,2.5,2.5,0,0,5,10])\n", - "\n", - "# sim_duration =100 \n", - "# opt_time=[]\n", - "\n", - "# x_sim = np.zeros((N,sim_duration))\n", - "# u_sim = np.zeros((M,sim_duration-1))\n", - "\n", - "# MAX_SPEED = 1.25\n", - "# MIN_SPEED = 0.75\n", - "# MAX_STEER_SPEED = 1.57/2\n", - "\n", - "# # Starting Condition\n", - "# x0 = np.zeros(N)\n", - "# x0[0] = 0\n", - "# x0[1] = -0.5\n", - "# x0[2] = np.radians(-0)\n", - "# _,psi,cte = calc_err(x0,track)\n", - "# x0[3]=psi\n", - "# x0[4]=cte\n", - "\n", - "# x_sim[:,0]=x0\n", - " \n", - "# #starting guess\n", - "# u_bar = np.zeros((M,T))\n", - "# u_bar[0,:]=0.5*(MAX_SPEED+MIN_SPEED)\n", - "# u_bar[1,:]=0.01\n", - "\n", - "# for sim_time in range(sim_duration-1):\n", - " \n", - "# iter_start=time.time()\n", - " \n", - "# # Prediction\n", - "# x_bar=np.zeros((N,T+1))\n", - "# x_bar[:,0]=x_sim[:,sim_time]\n", - "\n", - "# for t in range (1,T+1):\n", - "# xt=x_bar[:,t-1].reshape(5,1)\n", - "# ut=u_bar[:,t-1].reshape(2,1)\n", - "\n", - "# A,B,C=get_linear_model(xt,ut)\n", - "\n", - "# xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", - "\n", - "# _,psi,cte = calc_err(xt_plus_one,track)\n", - "# xt_plus_one[3]=psi\n", - "# xt_plus_one[4]=cte\n", - "\n", - "# x_bar[:,t]= xt_plus_one\n", - "\n", - "\n", - "# #CVXPY Linear MPC problem statement\n", - "# cost = 0\n", - "# constr = []\n", - "\n", - "# for t in range(T):\n", - "\n", - "# # Tracking\n", - "# if t > 0:\n", - "# idx,_,_ = calc_err(x_bar[:,t],track)\n", - "# delta_x = track[:,idx]-x[0:3,t]\n", - "# cost+= cp.quad_form(delta_x,10*np.eye(3))\n", - " \n", - "# # Tracking last time step\n", - "# if t == T:\n", - "# idx,_,_ = calc_err(x_bar[:,t],track)\n", - "# delta_x = track[:,idx]-x[0:3,t]\n", - "# cost+= cp.quad_form(delta_x,100*np.eye(3))\n", - "\n", - "# # Actuation rate of change\n", - "# if t < (T - 1):\n", - "# cost += cp.quad_form(u[:, t + 1] - u[:, t], 25*np.eye(M))\n", - " \n", - "# # Actuation effort\n", - "# cost += cp.quad_form( u[:, t],1*np.eye(M))\n", - " \n", - "# # Constrains\n", - "# A,B,C=get_linear_model(x_bar[:,t],u_bar[:,t])\n", - "# constr += [x[:,t+1] == A*x[:,t] + B*u[:,t] + C.flatten()]\n", - "\n", - "# # sums problem objectives and concatenates constraints.\n", - "# constr += [x[:,0] == x_sim[:,sim_time]] # starting condition\n", - "# constr += [u[0, :] <= MAX_SPEED]\n", - "# constr += [u[0, :] >= MIN_SPEED]\n", - "# constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED]\n", - " \n", - "# # Solve\n", - "# prob = cp.Problem(cp.Minimize(cost), constr)\n", - "# solution = prob.solve(solver=cp.ECOS, verbose=False)\n", - " \n", - "# #retrieved optimized U and assign to u_bar to linearize in next step\n", - "# u_bar=np.vstack((np.array(u.value[0, :]).flatten(),\n", - "# (np.array(u.value[1, :]).flatten())))\n", - " \n", - "# u_sim[:,sim_time] = u_bar[:,0]\n", - " \n", - "# # Measure elpased time to get results from cvxpy\n", - "# opt_time.append(time.time()-iter_start)\n", - " \n", - "# # move simulation to t+1\n", - "# tspan = [0,dt]\n", - "# x_sim[:,sim_time+1] = odeint(kinematics_model,\n", - "# x_sim[:,sim_time],\n", - "# tspan,\n", - "# args=(u_bar[:,0],))[1]\n", - " \n", - "# print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n", - "# np.max(opt_time),\n", - "# np.min(opt_time))) " - ] - }, - { - "cell_type": "code", - "execution_count": 19, + "execution_count": 23, "metadata": {}, "outputs": [ { @@ -1258,16 +1057,16 @@ "name": "stdout", "output_type": "stream", "text": [ - "CVXPY Optimization Time: Avrg: 0.1777s Max: 0.2998s Min: 0.1523s\n" + "CVXPY Optimization Time: Avrg: 0.1416s Max: 0.2571s Min: 0.1279s\n" ] } ], "source": [ "\n", - "track = compute_path_from_wp([0,3,4,6],\n", - " [0,0,2,1])\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 =50\n", + "sim_duration =100 \n", "opt_time=[]\n", "\n", "x_sim = np.zeros((N,sim_duration))\n", @@ -1323,8 +1122,16 @@ " for t in range(T):\n", "\n", " # Tracking\n", - " cost += 50*cp.sum_squares( x[3, t]) # psi\n", - " cost += 10*cp.sum_squares( x[4, t]) # cte\n", + " if t > 0:\n", + " idx,_,_ = calc_err(x_bar[:,t],track)\n", + " delta_x = track[:,idx]-x[0:3,t]\n", + " cost+= cp.quad_form(delta_x,10*np.eye(3))\n", + " \n", + " # Tracking last time step\n", + " if t == T:\n", + " idx,_,_ = calc_err(x_bar[:,t],track)\n", + " delta_x = track[:,idx]-x[0:3,t]\n", + " cost+= cp.quad_form(delta_x,100*np.eye(3))\n", "\n", " # Actuation rate of change\n", " if t < (T - 1):\n", @@ -1361,21 +1168,21 @@ " x_sim[:,sim_time+1] = odeint(kinematics_model,\n", " x_sim[:,sim_time],\n", " tspan,\n", - " args=(u_bar[:,1],))[1]\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))) " + " np.min(opt_time))) " ] }, { "cell_type": "code", - "execution_count": 20, + "execution_count": 24, "metadata": {}, "outputs": [ { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ "
" ] diff --git a/notebook/equations.ipynb b/notebook/equations.ipynb index 7eaebd5..f46b8ed 100644 --- a/notebook/equations.ipynb +++ b/notebook/equations.ipynb @@ -9,7 +9,7 @@ }, { "cell_type": "code", - "execution_count": 120, + "execution_count": 1, "metadata": {}, "outputs": [ { @@ -26,7 +26,7 @@ "[0, 0, 0, v*cos(psi), 0]])" ] }, - "execution_count": 120, + "execution_count": 1, "metadata": {}, "output_type": "execute_result" } @@ -37,10 +37,10 @@ "x,y,theta,psi,cte,v,w = sp.symbols(\"x y theta psi cte v w\")\n", "\n", "gs = sp.Matrix([[ sp.cos(theta)*v],\n", - " [ sp.sin(theta)*v],\n", - " [w],\n", - " [-w],\n", - " [ v*sp.sin(psi)]])\n", + " [ sp.sin(theta)*v],\n", + " [w],\n", + " [-w],\n", + " [ v*sp.sin(psi)]])\n", "\n", "state = sp.Matrix([x,y,theta,psi,cte])\n", "\n", @@ -79,6 +79,13 @@ "gs.jacobian(state)" ] }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + }, { "cell_type": "markdown", "metadata": {},