{ "cells": [ { "cell_type": "code", "execution_count": 1, "metadata": {}, "outputs": [], "source": [ "import numpy as np\n", "from scipy.integrate import odeint\n", "from scipy.interpolate import interp1d\n", "import cvxpy as cp\n", "\n", "import matplotlib.pyplot as plt\n", "plt.style.use(\"ggplot\")\n", "\n", "import time" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "### kinematics model equations\n", "\n", "The variables of the model are:\n", "\n", "* $x$ coordinate of the robot\n", "* $y$ coordinate of the robot\n", "* $v$ velocity of the robot\n", "* $\\theta$ heading of the robot\n", "\n", "The inputs of the model are:\n", "\n", "* $v$ linear velocity of the robot\n", "* $\\delta$ angular velocity of the robot\n", "\n", "These are the differential equations f(x,u) of the model:\n", "\n", "$\\dot{x} = f(x,u)$\n", "\n", "* $\\dot{x} = v\\cos{\\theta}$ \n", "* $\\dot{y} = v\\sin{\\theta}$\n", "* $\\dot{v} = a$\n", "* $\\dot{\\theta} = \\frac{v\\tan{\\delta}}{L}$\n", "\n", "Discretize with forward Euler Integration for time step dt:\n", "\n", "${x_{t+1}} = x_{t} + f(x,u)dt$\n", "\n", "* ${x_{t+1}} = x_{t} + v_t\\cos{\\theta}dt$\n", "* ${y_{t+1}} = y_{t} + v_t\\sin{\\theta}dt$\n", "* ${v_{t+1}} = v_{t} + a_tdt$\n", "* ${\\theta_{t+1}} = \\theta_{t} + \\frac{v\\tan{\\delta}}{L} dt$\n", "\n", "----------------------\n", "\n", "The Model is **non-linear** and **time variant**, but the Numerical Optimizer requires a Linear sets of equations. To approximate the equivalent **LTI** State space model, the **Taylor's series expansion** is used around $\\bar{x}$ and $\\bar{u}$ (at each time step):\n", "\n", "$ f(x,u) \\approx f(\\bar{x},\\bar{u}) + \\frac{\\partial f(x,u)}{\\partial x}|_{x=\\bar{x},u=\\bar{u}}(x-\\bar{x}) + \\frac{\\partial f(x,u)}{\\partial u}|_{x=\\bar{x},u=\\bar{u}}(u-\\bar{u})$\n", "\n", "This can be rewritten usibg the State Space model form Ax+Bu :\n", "\n", "$ f(\\bar{x},\\bar{u}) + A|_{x=\\bar{x},u=\\bar{u}}(x-\\bar{x}) + B|_{x=\\bar{x},u=\\bar{u}}(u-\\bar{u})$\n", "\n", "Where:\n", "\n", "$\n", "A =\n", "\\quad\n", "\\begin{bmatrix}\n", "\\frac{\\partial f(x,u)}{\\partial x} & \\frac{\\partial f(x,u)}{\\partial y} & \\frac{\\partial f(x,u)}{\\partial \\theta} \\\\\n", "\\end{bmatrix}\n", "\\quad\n", "=\n", "\\quad\n", "\\begin{bmatrix}\n", "0 & 0 & -v\\sin{\\theta} \\\\\n", "0 & 0 & v\\cos{\\theta} \\\\\n", "0 & 0 & 0\\\\\n", "\\end{bmatrix}\n", "\\quad\n", "$\n", "\n", "and\n", "\n", "$\n", "B = \n", "\\quad\n", "\\begin{bmatrix}\n", "\\frac{\\partial f(x,u)}{\\partial v} & \\frac{\\partial f(x,u)}{\\partial \\delta} \\\\\n", "\\end{bmatrix}\n", "\\quad\n", "= \n", "\\quad\n", "\\begin{bmatrix}\n", "\\cos{\\theta} & 0 \\\\\n", "\\sin{\\theta} & 0 \\\\\n", "\\frac{\\tan{\\delta}}{L} & \\frac{v}{L{\\cos{\\delta}}^2}\n", "\\end{bmatrix}\n", "\\quad\n", "$\n", "\n", "are the *Jacobians*.\n", "\n", "\n", "\n", "So the discretized model is given by:\n", "\n", "$ x_{t+1} = x_t + (f(\\bar{x},\\bar{u}) + A|_{x=\\bar{x}}(x_t-\\bar{x}) + B|_{u=\\bar{u}}(u_t-\\bar{u}) )dt $\n", "\n", "$ x_{t+1} = (I+dtA)x_t + dtBu_t +dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\bar{u}))$\n", "\n", "The LTI-equivalent kinematics model is:\n", "\n", "$ x_{t+1} = A'x_t + B' u_t + C' $\n", "\n", "with:\n", "\n", "$ A' = I+dtA|_{x=\\bar{x},u=\\bar{u}} $\n", "\n", "$ B' = dtB|_{x=\\bar{x},u=\\bar{u}} $\n", "\n", "$ C' = dt(f(\\bar{x},\\bar{u}) - A|_{x=\\bar{x},u=\\bar{u}}\\bar{x} - B|_{x=\\bar{x},u=\\bar{u}}\\bar{u}) $" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "-----------------\n", "[About Taylor Series Expansion](https://courses.engr.illinois.edu/ece486/fa2017/documents/lecture_notes/state_space_p2.pdf):\n", "\n", "In order to linearize general nonlinear systems, we will use the Taylor Series expansion of functions.\n", "\n", "Typically it is possible to assume that the system is operating about some nominal\n", "state solution $\\bar{x}$ (possibly requires a nominal input $\\bar{u}$) called **equilibrium point**.\n", "\n", "Recall that the Taylor Series expansion of f(x) around the\n", "point $\\bar{x}$ is given by:\n", "\n", "$f(x)=f(\\bar{x}) + \\frac{df(x)}{dx}|_{x=\\bar{x}}(x-\\bar{x})$ + higher order terms...\n", "\n", "For x sufficiently close to $\\bar{x}$, these higher order terms will be very close to zero, and so we can drop them.\n", "\n", "The extension to functions of multiple states and inputs is very similar to the above procedure.Suppose the evolution of state x\n", "is given by:\n", "\n", "$\\dot{x} = f(x1, x2, . . . , xn, u1, u2, . . . , um) = Ax+Bu$\n", "\n", "Where:\n", "\n", "$ A =\n", "\\quad\n", "\\begin{bmatrix}\n", "\\frac{\\partial f(x,u)}{\\partial x1} & ... & \\frac{\\partial f(x,u)}{\\partial xn} \\\\\n", "\\end{bmatrix}\n", "\\quad\n", "$ and $ B = \\quad\n", "\\begin{bmatrix}\n", "\\frac{\\partial f(x,u)}{\\partial u1} & ... & \\frac{\\partial f(x,u)}{\\partial um} \\\\\n", "\\end{bmatrix}\n", "\\quad $\n", "\n", "Then:\n", "\n", "$f(x,u)=f(\\bar{x},\\bar{u}) + \\frac{df(x,u)}{dx}|_{x=\\bar{x}}(x-\\bar{x}) + \\frac{df(x,u)}{du}|_{u=\\bar{u}}(u-\\bar{u}) = f(\\bar{x},\\bar{u}) + A_{x=\\bar{x}}(x-\\bar{x}) + B_{u=\\bar{u}}(u-\\bar{u})$\n", "\n", "-----------------" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "### Kinematics Model" ] }, { "cell_type": "code", "execution_count": 2, "metadata": {}, "outputs": [], "source": [ "# Control problem statement.\n", "\n", "N = 4 #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": 3, "metadata": {}, "outputs": [], "source": [ "def get_linear_model(x_bar,u_bar):\n", " \"\"\"\n", " \"\"\"\n", " L=0.3\n", " \n", " x = x_bar[0]\n", " y = x_bar[1]\n", " v = x_bar[2]\n", " theta = x_bar[3]\n", " \n", " a = u_bar[0]\n", " delta = u_bar[1]\n", " \n", " A = np.zeros((N,N))\n", " A[0,2]=np.cos(theta)\n", " A[0,3]=-v*np.sin(theta)\n", " A[1,2]=np.sin(theta)\n", " A[1,3]=v*np.cos(theta)\n", " A[3,2]=v*np.tan(delta)/L\n", " A_lin=np.eye(N)+dt*A\n", " \n", " B = np.zeros((N,M))\n", " B[2,0]=1\n", " B[3,1]=v/(L*np.cos(delta)**2)\n", " B_lin=dt*B\n", " \n", " f_xu=np.array([v*np.cos(theta), v*np.sin(theta), a,v*np.tan(delta)/L]).reshape(N,1)\n", " C_lin = dt*(f_xu - np.dot(A,x_bar.reshape(N,1)) - np.dot(B,u_bar.reshape(M,1)))\n", " \n", " return np.round(A_lin,4), np.round(B_lin,4), np.round(C_lin,4)" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Motion Prediction: using scipy intergration" ] }, { "cell_type": "code", "execution_count": 4, "metadata": {}, "outputs": [], "source": [ "# Define process model\n", "# This uses the continuous model \n", "def kinematics_model(x,t,u):\n", " \"\"\"\n", " \"\"\"\n", " \n", " #[x,y,v,th]\n", " #[a,d]\n", " \n", " L=0.3\n", " dxdt = x[2]*np.cos(x[3])\n", " dydt = x[2]*np.sin(x[3])\n", " dvdt = u[0]\n", " dthetadt = x[2]*np.tan(u[1])/L\n", "\n", " dqdt = [dxdt,\n", " dydt,\n", " dvdt,\n", " dthetadt]\n", "\n", " return dqdt\n", "\n", "def predict(x0,u):\n", " \"\"\"\n", " \"\"\"\n", " \n", " x_bar = np.zeros((N,T+1))\n", " \n", " x_bar[:,0] = x0\n", " \n", " # solve ODE\n", " for t in range(1,T+1):\n", "\n", " tspan = [0,dt]\n", " x_next = odeint(kinematics_model,\n", " x0,\n", " tspan,\n", " args=(u[:,t-1],))\n", "\n", " x0 = x_next[1]\n", " x_bar[:,t]=x_next[1]\n", " \n", " return x_bar" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Validate the model, here the status w.r.t a straight line with constant heading 0" ] }, { "cell_type": "code", "execution_count": 5, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "CPU times: user 3.66 ms, sys: 83 µs, total: 3.74 ms\n", "Wall time: 3.22 ms\n" ] } ], "source": [ "%%time\n", "\n", "u_bar = np.zeros((M,T))\n", "u_bar[0,:] = 0.2 #m/ss\n", "u_bar[1,:] = np.radians(-np.pi/4) #rad\n", "\n", "x0 = np.zeros(N)\n", "x0[0] = 0\n", "x0[1] = 1\n", "x0[2] = 0\n", "x0[3] = np.radians(0)\n", "\n", "x_bar=predict(x0,u_bar)" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Check the model prediction" ] }, { "cell_type": "code", "execution_count": 6, "metadata": {}, "outputs": [ { "data": { "image/png": "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\n", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "#plot trajectory\n", "plt.subplot(2, 2, 1)\n", "plt.plot(x_bar[0,:],x_bar[1,:])\n", "plt.plot(np.linspace(0,10,T+1),np.zeros(T+1),\"b-\")\n", "plt.axis('equal')\n", "plt.ylabel('y')\n", "plt.xlabel('x')\n", "\n", "plt.subplot(2, 2, 2)\n", "plt.plot(np.degrees(x_bar[2,:]))\n", "plt.ylabel('theta(t) [deg]')\n", "#plt.xlabel('time')\n", "\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Motion Prediction: using the state space model" ] }, { "cell_type": "code", "execution_count": 7, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "CPU times: user 1.95 ms, sys: 4.06 ms, total: 6.01 ms\n", "Wall time: 1.77 ms\n" ] } ], "source": [ "%%time\n", "\n", "u_bar = np.zeros((M,T))\n", "u_bar[0,:] = 0.2 #m/s\n", "u_bar[1,:] = np.radians(-np.pi/4) #rad\n", "\n", "x0 = np.zeros(N)\n", "x0[0] = 0\n", "x0[1] = 1\n", "x0[2] = 0\n", "x0[3] = np.radians(0)\n", "\n", "x_bar=np.zeros((N,T+1))\n", "x_bar[:,0]=x0\n", "\n", "for t in range (1,T+1):\n", " xt=x_bar[:,t-1].reshape(N,1)\n", " ut=u_bar[:,t-1].reshape(M,1)\n", " \n", " A,B,C=get_linear_model(xt,ut)\n", " \n", " xt_plus_one = np.dot(A,xt)+np.dot(B,ut)+C\n", " \n", " x_bar[:,t]= np.squeeze(xt_plus_one)" ] }, { "cell_type": "code", "execution_count": 8, "metadata": {}, "outputs": [ { "data": { "image/png": "iVBORw0KGgoAAAANSUhEUgAAAagAAAChCAYAAACSyiu8AAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAADh0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uMy4yLjIsIGh0dHA6Ly9tYXRwbG90bGliLm9yZy+WH4yJAAAgAElEQVR4nO3deXxU5dn/8c99spCEkGRIgkgQJIAKFC2YlLpgCgk8imCj9UFBQAiWKgIVWir0p4gPRtGaRsPqEtnUR7BIFEutjZSA5aENm0BQtiKiCCE72chy7t8fU1JoErKQmXMmud6vV15m5pw5853jYa6c7b6U1lojhBBC2IxhdQAhhBCiLlKghBBC2JIUKCGEELYkBUoIIYQtSYESQghhS1KghBBC2JK31QGEEM1XUlLC8uXLOXnyJEopHnvsMbp06UJycjJnz54lPDycmTNnEhgYaHVUIZpMyX1QQniuxYsX06dPH2JjY6mqquL8+fNs2LCBwMBA4uPjSUtLo7i4mHHjxlkdVYgmk0N8Qnio0tJSvvzyS4YOHQqAt7c37du3JzMzk5iYGABiYmLIzMy0MqYQzSaH+ITwUNnZ2QQFBbF06VJOnDhBZGQkEydOpLCwEIfDAYDD4aCoqMjipEI0j632oEzT5De/+Q0LFy60OooQtlddXc3x48cZPnw4L730Eu3atSMtLa3Rr09PT2fOnDnMmTPHhSmFaD5b7UFt2rSJiIgIysrKGjX/qVOn6nw+LCyMnJyclox2xeyWSfI07HKZunTp4uY0tYWGhhIaGkrv3r0B+PGPf0xaWhrBwcHk5+fjcDjIz88nKCioztfHxcURFxdX89hT/j3ZLQ/YL5On5anv35Nt9qByc3PZvXs3sbGxVkcRwiOEhIQQGhpaU1j2799P165diYqKIiMjA4CMjAyio6OtjClEs9lmD2rlypWMGzfusntP6enppKenA7Bw4ULCwsLqnM/b27veaVaxWybJ0zA7ZvpPCQkJpKSkUFVVRadOnZg6dSpaa5KTk9m8eTNhYWHMmjXL6piijTNLS5r1OlsUqF27dhEcHExkZCRZWVn1zvefhyTq22W02+4t2C+T5GmY3Q/xAVx77bV1nrOdN2+eBWmEuJSurERv/F9yt38GT7+CCnY06fW2KFCHDh1i586d7Nmzh4qKCsrKykhJSWHGjBlWRxNCCNEM+uRxzLeS4duvaTf0bip8fJu8DFsUqLFjxzJ27FgAsrKy2LhxoxQnIYTwQLq6Gv3JevTG96B9IMa0pwiOHdGsIyS2KFBCCCE8nz79LeZbr8Dxw6io21EPPYoKrPsq0sawXYHq168f/fr1szqGEEKIRtKmid78MfqD1eDbDjVlNkb04Cteru0KlBBCCM+hc85grkyBQ/uhfxTGhGmokI4tsmwpUEIIIZpMa43+/C/otamgQD08HXVbHEqpFnsPKVBCCCGaRBfkYq5eAvt3wvX9MSb9EhXaqcXfRwqUEEKIRtFaozO3od9ZDlUVqAenoIaMQBmuGZRICpQQQogG6XNF6HeWoXf9DSKvx5j0BKpzhEvfUwqUEEKIy9J7/465ejGUlqDum4Aafi/Ky8vl7ysFSgghRJ10aQl67Zvo7Z9B12sxZv4P6poebnt/KVBCCCFq0Qf3Yq5Kgfw81IjRqFEPoLx93JpBCpQQQoga+nw5ev1K9F83QecIjDkvoiKvtySLFCghhBAA6KMHnUMVnT2NirsHde94lG87y/JIgRJCiDZOV1agP3wX/ekG6BiO8etE1PX9rY4lBUoIIdoyfeKYsy3GqW9Qg4ejRieg/AKsjgVIgRJCiDZJV1Wh//QH9B/XQmAwxoxnUP1vtjrWJaRACSFEG6NPfeM813TiKGpQDGrMFFT7DlbHqkUKlBBCtBHarEanb0RvWAN+fhiPPom6+TarY9VLCpQQQrQB+uxpzBWvwJGDcNOPMCY8jgpyWB3rsqRACSFEK6a1Rm/9M/r9t8AwUJOeQN0ypEXbYriKFCghhGildF4O5qpFcHAP9LkJY+IMVMdwq2M1mhQoIYRoZbTWmDv+in73daiuQj30KCrmLo/Ya7qYFCghhGhFdFEBham/R+/YAr36OJsJdupidaxmsUWBysnJYcmSJRQUFKCUIi4ujhEjRlgdSwghPIre/X+Yby/lfFkp6v5JqGH3oAzXt8VwFVsUKC8vL8aPH09kZCRlZWXMmTOHG2+8ka5du1odTQghbE+XFKPfe92519StJ6HPPUtBQJDVsa6YLQqUw+HA4XBe7ujv709ERAR5eXlSoIRogGmazJkzh44dOzJnzhyKi4tJTk7m7NmzhIeHM3PmTAIDA62OKVxIH9jtvBCiKB816kHUiNF4d+4MOTlWR7tirmkkfwWys7M5fvw4vXr1sjqKELa3adMmIiL+3XY7LS2N/v37k5KSQv/+/UlLS7MwnXAlXV6G+fZSzFfng38Axm9fxrhnLMrbFvsdLcJWn6S8vJykpCQmTpxIQEDtwQrT09NJT08HYOHChYSFhdW5HG9v73qnWcVumSRPw+yY6WK5ubns3r2b++67j48//hiAzMxM5s+fD0BMTAzz589n3LhxFqYUrqAPZ2GufBVyzjjbr8c/hPLxtTpWi7NNgaqqqiIpKYnBgwczaNCgOueJi4sjLi6u5nFOPbuwYWFh9U6zit0ySZ6GXS5Tly7NvyqqqKiIrVu3snv3bk6cOEFpaSkBAQF0796dH/7wh/zkJz8hKKjh8wcrV65k3LhxlJWV1TxXWFhYc7jc4XBQVFTU7JzCfnRlBTrtbfRfPoSwqzBmv4Dq3dfqWC5jiwKltWb58uVEREQwcuRIq+MI4TLvvvsu27ZtY8CAAQwdOpSIiAj8/f0pKyvju+++4+DBgzz55JPcfvvtPPTQQ/UuZ9euXQQHBxMZGUlWVlazsnjqEQm75QH3ZKo8+iWFry7A/PZr/O+8l8AJj2P4190Ww27rqLl5bFGgDh06xNatW+nWrRuzZ88GYMyYMQwcONDiZEK0LIfDQUpKCj4+PrWm9ejRg9tvv52Kigo2b9582eUcOnSInTt3smfPHioqKigrKyMlJYXg4GDy8/NxOBzk5+dfdk/MU49I2C0PuDaTrqpC/3EdetM6CHJgPPEsFf0GkFdSCiWlbs/THA3lqe+IhC0K1A033MC6deusjiGEy9111101vxcUFBASElJrntLSUu68887LLmfs2LGMHTsWgKysLDZu3MiMGTNYs2YNGRkZxMfHk5GRQXR0dMt+AOFW+rsTzmaC3/zTOX7egz9HBbSdqzJtdxWfEG3FL3/5yzqfnzlzZrOXGR8fz759+5gxYwb79u0jPj6+2csS1tFmNeYn6zGfmwn5uRhTf4uRMLNNFSewyR6UEG2R1rrWc6WlpRhG0/5u7NevH/369QOgQ4cOzJs3r0XyCWvo7FPOZoLHvoKBt2CMm4rqEGx1LEtIgRLCzR577DEAKioqan6/oLi4mNtus28DOeE62jTRGX9C/2EleHujHvkV6kd3eNwAry1JCpQQbjZ9+nS01rzwwgtMnz79kmkhISFXdAm78Ew69yzmqhT48gv4wUCMCdNRjlCrY1lOCpQQbta3r/O+ldTUVNq1a2dxGmElrTV6+2b02jfA1Kjxj6MGD2/Te00Xk4skhHCjTZs2UVlZCVBvcaqsrGTTpk3ujCUsoAvzMZckole+CtdEYjzzKsYd/yXF6SKyByWEGxUUFDBjxgwGDBhA37596dKlC35+fpSXl3Pq1CkOHjzInj17iImJsTqqcCG983PMd5bB+fOoByajho5CNfHimLZACpQQbjR27FhGjhzJli1b2Lx5M9988w0lJSUEBgbSrVs3BgwYwJgxY+jQoYPVUYUL6JJz6HeWozO3QY/rMCY9gbpaujbUp9UVKPP//kpB1i6qKyqcTyjD+ZeJYYDhBV5e4O0N3j7OHx9f8PEBX1/wbQft/FHtnP/FLwD8/cG/PQS0b5WDMQr3CwoK4p577uGee+6xOopwI70vE3P1YiguQsWPQ935M5SX5zYTdIdWV6AoKaL69HdQVeV8rDXarAbThOrqf/1UOadXVkBVZa1F1L475V+8faB9BwhoD4EdIDAIFRgEgUEQFAIdglFBIRDSEYId4N9ejicL0cbpslL0ulT053+BiO4YM55BdYu0OpZHaHUFyoj7KaEPTm70OFRaa2eRqqiA8+VQUe78b3k5lJehy0uhrARKL/wUo0vOQUkxZH+PPvYVFBc5CyD/Udx8fFH/nYAxRNrXi9pKS0t5//33OXjwIOfOnbvkxt1ly5ZZmEy0FP3VPsyVKZCXg7rrftSoMag6xmEUdWt1BaqplFL/OsznC+1rDyPSmP0fbZpQWgznCqEwH12YD4V5UJiPiujW8qFFq/Dmm2+Sl5fH/fffz6JFi5g+fTofffRRve1mhOfQ58+jN6xGf7YROnXBeHIhqucNVsfyOG2+QLUEZRjOw3yBQXD1NY0qakLs27eP5ORkOnTogGEYREdH07NnT1588UVpO+PB9LGvMFe8Cme+Q8WOQt07wXleWzSZFCghLKK1rukc7efnR0lJCSEhIZw+fdriZKI5dGUl+uP30H9aD45QjFkLUH1usjqWR2t0gVq1ahUxMTFce+21LowjRNvRvXt3Dh48SP/+/bnhhhtITU3Fz8+Pq6++2upoookqjx/B/P0z8O3XqNviUKMnowLaWx3L4zW6QFVXV5OYmEhQUBCDBw9m8ODBhIbKWFFCNNcvfvGLmgsjEhISePfddykpKWHatGkWJxONpaur0Z+sJ+/j96B9B4xpT6Nukh5cLaXRBSohIYGJEyeyZ88etm3bxgcffEDv3r254447GDRoEH5+fq7MKUSrU1RURO/evQHnvVGPPvooAEePHrUylmgk/f23mCtegeOHaXd7LJU/m+S87US0mCaNrWEYBjfffDNPPPEEiYmJFBUVsXTpUn7+85+zfPly8vLyXJVTiFbnueeeq/P5xMRENycRTaFNEzP9I8wFT0D296gpswn51QIpTi7QpIskSktL2bFjB9u2bePEiRMMGjSIyZMnExYWxscff8zzzz/Pyy+/7KqsQrQK5oV75rSu+bngzJkzeMnoAralc84472s6tB/6R2FMmIYK6Wh1rFar0QUqKSmJL774gj59+jBs2DCio6PxueiGswkTJjBx4kRXZBSiVRkzZkzN7w8++OAl0wzD4N5773V3JNEArTX687+g16aCAvXwdOfFEDJSjEs1ukD17t2byZMnExISUud0wzB44403mh1k7969rFixAtM0iY2NJT4+vtnLEsLOFi9ejNaa+fPn8+yzz6K1RimFUoqgoCB8fWXMRzvRBbmYq5fA/p1wfX+MSb9EhXayOlab0OgC1ZiBLZvbfM00TVJTU3nqqacIDQ1l7ty5REVF0bWrjPIrWp/w8HAAli5dCji3/8LCQhwOh5WxxH/QWqP/sRX97mtQVYF6cApqyAhpi+FGtrhR9+jRo3Tu3JmrrroKgFtvvZXMzEwpUKJVKykp4c0332THjh14e3uzZs0adu7cydGjR2sd+hPupc8VOvs17doOkdc722J0jrA6VptjiwKVl5d3yT1VoaGhHDlypFnLmjcviCNHvKmstNc9Wj4+9sokeRp2881ezJ3ruuW/8cYbtG/fnqVLlzJr1iwArrvuOlavXi0FykJ679+dbTFKS1D3TUANv1faYljEFgXq4quYLqjr5GN6ejrp6ekALFy4kLCwsFrz+Pt7oZS65AIOO7BbJsnTMMNQdW5jLWX//v289tpreHv/+59hUFAQhYWFLntPUT9dWoJe+yZ6+2fQtQfGrP9Bde1hdaw2zRYFKjQ0lNzc3JrHubm5dR6Pj4uLIy4uruZxXS015s6FsLCwRrfbcBe7ZZI8Dbtcpi5dulzx8gMCAjh37twl23pOTo6ci7KAPrgXc1UKFOSh7h6NGvkAyttefzC1RbY429ezZ0++//57srOzqaqqYvv27URFRVkdSwiXio2NJSkpiQMHDqC15vDhwyxZsoRhw4ZZHa3N0OfLMd9djpk8D3zbYcx5CSN+nBQnm7DFHpSXlxcJCQkkJiZimiZDhgzhmmuusTqWEC7105/+FB8fH1JTU6murmbZsmXExcUxYkTjGlzm5OSwZMkSCgoKUErVvLa4uJjk5GTOnj1LeHg4M2fOJDCwdq+ztk4f/dI5VFH296i4e1D3jkf5SlsMO7FFgQIYOHAgAwcOtDqGEG6jlOLuu+/m7rvvbtbrvby8GD9+PJGRkZSVlTFnzhxuvPFGtmzZQv/+/YmPjyctLY20tDTGjRvXwuk9l66sQH/4LvrTNOgYhvHrRNT1/a2OJepgmwIlRFt06tQpvv76a8rLyy95fujQoQ2+1uFw1Jyv8vf3JyIigry8PDIzM5k/fz4AMTExzJ8/XwrUv+gTxzDfSoZT36AGD0eNTkD5BVgdS9RDCpQQFvnggw9Yv3493bt3r3WTe2MK1MWys7M5fvw4vXr1uuSmX4fDQVFRUYtl9lS6qgr9pz+g/7gWAoMxZjyD6n+z1bFEA6RACWGRTZs28fzzz9O9e/crWk55eTlJSUlMnDixpkNvYzTmtg0Ab29vl15u31RNzVN18jiFKQuoOvoVfncMp8MjszA6tOzI456+jlytuXmkQAlhEV9fXyIirmx0gqqqKpKSkhg8eDCDBg0CIDg4mPz8fBwOB/n5+QQF1f1l3JjbNsB+twA0No82q9HpH6E3vA1+/hiPPknlzbeRd74Czrfs5/HUdeQuDeWp77YNW1xmLkRbYZpmzc8DDzzAW2+9RX5+/iXPX2jH0RCtNcuXLyciIoKRI0fWPB8VFUVGRgYAGRkZREe3vQ6v+uxpzJf/H/r9FfCDgRjPLkLdfJvVsUQTyR6UEG50cauNCz777LNaz61du7bBZR06dIitW7fSrVs3Zs+eXbP8+Ph4kpOT2bx5M2FhYTXDKLUFWmv01j+j338LDAM16QnULUOkLYaHkgIlhBstXrwYcH6R7tixg1tuueWS6Vpr/v73vzdqWTfccAPr1q2rc9q8efOuLKgH0nk5mKsXQdYe6HMTxsQZqI7hVscSV0AKlBBudKHVBsD69evrbGPzwQcfMGrUKHfG8mhaa/SOLej/fR2qq1APPYqKuUv2mloBKVBCuNmBAwcAqK6urvn9gjNnzuDv729FLI+kiwow314Ke3ZArz7OZoKdrnycRGEPUqCEcLNly5YBUFlZWfM7OEeWCAkJISEhwapoHkXv3o65ZimUl6Lun4Qadg/KkLYYrYkUKCHcbMmSJYDzfNS0adMsTuN5zOIizNTfo3dsgW49MRJmoiK6WR1LuIAUKCEsIsWp6fSB3eS+vQRdkIcaNQY14r9R3vI11lrJ/1khhO3p8jL0+yvQWz/B65oeGI/NRXXvZXUs4WJSoIQQtqYPH8Bc8SrkZqP+615CE2aQW3TO6ljCDaRACSFsSVecR6e9jU7/CMKuwpj9Aqp333/1bJIC1RZIgRJC2I4+fsTZTPD7k6ifjED97GGUn1x+39ZIgRJC2IauqkT/cR160/sQ5MB44llUvwFWxxIWkQIlhLAF/d0JZzPBb/6J+vEQ1JifowKkVX1bJgVKCGEpbVajP01Df/gO+LfHmPpb1IAfWx1L2IAUKCGEZfSZU85zTce+goG3YIybiuoQbHUsYROWF6g1a9awa9cuvL29ueqqq5g6dSrt27e3OpYQwoW0aaK3bEKvXwnePqhHfoX60R0ywKu4hOUF6sYbb2Ts2LF4eXnx9ttvs2HDBsaNG2d1LCGEi+jcs5irUuDLL5zNBCdMRzlCrY4lbMjyAnXTTTfV/H7dddexY8cOC9MIIVxFa43evhm99g0wNWr846jBw2WvSdTL8gJ1sc2bN3PrrbdaHUMI0cJ0YT7mmiXwxT/guh84mwmGd7Y6lrA5txSoBQsWUFBQUOv5Bx98kOjoaMDZpM3Ly4vBgwfXu5z09HTS09MBWLhwIWFhYXXO5+3tXe80q9gtk+RpmB0zeSK983PMd5ZBeTlq9GRU7CiUYVgdS3gAtxSop59++rLTt2zZwq5du5g3b95ld/fj4uKIi4ureZyTk1PnfGFhYfVOs4rdMkmehl0uU5cu0hSvIbrkHPqd5ejMbXBtb4yEJ1BXX2N1LOFBLD/Et3fvXj788EOeffZZ2rVrZ3UcIUQL0PsyMVcvhuIi1E8fQt11P8pLmgmKprG8QKWmplJVVcWCBQsA6N27N1OmTLE4lRCiOXRZKXpdKvrzv0BEd4wZz6C6RVodS3goywvUokWLrI4ghGgB+qt9mCtTIC/Hucc0agzKx8fqWMKDWV6ghBCeTZ8/j96wGv3ZRujUBePJhaieN1gdS7QCUqCEEM2mj33lbCZ45jvn1Xn3TkDJuWTRQqRACSGaTFdWoj9+D/2n9eAIxZi1ANXnpoZfKEQTSIESQjSJPnnc2Rbj269Rt8WhHngE5R9gdSzRCkmBEqIV2rt3LytWrMA0TWJjY4mPj7/iZerqavQn69Eb34PADhjTnkbdFN0CaYWomxQoIVoZ0zRJTU3lqaeeIjQ0lLlz5xIVFUXXrl2bvUz9/bfOvaavj6CiB6PG/gIVGNSCqYWoTQqUEK3M0aNH6dy5M1dddRUAt956K5mZmc0qUNo0Kd24FnPNMvBth5oyGyO6/uHIhGhJUqCEaGXy8vIIDf13+4rQ0FCOHDnS5OVosxrzlfmc+/IL6B+FMWEaKqRjS0YV4rKkQAnRymitaz1X1xiXjRl8ueTmW/AeNgrfn9xlm7YYdhzE126ZWkseKVBCtDKhoaHk5ubWPM7NzcXhcNSar1GDL8eMsN1AvnbLA/bL5Gl56ht8Wca8F6KV6dmzJ99//z3Z2dlUVVWxfft2oqKirI4lRJPJHpQQrYyXlxcJCQkkJiZimiZDhgzhmmukzYXwPFKghGiFBg4cyMCBA62OIcQVUbquM6pCCCGExVrlOag5c+ZYHaEWu2WSPA2zYyYr2G092C0P2C9Ta8nTKguUEEIIzycFSgghhC15zZ8/f77VIVwhMtJ+babtlknyNMyOmaxgt/Vgtzxgv0ytIY9cJCGEEMKW5BCfEEIIW/Lo+6Aa6nmjtWbFihXs2bOHdu3aMXXqVJft9ubk5LBkyRIKCgpQShEXF8eIESMumScrK4uXXnqJTp06ATBo0CDuv/9+l+S54PHHH8fPzw/DMPDy8mLhwoWXTHfnOjp16hTJyck1j7Ozsxk9ejR33313zXPuWEdLly5l9+7dBAcHk5SUBEBxcTHJycmcPXuW8PBwZs6cSWBgYK3XuqLPkl3Z8bM2tD272pVsO+7MtG7dOj777DOCgpwtUcaMGeO2++Lq+y5s1nrSHqq6ulpPmzZNnz59WldWVupf//rX+uTJk5fMs2vXLp2YmKhN09SHDh3Sc+fOdVmevLw8fezYMa211qWlpXrGjBm18hw4cEC/8MILLstQl6lTp+rCwsJ6p7tzHV2surpaP/LIIzo7O/uS592xjrKysvSxY8f0rFmzap5bs2aN3rBhg9Za6w0bNug1a9bUmbmhba61sOtnbWh7drXmbjvuzrR27Vr94YcfujXHBfV9FzZnPXnsIb6Le954e3vX9Ly52M6dO7njjjtQSnHddddRUlJCfn6+S/I4HI6aPQ9/f38iIiLIy8tzyXu1JHeuo4vt37+fzp07Ex4e7vL3+k99+/at9ZdbZmYmMTExAMTExNTalqBx21xr0ZY+a1M0d9txdyYr1fdd2Jz15LGH+BrT8yYvL++SId5DQ0PJy8urc2TnlpSdnc3x48fp1atXrWmHDx9m9uzZOBwOxo8f75Yx0hITEwEYNmzYJaNXg3Xr6G9/+xu33XZbndOsWEeFhYU1n9nhcFBUVFRrnpbqs+QJ7PxZL7c9W6Ex244V/vznP7N161YiIyOZMGGCJUXs4u/C5qwnjy1QuhE9bxozT0srLy8nKSmJiRMnEhAQcMm0Hj16sHTpUvz8/Ni9eze/+93vSElJcWmeBQsW0LFjRwoLC3nuuefo0qULffv2rZluxTqqqqpi165djB07ttY0K9ZRY1mxrqxi18/a0PYsnIYPH15z7nbt2rWsXr2aqVOnujXD5b4LG8tjD/E1pudNaGjoJT1I6uuL01KqqqpISkpi8ODBDBo0qNb0gIAA/Pz8AOdgntXV1S7/a6tjR2cH1ODgYKKjozl69Ogl0929jgD27NlDjx49CAkJqTXNinUEzvVz4dBmfn5+zcnlizW2z1JrYNfP2tD2bIXGbDvuFhISgmEYGIZBbGwsx44dc+v71/Vd2Jz15LEFqjE9b6Kioti6dStaaw4fPkxAQIDL/pFprVm+fDkRERGMHDmyznkKCgpq/jI9evQopmnSoUMHl+QB518wZWVlNb/v27ePbt26XTKPO9fRBZc7vOfudXRBVFQUGRkZAGRkZBAdHV1rnrbUZ8mOn7Ux27MVGrPtuNvF55H/8Y9/uLXdSn3fhc1ZTx59o+7u3btZtWpVTc+b++67j08//RRw7uJqrUlNTeWLL77A19eXqVOn0rNnT5dk+eqrr5g3bx7dunWrORQyZsyYmr2T4cOH88knn/Dpp5/i5eWFr68vEyZM4Prrr3dJHoAzZ87w8ssvA1BdXc3tt99u6ToCOH/+PI899hiLFy+u2e2/OI871tErr7zCwYMHOXfuHMHBwYwePZro6GiSk5PJyckhLCyMWbNmERgYSF5eHq+99hpz584F6t7mWiu7fdb6tmd3asq2Y2WmrKwsvv76a5RShIeHM2XKFLftAdf3Xdi7d+8mryePLlBCCCFaL489xCeEEKJ1kwIlhBDClqRACSGEsCUpUEIIIWxJCpQQQghbkgIlhBDClqRACSGEsCUpUEIIIWxJClQbcvr0aSZNmsQ///lPwDli9eTJk8nKyrI4mRBC1CYFqg3p3LkzDz30EIsWLeL8+fMsW7aMmJgY+vXrZ3U0IYSoRYY6aoNefPFFsrOzUUrxwgsv4OPjY3UkIYSoRfag2qDY2FhOnjzJnXfeKcVJCGFbUqDamPLyclatWsXQoUN5//33KS4utjqSEELUSQpUG28dINUAAACESURBVLNixQp69OjBo48+ysCBA3n99detjiSEEHWSAtWGZGZmsnfvXqZMmQLAww8/zPHjx9m2bZvFyYQQoja5SEIIIYQtyR6UEEIIW5ICJYQQwpakQAkhhLAlKVBCCCFsSQqUEEIIW5ICJYQQwpakQAkhhLAlKVBCCCFsSQqUEEIIW/r/95628IoYP0wAAAAASUVORK5CYII=\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)')\n", "#plt.xlabel('time')\n", "\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "The results are the same as expected, so the linearized model is equivalent as expected." ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## PRELIMINARIES" ] }, { "cell_type": "code", "execution_count": 9, "metadata": {}, "outputs": [], "source": [ "def compute_path_from_wp(start_xp, start_yp, step = 0.1):\n", " 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)-1\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[3]) - dy * np.sin(-state[3]),\n", " dy * np.cos(-state[3]) + dx * np.sin(-state[3]) ))\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 f(x,coeff):\n", "# return round(coeff[0]*x**5+coeff[1]*x**4+coeff[2]*x**3+coeff[3]*x**2+coeff[4]*x**1+coeff[5]*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)\n", "# def df(x,coeff):\n", "# return round(5*coeff[0]*x**4 + 4*coeff[1]*x**3 +3*coeff[2]*x**2 + 2*coeff[3]*x**1 + coeff[4]*x**0,6)" ] }, { "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 this is the value of the fitted polynomial\n", "\n", "* **heading error** epsi: desired heading - heading of vehicle -> is the inclination of tangent to the fitted polynomial\n", "\n", "Then using the fitted polynomial representation in vehicle frame the errors can be easily computed as:\n", "\n", "$\n", "cte = f(px) \\\\\n", "\\psi = -atan(f`(px)) \\\\\n", "$" ] }, { "cell_type": "code", "execution_count": 10, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "-----------------------------------------------------------------\n", " OSQP v0.6.0 - Operator Splitting QP Solver\n", " (c) Bartolomeo Stellato, Goran Banjac\n", " University of Oxford - Stanford University 2019\n", "-----------------------------------------------------------------\n", "problem: variables n = 282, constraints m = 343\n", " nnz(P) + nnz(A) = 910\n", "settings: linear system solver = qdldl,\n", " eps_abs = 1.0e-04, eps_rel = 1.0e-04,\n", " eps_prim_inf = 1.0e-04, eps_dual_inf = 1.0e-04,\n", " rho = 1.00e-01 (adaptive),\n", " sigma = 1.00e-06, alpha = 1.60, max_iter = 10000\n", " check_termination: on (interval 25),\n", " scaling: on, scaled_termination: off\n", " warm start: on, polish: on, time_limit: off\n", "\n", "iter objective pri res dua res rho time\n", " 1 0.0000e+00 1.04e+00 1.04e+02 1.00e-01 3.23e-04s\n", " 50 3.3426e+00 2.85e-07 4.93e-08 1.00e-01 6.84e-04s\n", "\n", "status: solved\n", "solution polish: unsuccessful\n", "number of iterations: 50\n", "optimal objective: 3.3426\n", "run time: 9.06e-04s\n", "optimal rho estimate: 1.76e-01\n", "\n", "CPU times: user 226 ms, sys: 5.12 ms, total: 231 ms\n", "Wall time: 234 ms\n" ] } ], "source": [ "%%time\n", "\n", "MAX_SPEED = 1.25\n", "MIN_SPEED = 0.75\n", "MAX_STEER = 1.57\n", "MAX_ACC = 1.0\n", "REF_VEL=1.0\n", "\n", "track = compute_path_from_wp([0,3,6],\n", " [0,0,0],0.5)\n", "\n", "# Starting Condition\n", "x0 = np.zeros(N)\n", "x0[0] = 0\n", "x0[1] = -0.25\n", "x0[2] = 0.0\n", "x0[3] = np.radians(-0)\n", " \n", "#starting guess\n", "u_bar = np.zeros((M,T))\n", "u_bar[0,:]=0.5\n", "u_bar[1,:]=0.1\n", "\n", " \n", "K=road_curve(x0,track)\n", "\n", "# dynamics starting state w.r.t vehicle frame\n", "x_bar=np.zeros((N,T+1))\n", "x_bar[2]=x0[2]\n", "#prediction for linearization of costrains\n", "for t in range (1,T+1):\n", " xt=x_bar[:,t-1].reshape(N,1)\n", " ut=u_bar[:,t-1].reshape(M,1)\n", " A,B,C=get_linear_model(xt,ut)\n", " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", " x_bar[:,t]= xt_plus_one\n", " \n", "\n", "x = cp.Variable((N, T+1))\n", "u = cp.Variable((M, T))\n", "\n", "#CVXPY Linear MPC problem statement\n", "cost = 0\n", "constr = []\n", "\n", "for t in range(T):\n", " \n", " #cost += 1*cp.sum_squares(x[2,t]-1.0) # move car to \n", " cost += 100*cp.sum_squares(x[3,t]-np.arctan(df(x_bar[0,t],K))) # psi\n", " cost += 1*cp.sum_squares(f(x_bar[0,t],K)-x[1,t]) # cte\n", " # Actuation effort\n", " cost += cp.quad_form( u[:, t],1*np.eye(M))\n", " \n", " # Actuation rate of change\n", " if t < (T - 1):\n", " cost += cp.quad_form(u[:, t + 1] - u[:, t], 1*np.eye(M))\n", " \n", " # KINEMATICS 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 += [x[2, :] <= MAX_SPEED]\n", "# constr += [x[2, :] >= MIN_SPEED]\n", "constr += [cp.abs(u[0, :]) <= MAX_ACC]\n", "constr += [cp.abs(u[1, :]) <= MAX_STEER]\n", "\n", "prob = cp.Problem(cp.Minimize(cost), constr)\n", "solution = prob.solve(solver=cp.OSQP, verbose=True)" ] }, { "cell_type": "code", "execution_count": 11, "metadata": {}, "outputs": [ { "data": { "image/png": "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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", "v_mpc=np.array(x.value[2, :]).flatten()\n", "theta_mpc=np.array(x.value[3, :]).flatten()\n", "a_mpc=np.array(u.value[0, :]).flatten()\n", "w_mpc=np.array(u.value[1, :]).flatten()\n", "\n", "#simulate robot state trajectory for optimized U\n", "x_traj=predict(x0, np.vstack((a_mpc,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(a_mpc)\n", "plt.ylabel('a(t)')\n", "#plt.xlabel('time')\n", "\n", "\n", "plt.subplot(2, 2, 4)\n", "plt.plot(theta_mpc)\n", "plt.ylabel('theta(t)')\n", "\n", "plt.subplot(2, 2, 3)\n", "plt.plot(v_mpc)\n", "plt.ylabel('v(t)')\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "full track demo" ] }, { "cell_type": "code", "execution_count": 29, "metadata": {}, "outputs": [ { "name": "stderr", "output_type": "stream", "text": [ ":29: RuntimeWarning: invalid value encountered in true_divide\n", " v /= np.linalg.norm(v)\n", ":34: RankWarning: Polyfit may be poorly conditioned\n", " K=road_curve(x_sim[:,sim_time],track)\n", ":34: RankWarning: Polyfit may be poorly conditioned\n", " K=road_curve(x_sim[:,sim_time],track)\n", ":34: RankWarning: Polyfit may be poorly conditioned\n", " K=road_curve(x_sim[:,sim_time],track)\n", ":34: RankWarning: Polyfit may be poorly conditioned\n", " K=road_curve(x_sim[:,sim_time],track)\n" ] }, { "name": "stdout", "output_type": "stream", "text": [ "CVXPY Optimization Time: Avrg: 0.2116s Max: 0.2973s Min: 0.1930s\n" ] }, { "name": "stderr", "output_type": "stream", "text": [ ":34: RankWarning: Polyfit may be poorly conditioned\n", " K=road_curve(x_sim[:,sim_time],track)\n" ] } ], "source": [ "track = compute_path_from_wp([0,3,4,6,10,13],\n", " [0,0,2,4,3,3],0.5)\n", "\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],0.5)\n", "\n", "sim_duration = 80 #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.25\n", "MIN_SPEED = 0.75\n", "MAX_STEER = 1.57/2\n", "MAX_ACC = 1.0\n", "\n", "# Starting Condition\n", "x0 = np.zeros(N)\n", "x0[0] = 0\n", "x0[1] = -0.25\n", "x0[2] = 0\n", "x0[3] = 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\n", "u_bar[1,:]=0.01\n", "\n", "for sim_time in range(sim_duration-1):\n", " \n", " iter_start=time.time()\n", " K=road_curve(x_sim[:,sim_time],track)\n", " \n", " # dynamics starting state w.r.t vehicle frame\n", " x_bar=np.zeros((N,T+1))\n", " x_bar[2,0]=x_sim[2,sim_time]\n", " \n", " #prediction for linearization of costrains\n", " for t in range (1,T+1):\n", " xt=x_bar[:,t-1].reshape(N,1)\n", " ut=u_bar[:,t-1].reshape(M,1)\n", " A,B,C=get_linear_model(xt,ut)\n", " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", " x_bar[:,t]= xt_plus_one\n", " \n", " #CVXPY Linear MPC problem statement\n", " cost = 0\n", " constr = []\n", " x = cp.Variable((N, T+1))\n", " u = cp.Variable((M, T))\n", " \n", " #Prediction Horizon\n", " for t in range(T):\n", "\n", " #cost += 30*cp.sum_squares(x[2,t]-np.arctan(df(x_bar[0,t],K))) # psi\n", " cost += 50*cp.sum_squares(x[3,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", " cost += 10*cp.sum_squares(1.-x[2,t]) # desired v\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", " # Kinrmatics Constrains (Linearized model)\n", " A,B,C=get_linear_model(x_bar[:,t],u_bar[:,t])\n", " constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()]\n", "\n", " # sums problem objectives and concatenates constraints.\n", " constr += [x[:,0] == x_bar[:,0]] #<--watch out the start condition\n", " constr += [x[2, :] <= MAX_SPEED]\n", " constr += [x[2, :] >= 0.0]\n", " constr += [cp.abs(u[0, :]) <= MAX_ACC]\n", " constr += [cp.abs(u[1, :]) <= MAX_STEER]\n", " \n", " # Solve\n", " prob = cp.Problem(cp.Minimize(cost), constr)\n", " solution = prob.solve(solver=cp.OSQP, verbose=False)\n", " \n", " #retrieved optimized U and assign to u_bar to linearize in next step\n", " u_bar=np.vstack((np.array(u.value[0, :]).flatten(),\n", " (np.array(u.value[1, :]).flatten())))\n", " \n", " u_sim[:,sim_time] = u_bar[:,0]\n", " \n", " # Measure elpased time to get results from cvxpy\n", " opt_time.append(time.time()-iter_start)\n", " \n", " # move simulation to t+1\n", " tspan = [0,dt]\n", " x_sim[:,sim_time+1] = odeint(kinematics_model,\n", " x_sim[:,sim_time],\n", " tspan,\n", " args=(u_bar[:,0],))[1]\n", " \n", "print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n", " np.max(opt_time),\n", " np.min(opt_time))) " ] }, { "cell_type": "code", "execution_count": 34, "metadata": {}, "outputs": [ { "data": { "image/png": "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\n", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "#plot trajectory\n", "grid = plt.GridSpec(4, 5)\n", "\n", "plt.figure(figsize=(15,10))\n", "\n", "plt.subplot(grid[0:4, 0:4])\n", "plt.plot(track[0,:],track[1,:],\"b+\")\n", "plt.plot(x_sim[0,:],x_sim[1,:])\n", "plt.axis(\"equal\")\n", "plt.ylabel('y')\n", "plt.xlabel('x')\n", "\n", "plt.subplot(grid[0, 4])\n", "plt.plot(u_sim[0,:])\n", "plt.ylabel('a(t) [m/ss]')\n", "\n", "plt.subplot(grid[1, 4])\n", "plt.plot(x_sim[2,:])\n", "plt.ylabel('v(t) [m/s]')\n", "\n", "plt.subplot(grid[2, 4])\n", "plt.plot(np.degrees(u_sim[1,:]))\n", "plt.ylabel('delta(t) [deg/s]')\n", "\n", "plt.subplot(grid[3, 4])\n", "plt.plot(x_sim[3,:])\n", "plt.ylabel('theta(t) [m/s]')\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## OBSTACLE AVOIDANCE\n", "see dccp paper for reference" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "import dccp\n", "track = compute_path_from_wp([0,3,4,6,10,13],\n", " [0,0,2,4,3,3],0.25)\n", "\n", "obstacles=np.array([[4,6],[2,4]])\n", "obstacle_radius=0.5\n", "\n", "def to_vehic_frame(pt,pos_x,pos_y,theta):\n", " dx = pt[0] - pos_x\n", " dy = pt[1] - pos_y\n", "\n", " return [dx * np.cos(-theta) - dy * np.sin(-theta),\n", " dy * np.cos(-theta) + dx * np.sin(-theta)]\n", " \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],0.5)\n", "\n", "sim_duration = 80 #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.25\n", "MIN_SPEED = 0.75\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", " #compute coefficients\n", " K=road_curve(x_sim[:,sim_time],track)\n", " \n", " #compute opstacles in ref frame\n", " o_=[]\n", " for j in range(2):\n", " o_.append(to_vehic_frame(obstacles[:,j],x_sim[0,sim_time],x_sim[1,sim_time],x_sim[2,sim_time]) )\n", " \n", " # dynamics starting state w.r.t vehicle frame\n", " x_bar=np.zeros((N,T+1))\n", " \n", " #prediction for linearization of costrains\n", " for t in range (1,T+1):\n", " xt=x_bar[:,t-1].reshape(N,1)\n", " ut=u_bar[:,t-1].reshape(M,1)\n", " A,B,C=get_linear_model(xt,ut)\n", " xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n", " x_bar[:,t]= xt_plus_one\n", " \n", " #CVXPY Linear MPC problem statement\n", " cost = 0\n", " constr = []\n", " x = cp.Variable((N, T+1))\n", " u = cp.Variable((M, T))\n", " \n", " #Prediction Horizon\n", " for t in range(T):\n", "\n", " #cost += 30*cp.sum_squares(x[2,t]-np.arctan(df(x_bar[0,t],K))) # psi\n", " cost += 50*cp.sum_squares(x[2,t]-np.arctan2(df(x_bar[0,t],K),x_bar[0,t])) # 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], 100*np.eye(M))\n", " \n", " # Actuation effort\n", " cost += cp.quad_form( u[:, t],1*np.eye(M))\n", " \n", " # Kinrmatics Constrains (Linearized model)\n", " A,B,C=get_linear_model(x_bar[:,t],u_bar[:,t])\n", " constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()]\n", " \n", " # Obstacle Avoidance Contrains\n", " for j in range(2):\n", " constr += [ cp.norm(x[0:2,t]-o_[j],2) >= obstacle_radius ]\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(method=\"dccp\", 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": "markdown", "metadata": {}, "source": [ "#plot trajectory\n", "grid = plt.GridSpec(2, 3)\n", "\n", "plt.figure(figsize=(15,10))\n", "\n", "ax=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", "#obstacles\n", "circle1=plt.Circle((obstacles[0,0], obstacles[1,0]), obstacle_radius, color='r')\n", "circle2=plt.Circle((obstacles[0,1], obstacles[1,1]), obstacle_radius, color='r')\n", "plt.axis(\"equal\")\n", "plt.ylabel('y')\n", "plt.xlabel('x')\n", "\n", "ax.add_artist(circle1)\n", "ax.add_artist(circle2)\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", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "code", "execution_count": null, "metadata": {}, "outputs": [], "source": [] } ], "metadata": { "kernelspec": { "display_name": "Python [conda env:jupyter] *", "language": "python", "name": "conda-env-jupyter-py" }, "language_info": { "codemirror_mode": { "name": "ipython", "version": 3 }, "file_extension": ".py", "mimetype": "text/x-python", "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", "version": "3.8.3" } }, "nbformat": 4, "nbformat_minor": 4 }