{ "cells": [ { "cell_type": "code", "execution_count": 73, "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": 74, "metadata": {}, "outputs": [], "source": [ "# Control problem statement.\n", "\n", "N = 3 #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": 75, "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", " \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_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_lin=dt*B\n", " \n", " f_xu=np.array([v*np.cos(theta),v*np.sin(theta),w]).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": 76, "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", "\n", " dqdt = [dxdt,\n", " dydt,\n", " dthetadt]\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": 77, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "CPU times: user 5.97 ms, sys: 113 µs, total: 6.08 ms\n", "Wall time: 4.96 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", "\n", "x_bar=predict(x0,u_bar)" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Check the model prediction" ] }, { "cell_type": "code", "execution_count": 78, "metadata": {}, "outputs": [ { "data": { "image/png": "iVBORw0KGgoAAAANSUhEUgAAAagAAACfCAYAAACsuk1hAAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAADh0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uMy4xLjMsIGh0dHA6Ly9tYXRwbG90bGliLm9yZy+AADFEAAAgAElEQVR4nO3deVgVdf//8ednWERUdhTldhdScxduyyU3rDs1S1NzuTN3zQX3LCuVDLUSSUJtEc1sU1Py7s7bSs2sbHHDXH7lkpWmhoA7mcJ8fn/wlUtSFPGcMwO8H9fFdZ0zM2fOi7nmnPeZz3zmM0prrRFCCCFsxrA6gBBCCHE9UqCEEELYkhQoIYQQtiQFSgghhC1JgRJCCGFLUqCEEELYkhQoIYQQtuRudYDbcezYsetODwoKIi0tzcVprs9OWcBeeeyUBW6cp1KlSi5O41gpKSksWbIE0zRp3749Dz300E1fI5+vW2enPHbKAoX7fMkRlBDFnGmaJCUlMWXKFOLj4/n66685evSo1bGEuCkpUEIUcwcPHiQkJIQKFSrg7u5O8+bN2bp1a6HWJQPPCFeSAiVEMZeRkUFgYGDu88DAQDIyMm55PVprzNdeIHPdailUwiWK9DkoIYTjrF+/nvXr1wMwe/ZsgoKC8sw3/8zkTHYW516bg2fEN/iOfArDL8CKqLnc3d2vyWklO+WxUxYoXB4pUEIUcwEBAaSnp+c+T09PJyDg2sISFRVFVFRU7vPrndDWj0+h3Hefc+6tBZwc82+MAWNQ9Zo6J3gBFKWOAK5mpywgnSSEENdRs2ZNjh8/TmpqKllZWWzZsoWIiIhCrUsZBt4PPILxdByU88WcF4P5/hvoy5ccnFoIOYISothzc3Nj4MCBxMbGYpombdu2pXLlyre1TvWPahhT5qBXv4Xe8BH6xx8wBk9A/aOaY0ILgRQoIUqEJk2a0KRJE4euU3mWQvUagr6zCeab8zBjJ6AefgzVrjPKkMYZcftkLxJC3BZVvynGtASo2wi9fBFmQgz69K33EhTi76RACSFum/Lxwxj1DKrvcDiwFzMmGp3yndWxRBEnBUoI4RBKKYw2HTGeiQf/QMz5sZhvL0D/9ZfV0UQRJQVKCOFQqmJljKfmoO7riv5iHebzY9G/HrI6liiCpEAJIRxOeXhgdB+AMX4GXLyIOWsS5ier0aZpdTRRhEiBEkI4jarTEGN6AjT8J/qDNzHjp6Iz7HPxqLA3KVBCOJFpmgX6K85j26ky5TCGT0Y9NhoO78/pQLF9i9WxRBEg10EJ4US9e/cu0HKenp4sW7bMyWmso5RCteyADrsTc1Ec5quzUS2iUL2GoLxKWx1P2JQUKCGcyNPTk7lz595wGa01TzzxhIsSWUtVqIQx+QX0R++h//cB+sDenBEoqodbHU3YkBQoIZzogQceIDg4+KbLde7c2QVp7EG5u6O6Poq+szFm0lzM2U+guvRB3f8wynCzOp6wETkHJYQT9ezZs0DLde/e3clJ7EeF18OYloBq2gL94duYc55Gp6daHUvYiBxBCeEif/zxx3Wne3h44Ofnh1ECx69T3mVhyESoH4F+91XMmDGovsMxmrW2OpqwASlQQrhIdHR0vvMMw6Bp06YMHjwYPz8/F6aynlIKdXdbdK06mElz0YviMPdsR/UehvIuY3U8YSFbFKi0tDTmz5/P6dOnUUoRFRVFx44drY4lhEMNGzaMvXv30qNHj9ybt61atYrw8HDq1q3LO++8Q1JSEhMmTLA6qiVUcAjGpFnoj1egP16OPrAPY/B4VK26VkcTFrFFm4KbmxuPPvoo8fHxxMbG8sknn3D06FGrYwnhUCtWrGDYsGGEhITg7u5OSEgIgwcPZtWqVYSGhjJixAj27dtndUxLKTc3jC69MZ6YDUphvjgFc8276Oxsq6MJC9iiQPn7+1OjRg0ASpcuTWhoKBkZMly/KF601pw8eTLPtLS0NMz/G/7Hy8uLbPkiBkDVrI0xdR7qrjbo/76P+eKT6JMnrI4lXMwWTXxXS01N5fDhw9SqVcvqKEI4VMeOHXnuuedo06YNgYGBZGRk8Pnnn+c2Z+/YsYPwcLke6ApV2hs1cCxm/aboZQtyOlD0GYa6uy1KKavjCRdQ2kZjrFy8eJFp06bRrVs3mjVrds389evXs379egBmz57NpUuXrrsed3d3srKynJq1oOyUBeyVx05Z4MZ5PD09HfIeKSkpfPPNN5w6dQo/Pz+aN29Oo0aNHLJuRzt27Nh1p185f+ZKOv0k5uJ42L8HFdkK1fdxVJmylmS5ETvlsVMWuHGeSpUqXXe6bQpUVlYWL7zwAg0bNizwRYt2+gDlx05ZwF557JQFCvcBKs7s9vnSZjb6k2T0mnfA1x9j4DiCW7QtMvuQq9kpCxTu82WLc1Baa1599VVCQ0NL1BX1omS5fPky7733HqNGjeKxxx4DYNeuXaxbt87iZEWDMtww7u+O8eSL4O6JGfcM55YtRGddtjqacBJbFKiffvqJzZs3s2fPHiZNmsSkSZPYsWOH1bGEcKilS5dy5MgRoqOjc8+hVK5cmU8//dTiZEWLqhaGMfVlVMsOZK5ehjl7MvqE9PotjmzRSaJ27dqsWLHC6hhCONX3339PQkICXl5euQUqICBAeqwWgirlheo3irLN23ImcSbmjHGoRwajWt0rHSiKEVscQQlREri7u+d2Kb/i7NmzlCtXzqJERZ/XXa1zbohYszZ62XzMBbPQ585aHUs4iBQoIVzkrrvuIjExkdTUnAFRT506RVJSEs2bN7c4WdGm/AIxxsagegyEPdtyboi4b6fVsYQDSIESwkX69OlD+fLlmTBhApmZmURHR+Pv70+PHj2sjlbkKcPAuPchjKfmgHcZzPhpmCuS0JelA0VRZotzUEKUBO7u7vTv35/+/fvnNu3J+RLHUlVqYDw9F/3BEvRna9D/bxfG4Imo0CpWRxOFIAVKCCfK7xYbAH/++Wfu4woVKrgiTomgSpVC9R2OrtcUc2kCZux4VI8BqDYd5QdBESMFSggnutEtNq62fPlyJycpeVTDSIxpCZhvzkO/+xp693aM/qNRPv5WRxMFJAVKCCe6uvB8/vnn7N69mx49ehAcHMzJkyf54IMPqF+/voUJizfl648RPQ39+cfolUswp0dj9I9GNYi0OpooAOkkIYSLLF++nOHDh1OxYkXc3d2pWLEiQ4cO5f3337c6WrGmlMJo1xnjmbng44f5ygzMd19FX/rL6mjiJordEZS59BXSDv9ENgrcPcDdHUp759xa2rsMlPUF/0CUfxD4B0JwRVSpUlbHFiWA1prU1FT+8Y9/5E47efLkNddGCedQoVUxno5Dr16GXr8G/eNujCETUZWrWx1N5KPYFSjKV8Jdm2RnXoCsLMi6DOfPoVOPQ+Z5uHAetCbPCLkBwRASiqpUBarURFWrBRUqoQw3i/4JURx16tQp93YbVwbO/OKLL+jUqZPV0UoM5eGJemQQul4TzCUvY86cgOraDxXVBWVIg5LdFLsCZdz/MH43GDVXZ2XB2VOQkYbOOAmpx+DE7+gTv6M3r4NLl3KKVykvqHEHKrweKvxOqH4HysPDpf+LKF66dOlClSpV+Oabb/jll1/w8/Pj8ccfd8jtNpYtW8b27dtxd3enQoUKjBgxgjJlygCQnJzMxo0bMQyDAQMG2Pb2Hq6k7myc04Fi6SvolYvRe3dgDBiD8gu0Opq4SrErUDej3N1zjpgCglHUyTNPZ2fDiaPoXw/CLwfQB/ah//MuWmvwLAV1GqLqR6DqN0UFBFv0H4iirFGjRk4pEA0aNKBPnz64ubnx9ttvk5yczL///W+OHj3Kli1bmDt3LqdOnWLGjBnMmzcPQ44WUOV8MUY+jd78CXrFIsyYaIx+o1GN77I6mvg/Ja5A3Yhyc4PQqqjQqtC8PQD6wjk4sA+9dyd69zb0ru9zjrCqh+fcOK1pC1RAkKW5hX1t2LCB9u3b33S5jRs30q5du0K/T8OGDXMfh4eH8+233wKwdetWmjdvjoeHB+XLlyckJISDBw/KnXv/j1IK1fpf6PB6mIviMBfMzBlw9pHBqFJeVscr8aRA3YQqUw4aNUM1apZzJHX8CDrlO/S2r9ArktArkqB2A1TLDqgmd6M8HHPnVVE8vPXWW7Rr146b3Rd02bJlt1WgrrZx48bc8f0yMjIICwvLnXej0dP/fsfqoKDr//Byd3fPd56rOSxLUBB6zmLOv/cGmR++g3HoR3zHT8ejZm1r8jiAnbJA4fJIgboFSimoVCWnM0XHHjnnrbZ+id6yAb0oDu1dFnV3W1S7zqjyFa2OK2zg4sWL9OrV66bLeRTg/OaMGTM4ffr0NdN79epFZGTOdT2rV6/Gzc2NVq1a3XLWqKgooqKicp/ndx7XTndqdXiWjj0xatQmOymejMlDUA/+G3XfQwXuMFWst81tKswddaVA3QYVEop6oBe6U0/4aTf6y0/Rm9aiN/4XGjbD6NAFHdja6pjCQomJiQVariBD8Dz77LM3nL9p0ya2b9/O1KlT89xvKj09PXeZjIwMAgICCpSppFK1G2BMT8BcNh+9emlOB4qBY+W8swWkQDmAMoycDhR1GqJPp6M//x968/8wU77lVN2G6Psezpkv44CVOMHBrvlSS0lJYc2aNcTExFDqquv6IiIiSEhIoHPnzpw6dYrjx49Tq1Ytl2QqylSZchjDJqO3bES/9xpmzBiMR0egIlpaHa1EkQLlYMovENX13+iOPdBffUb2Z8mY8VOhZm2Mrv1Qd9SzOqIohpKSksjKymLGjBkAhIWFMXToUCpXrszdd9/N+PHjMQyDQYMGSQ++AlJKoVq0R4fVwVw0F/O1F1G7t6N6D0F5eVsdr0RQ+mZnb23s2LFj151up7bXQF8fTq5Zjl67Ek6lQcN/YnTrl3MeywJ22jZ2ygKFayMvzorC58tVWXRWFvrj5eiPV0JQeYzBE1A17rAsT0HYKQsU7vNlm59SKSkpjBkzhtGjR/Phhx9aHcdhlIcnRpv7MZ5fiOr2GOzfgzk9GvO919GZF6yOJ4QoAOXujvFgX4xJM8E0MV+YjPnf93OunRROY4sCZZomSUlJTJkyhfj4eL7++muOHj1qdSyHUp6lMO5/GCP2dVSbf6E/X4v57OOY335+0y7IQgh7UGF1MabOQ0W0Qq95F3POFHRa/vf8ErenwOeg3nzzTdq0aUO1atUcHuLgwYOEhITk3rStefPmbN26Nc+gmsWFKueD6jMc3aID5jsL0Unx6G83YfQbJb2EiqmzZ8+yefNmduzYwa+//kpmZibe3t5UrVqVRo0a0aZNG3x8fKyOKQpIeZdBDZmAWb8p+t1XMZ8bg+ozHOOuNlZHK3YKXKBM0yQ2NhYfHx9atWpFq1atCAx0zLhVGRkZedYVGBjIgQMHCrWuqVN9OHDAncuX7TGmlodHflkC0fqfcDodvv8DlpgQbICvP87s7Jd/HtezUxaApk3deOopx67znXfe4auvvqJx48a0a9eO0NBQSpcuzZ9//snvv//Ovn37mDx5Mi1btqRv376OfXPhVMZdbdA1a2MujkcnzcXcvR0z+mmrYxUrBS5QAwcOpH///uzcuZMvv/yS1atXExYWxj333EOzZs3w8nL+sCAFudK9dGk3lFIFuvDRFW6apXwI2s+frN9/Q//xO8af53GrVBXl7pyR1IvUtnExw1AOv/I+MDCQhISE6/6f1atXp2XLlly6dImNGzc69H2Fa6jgEIyJM9H/W4n+6H3Sx/WD/mNyBpgWt63QvfiOHDlCQkICv/32G56enrRo0YKePXsW6iLA/fv3s3LlSp5+OufXR3JyMgBdu3a94euKUy8jbZroDR+hVy0FXz+MwRNRYXUty+MKdsoCzu/Fd/r0afz8/Ao83WrF6fPlCvrnn1BLXib7j+Oojt1RnXvlDE5tETttG3BBL77MzEw2btxITEwM06ZNo1atWsTExBAfH4+XlxczZ8689dRAzZo1OX78OKmpqWRlZbFlyxYiIiIKta6iShkGRocHMZ56EdzcMV+agvnph9KBohgZM2bMdaePGzfOxUmEM6gadxAw901U87boj1dgvvgkOvX6RV4UTIHLe1xcHLt27aJOnTp06NCByMjIPM0W/fr1o3///oUK4ebmxsCBA4mNjcU0Tdq2bUvlypULta6iTlWthfHsy5hvJqBXLobfDkG/UShPuetvUXe9HxuZmZly4WwxYpQug9F/DLpeU8xl8zGfG4vqPRTVvL2MJFMIBS5QYWFhDBo0KN+mCMMweOONNwodpEmTJjRp0qTQry9OVGlvjOGT0WtXote8gz5+FGP0syg/GUOtKHr88ccBuHTpUu7jK86fP0+LFi2siCWcSEW0xKhxB+bil9FvJqB3b8N4dGTO3RFEgRW4QHXp0uWmy1w9Bpi4PUopVKee6MrVMV+fgzlrEsaYaZaNQCEKb/To0WitmTVrFqNHj84zz8/Pr0SOUlESqIBgjPHPoT/9EP3hO5iHfsIYNA5Vu4HV0YoMGYvP5lSDSIwnZmImPIc5ezLGyKdlPL8ipm7dnM4uSUlJ8iOuhFGGG+pfD6PrNMR8Iw5z7rOoe7uiHuqLcrdPD1a7ksbvIkBVqYnx1EvgF4A5bzp6z3arI4kCWrt2LZcvXwbyb2G4fPkya9eudWUs4WI555bjUa3uQ3+yGnPWE+jjxWu0HGeQI6giQgWWx5g0C/PlqZiJsRhDJ6Ga3G11LHETp0+fJjo6msaNG1O3bl0qVaqEl5cXFy9e5NixY+zbt4+dO3fSurXcN6y4U6W8UI+OQNdvgrn0Fcznx6J6Dkbdc590oMiHFKgiRJXzwZjwfE5z32svYAx9AtW0udWxxA306dOHzp07s2nTJjZu3Mhvv/3GhQsXKFu2LFWqVKFx48b07t2bcuXk5HlJoRrdhVEtDHPJPPTbC3I6UDw2GlXO1+potiMFqohR3mUxxsZgvjwN8405GJ5TUPVL1jVjRY2Pjw9dunQpUEcjUTIov0CMMdNzLs5fvRQzJhpjwFjUnY2tjmYrcg6qCFJepTGip0FoVcyFs9E//mB1JCHELcq9OH9KHHiXzfnRuXwR+vIlq6PZhhxBFVHKu0zOkdScKZgLZmI8MRv1j2pWxxI3kJmZycqVK9m3bx/nzp3Lc+HuwoULLUwmrKQqV8d4Zi76gzfR6/+D/n+7MIZMRIVWtTqa5eQIqghT5XwwxkyDUl6YCc+hT6VbHUncwKJFizh8+DDdu3fn/PnzDBw4kKCgIDp16mR1NGEx5VkKo88wjOipcPY05vPjMTf8t8QPdSYFqohTAcE5zX1/XsBMiEH/mWl1JJGPH374gQkTJhAZGYlhGERGRjJu3Di+/PJLq6MJm1D1IzCmJ0Cdhuj3X8/54XnmlNWxLCMFqhhQlatjPP4kqnJ1kIv/bEtrjbe3NwBeXl5kZmbi5+fHiRMnLE4m7ET5+OcMbdZnOPy0GzMmGv3DVqtjWULOQRUTqm5jVF3pAWRnVatWZd++fdSvX5/atWuzaNEivLy8qFixotXRhM0opVBtO6LvqJczAsUrM1BtOqK6D0CVoNFI5AhKCBcZNmwYwcHBAAwYMABPT08uXLjAqFGjLE4m7EpVqoIxZQ7q3ofQm9Zixo5H//az1bFcRo6ghHCRs2fPEhYWBoCvry/Dhw8H4ODBg1bGEjanPDxQPQai72yMuXge5syJqG6PoqIeRBXzW7UU7/9OCBt5/vnnrzs9NjbWxUlEUaTqNsaYlgD1I9Arl2C+PK3Y99yVAiWEk5mmiWmaaK3RWuc+N02T48eP4+bmZnVEUUSocj4YI55CPToSDv2Y04FixxarYzmNNPEJ4WS9e/fOfdyrV6888wzDoGvXrq6OJIowpRTqnvvQ4fUwF8VhLpyNatkB9chglFdpq+M5lBQoIZwsMTERrTXTp08nJiYGrXXOl4xS+Pj44OnpaXVEUQSpkFCMJ19A/+c99LpV6P17MQZPQFUPszqaw0gTnxBOFhwcTPny5VmwYAHBwcEEBQXh7u5OUFCQFCdxW5S7B0a3fhgTYiHrEuYLT2CuXYk2s62O5hBSoIRwkQsXLjBv3jz69u1LdHQ0ANu2beP999+3OJko6tQd9TCmJqAa341OXoYZ9wzZqcetjnXbLC9Qy5YtY+zYsUycOJGXXnqJCxcuWB1JCKd444038Pb2ZsGCBbi757Suh4eHs2VL8T3JLVxHlSmLGjoJNWAs/Poz6eMew/x+s9WxbovlBapBgwbExcUxZ84cKlasSHJystWRhHCK3bt3M2DAAPz9/XOn+fj4cObMGQtTieJEKYXRvB3GtHm4V66GfmMOZlJ8kR2j0/IC1bBhw9xutuHh4WRkZFicSAjn8Pb25ty5c3mmpaWl5SlYt+ujjz6iZ8+enD17FsgZ/2/x4sWMHj2aiRMn8vPPJWcUgpJMBYfgH7sA9UAv9HdfYD43Bn3oR6tj3TJb9eLbuHEjzZvnfwvz9evXs379egBmz55NUFDQdZe7cgLaDuyUBeyVx05ZwPl52rdvT1xcHL169UJrzf79+3nvvffo0KGDQ9aflpbGDz/8kOd/2LlzJydOnCAhIYEDBw6waNEiZs6c6ZD3E/am3NwxuvRB122c0x39xSdRnR5BdeqJKiLX3rmkQM2YMYPTp09fM71Xr15ERkYCsHr1atzc3GjVqlW+64mKiiIqKir3eVpa2nWXCwoKyneeq9kpC9grj52ywI3zVKpU6bbX/+CDD+Lp6UlSUhLZ2dksXLiQqKgoOnbseNvrBli6dCl9+/blpZdeyp22bds27rnnHpRShIeHc+HCBU6dOuXQozZhb6pWHYxpCeh3X0N/9B56306MQeNRwSFWR7splxSoZ5999obzN23axPbt25k6dSpKKVdEEsLllFJ07NjRYQXpalu3biUgIIBq1arlmZ6RkZHniCowMJCMjAwpUCWMKu2NGjQOs14T9DuvYj43BtVnOOquNrb+zrW8iS8lJYU1a9YQExNDqRI0jLwomY4dO8Yvv/zCxYsX80xv167dTV97o5aI5ORknnnmmdvKJk3ot89Oea6bpdPDZEc258y857i8OB7P/bvxGT4Jo0w5a/Lc7DVOylJgSUlJZGVlMWPGDADCwsIYOnSoxamEcLzVq1ezatUqqlates2PsYIUqPxaIn777TdSU1OZNGkSAOnp6UyePJlZs2YREBCQp9kyPT2dgICA665HmtBvn53y5JvF8ECPmY763yr++ug9Tu7bhTFoHCq8njV5yL8J3fIC9corr1gdQQiXWLt2LTNnzqRq1aoOXW+VKlVYtGhR7vORI0cya9YsfHx8iIiIYN26dbRo0YIDBw7g7e0tzXsCZbihOvVE122U04FiztOo+7ujHuiNcre8LOSyTxIhijlPT09CQ0Nd+p6NGzdmx44dREdH4+npyYgRI1z6/sLeVPVwjGdfRi9fhF67Er13J8aQiagKt98pyBGkQAnhRKZp5j5+5JFHWLx4MT169MDX1zfPcoYDbzw3f/783MdKKQYPHuywdYviR3mVRj02Gl2vKeZbiTkdKHoNyRkh3eIOFFKghHCiq2+1ccWGDRuumbZ8+XJXxBEiX6ppc4zq4ZhLXka/lYjesx3j0ZGosj6WZZICJYQTJSYmWh1BiAJTAUEY455Df7YmZ9DZn6MxBo5D1WloSR7LhzoSojgLDg7O/fvmm2/yPL/y991331kdU4hcyjAw7uuKMeUl8PLGnPss5sol6MuXXZ5FCpQQLrJq1apbmi6ElVSVmhjPxKPa3I/+NBlz1kT08SMuzSBNfEI42Z49e4CcDhNXHl/xxx9/ULp08bpNtyg+VKlSqL6P53SgeDMBc8Y4VI+BqDb3u6QDhRQoIZxs4cKFAFy6dCn3MeT0sPPz82PgwIFWRROiQFTDf2JMfwXzzXnod1/N6UDx2GiUj59T31cKlBBOdqXbd2JiIqNGjbI4jRCFo3z9MUZPRX/+MfqDNzFjojEGjEHVa+q095RzUEK4iBQnUdQpw8Bo/wDG03FQzhdzXgzm+2+gL19yyvtJgRJCCHFL1D+qYTwdh2r/AHrDR5ixE9BHf3H4+0iBEkIIccuUhydGryEY0dPg3BnM2AmY6/+Dvmr0lNslBUoIIUShqfpNMaYlQN1G6OWLMBNi0KczHLJuKVBCCCFui/Lxwxj1DKrvcDiwFzMmGp1y+xegS4ESQghx25RSGG06YjwTD/6BmPNjMd9egP7rr0KvUwqUEEIIh1EVK2M8NQd1X1f0F+swnx+L/vVQodYlBUoIIYRDKQ8PjO4DMMbPgIt/Ys6axF/bv7nl9UiBEkII4RSqTkOMaQmoe+7Do26DW369FCghhBBOo8r6YPQZhlG6zC2/VgqUEEIIW5ICJYQQwpakQAkhhLAlpbXWVocQQggh/q5YHkE9+eSTVkfIZacsYK88dsoC9stjV3baTnbKAvbKY6csULg8xbJACSGEKPqkQAkhhLAlt+nTp0+3OoQz1KhRw+oIueyUBeyVx05ZwH557MpO28lOWcBeeeyUBW49j3SSEEIIYUvSxCeEEMKW3K0OcDtSUlJYsmQJpmnSvn17HnrooTzzL1++TGJiIj///DPlypVj7NixlC9f3uE50tLSmD9/PqdPn0YpRVRUFB07dsyzzN69e3nxxRdz379Zs2Z0797d4VmuGDlyJF5eXhiGgZubG7Nnz84zX2vNkiVL2LlzJ6VKlWLEiBFOaQ44duwY8fHxuc9TU1Pp2bMnnTp1yp3m7G2zYMECduzYga+vL3FxcQCcP3+e+Ph4Tp48SXBwMOPGjaNs2bLXvHbTpk2sXr0agG7dutGmTRuH5SpqbvZ5c7Wb7ePOdDv7lKvyrFixgg0bNuDj4wNA7969adKkidOz5Pd9WKjto4uo7OxsPWrUKH3ixAl9+fJlPXHiRH3kyJE8y6xbt06/9tprWmutv/rqKz137lynZMnIyNCHDh3SWmudmZmpo6Ojr8myZ88ePWvWLKe8//WMGDFCnzlzJt/527dv17Gxsdo0Tf3TTz/pp556yumZsrOz9eDBg3Vqamqe6c7eNnv37tWHDh3S49fRze4AAAYASURBVMePz522bNkynZycrLXWOjk5WS9btuya1507d06PHDlSnzt3Ls/jkqggnzdXu9k+7kyF3adcmWf58uV6zZo1LstwRX7fh4XZPkW2ie/gwYOEhIRQoUIF3N3dad68OVu3bs2zzLZt23J/8d51113s2bMH7YRTbv7+/rlHH6VLlyY0NJSMDMfc8thZtm3bxj333INSivDwcC5cuMCpU6ec+p67d+8mJCSE4OBgp77P39WtW/eaX2pbt26ldevWALRu3fqafQdyjhgaNGhA2bJlKVu2LA0aNCAlJcUlme2mIJ+3kqSw+5Qr81glv+/DwmyfItvEl5GRQWBgYO7zwMBADhw4kO8ybm5ueHt7c+7cudxDXmdITU3l8OHD1KpV65p5+/fvZ9KkSfj7+/Poo49SuXJlp+UAiI2NBaBDhw5ERUXlmZeRkUFQUFDu88DAQDIyMvD393danq+//poWLVpcd56rt82ZM2dy/1c/Pz/OnDlzzTJ/38cCAgJs/8PDWQryebPCjfZxVyvIPuVqn3zyCZs3b6ZGjRr069fP5UXs6u/DwmyfIlug7OjixYvExcXRv39/vL2988yrXr06CxYswMvLix07dvDSSy+RkJDgtCwzZswgICCAM2fO8Pzzz1OpUiXq1q3rtPe7maysLLZv306fPn2umefqbfN3SimUUi57P+EYdtvHr2aHferee+/NPZe7fPly3nrrLUaMGOGy97/R92FBt0+RbeILCAggPT0993l6ejoBAQH5LpOdnU1mZiblypVzSp6srCzi4uJo1aoVzZo1u2a+t7c3Xl5eADRp0oTs7GzOnj3rlCxA7rbw9fUlMjKSgwcPXjM/LS0t9/n1tp8j7dy5k+rVq+Pn53fNPFdvG8jZLleaNE+dOnXdo+q/72MZGRlO3UZ2VpDPm6vdbB93tYLsU67k5+eHYRgYhkH79u05dKhwt10vjOt9HxZm+xTZAlWzZk2OHz9OamoqWVlZbNmyhYiIiDzLNG3alE2bNgHw7bffcueddzrlV43WmldffZXQ0FA6d+583WVOnz6de/7r4MGDmKbptGJ58eJF/vzzz9zHP/zwA1WqVMmzTEREBJs3b0Zrzf79+/H29rasec+V2+aKiIgIvvjiCwC++OILIiMjr1mmUaNG7Nq1i/Pnz3P+/Hl27dpFo0aNnJrLrgryeXOlguzjrlaQfcqVrj6n/P333zu92fyK/L4PC7N9ivSFujt27GDp0qWYpknbtm3p1q0by5cvp2bNmkRERHDp0iUSExM5fPgwZcuWZezYsVSoUMHhOX788UemTp1KlSpVcgtg7969c49Q7r33XtatW8enn36Km5sbnp6e9OvXjzvuuMPhWQD++OMP5syZA+QcObZs2ZJu3brx6aef5ubRWpOUlMSuXbvw9PRkxIgR1KxZ0yl5Ll68yIgRI0hMTMw91L86i7O3zcsvv8y+ffs4d+4cvr6+9OzZk8jISOLj40lLS8vT5fXQoUN89tlnDB8+HICNGzeSnJwM5HQzb9u2rcNyFTXX+7xZJb993FVuZZ+yKs/evXv55ZdfUEoRHBzM0KFDnfoj9Ir8vg/DwsJuefsU6QIlhBCi+CqyTXxCCCGKNylQQgghbEkKlBBCCFuSAiWEEMKWpEAJIYSwJSlQQgghbEkKlBBCCFuSAiWEEMKWpECVACdOnGDAgAH8/PPPQM6YcoMGDWLv3r0WJxNCiPxJgSoBQkJC6Nu3L6+88gp//fUXCxcupHXr1tx5551WRxNCiHzJUEclyAsvvEBqaipKKWbNmoWHh4fVkYQQIl9yBFWCtG/fniNHjvCvf/1LipMQwvakQJUQFy9eZOnSpbRr146VK1dy/vx5qyMJIcQNSYEqIZYsWUKNGjUYPnw4TZo04fXXX7c6khBC3JAUqBJg69atpKSkMGTIEAAee+wxDh8+zJdffmlxMiGEyJ90khBCCGFLcgQlhBDClqRACSGEsCUpUEIIIWxJCpQQQghbkgIlhBDClqRACSGEsCUpUEIIIWxJCpQQQghbkgIlhBDClv4/OIj4vRyeUB4AAAAASUVORK5CYII=\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", "\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": 79, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "CPU times: user 2.2 ms, sys: 132 µs, total: 2.33 ms\n", "Wall time: 1.53 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", "\n", "x_bar=np.zeros((N,T+1))\n", "x_bar[:,0]=x0\n", "\n", "for t in range (1,T+1):\n", " xt=x_bar[:,t-1].reshape(N,1)\n", " ut=u_bar[:,t-1].reshape(M,1)\n", " \n", " A,B,C=get_linear_model(xt,ut)\n", " \n", " xt_plus_one = np.dot(A,xt)+np.dot(B,ut)+C\n", " \n", " x_bar[:,t]= np.squeeze(xt_plus_one)" ] }, { "cell_type": "code", "execution_count": 80, "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", "\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": 81, "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": 84, "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", "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": 99, "metadata": {}, "outputs": [ { "name": "stderr", "output_type": "stream", "text": [ "/home/marcello/.local/lib/python3.6/site-packages/ipykernel_launcher.py:29: RuntimeWarning: invalid value encountered in true_divide\n" ] }, { "name": "stdout", "output_type": "stream", "text": [ "CVXPY Optimization Time: Avrg: 0.1807s Max: 0.2490s Min: 0.1668s\n" ] } ], "source": [ "track = compute_path_from_wp([0,3,4,6,10],\n", " [0,0,2,4,3])\n", "\n", "sim_duration = 60 #time steps\n", "opt_time=[]\n", "\n", "x_sim = np.zeros((N,sim_duration))\n", "u_sim = np.zeros((M,sim_duration-1))\n", "\n", "MAX_SPEED = 1.5\n", "MIN_SPEED = 0.5\n", "MAX_STEER_SPEED = 1.57\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", " \n", " #x_bar[:,0]=x_sim[:,sim_time]\n", " for t in range (1,T+1):\n", " xt=x_bar[:,t-1].reshape(N,1)\n", " ut=u_bar[:,t-1].reshape(M,1)\n", "\n", " A,B,C=get_linear_model(xt,ut)\n", "\n", " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\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", " cost += 10*cp.sum_squares(x[2,t]-np.arctan(df(x_bar[0,t],K))) # psi\n", " cost += 20*cp.sum_squares(f(x_bar[0,t],K)-x[1,t]) # cte\n", "\n", " # Actuation rate of change\n", " if t < (T - 1):\n", " cost += cp.quad_form(u[:, t + 1] - u[:, t], 1*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": 100, "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 }