From 3866ca7ca97d32135e92e7f4abb9341baa969880 Mon Sep 17 00:00:00 2001 From: mcarfagno Date: Fri, 1 May 2020 17:05:24 +0100 Subject: [PATCH] Simplified kinematics equations, param tuning --- notebook/MPC_cte_cvxpy.ipynb | 158 +++++++++++++---------------------- 1 file changed, 58 insertions(+), 100 deletions(-) diff --git a/notebook/MPC_cte_cvxpy.ipynb b/notebook/MPC_cte_cvxpy.ipynb index 1473304..4b11d23 100644 --- a/notebook/MPC_cte_cvxpy.ipynb +++ b/notebook/MPC_cte_cvxpy.ipynb @@ -2,7 +2,7 @@ "cells": [ { "cell_type": "code", - "execution_count": 1, + "execution_count": 73, "metadata": {}, "outputs": [], "source": [ @@ -199,13 +199,13 @@ }, { "cell_type": "code", - "execution_count": 2, + "execution_count": 74, "metadata": {}, "outputs": [], "source": [ "# Control problem statement.\n", "\n", - "N = 5 #number of state variables\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" @@ -213,7 +213,7 @@ }, { "cell_type": "code", - "execution_count": 3, + "execution_count": 75, "metadata": {}, "outputs": [], "source": [ @@ -224,8 +224,6 @@ " 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", @@ -233,18 +231,15 @@ " 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", + " 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" @@ -259,7 +254,7 @@ }, { "cell_type": "code", - "execution_count": 4, + "execution_count": 76, "metadata": {}, "outputs": [], "source": [ @@ -271,14 +266,10 @@ " 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", + " dthetadt]\n", "\n", " return dqdt\n", "\n", @@ -314,15 +305,15 @@ }, { "cell_type": "code", - "execution_count": 5, + "execution_count": 77, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "CPU times: user 3.97 ms, sys: 0 ns, total: 3.97 ms\n", - "Wall time: 3.46 ms\n" + "CPU times: user 5.97 ms, sys: 113 µs, total: 6.08 ms\n", + "Wall time: 4.96 ms\n" ] } ], @@ -337,8 +328,6 @@ "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)" ] @@ -352,14 +341,14 @@ }, { "cell_type": "code", - "execution_count": 6, + "execution_count": 78, "metadata": {}, "outputs": [ { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ - "
" + "
" ] }, "metadata": {}, @@ -380,14 +369,6 @@ "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()" @@ -411,15 +392,15 @@ }, { "cell_type": "code", - "execution_count": 7, + "execution_count": 79, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "CPU times: user 1.78 ms, sys: 679 µs, total: 2.46 ms\n", - "Wall time: 1.63 ms\n" + "CPU times: user 2.2 ms, sys: 132 µs, total: 2.33 ms\n", + "Wall time: 1.53 ms\n" ] } ], @@ -434,15 +415,13 @@ "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", + " 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", @@ -453,14 +432,14 @@ }, { "cell_type": "code", - "execution_count": 8, + "execution_count": 80, "metadata": {}, "outputs": [ { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ - "
" + "
" ] }, "metadata": {}, @@ -481,14 +460,6 @@ "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()" @@ -521,7 +492,7 @@ }, { "cell_type": "code", - "execution_count": 9, + "execution_count": 81, "metadata": {}, "outputs": [], "source": [ @@ -686,14 +657,14 @@ }, { "cell_type": "code", - "execution_count": 10, + "execution_count": 82, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "[ 0. 0. 0. -0.17453294 -1.015427 ]\n" + "[0. 0. 0.]\n" ] } ], @@ -726,30 +697,24 @@ "x_bar[0,0]=0\n", "x_bar[1,0]=0\n", "x_bar[2,0]=0\n", - "# x_bar[3,0]=x_bar[2,0]-np.arctan2(df(x_bar[0,0],K),x_bar[0,0])\n", - "x_bar[3,0]=x_bar[2,0]-np.arctan(df(x_bar[0,0],K))\n", - "x_bar[4,0]=f(x_bar[0,0],K)-x_bar[1,0]\n", + "\n", "\n", "print(x_bar[:,0])\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", + " 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", - "# xt_plus_one[3]=xt_plus_one[2]-np.arctan2(df(xt_plus_one[0],K),xt_plus_one[0])\n", - " xt_plus_one[3]=xt_plus_one[2]-np.arctan(df(xt_plus_one[0],K))\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" ] }, { "cell_type": "code", - "execution_count": 11, + "execution_count": 83, "metadata": {}, "outputs": [ { @@ -761,8 +726,8 @@ " (c) Bartolomeo Stellato, Goran Banjac\n", " University of Oxford - Stanford University 2019\n", "-----------------------------------------------------------------\n", - "problem: variables n = 283, constraints m = 323\n", - " nnz(P) + nnz(A) = 857\n", + "problem: variables n = 241, constraints m = 281\n", + " nnz(P) + nnz(A) = 715\n", "settings: linear system solver = qdldl,\n", " eps_abs = 1.0e-05, eps_rel = 1.0e-05,\n", " eps_prim_inf = 1.0e-04, eps_dual_inf = 1.0e-04,\n", @@ -773,18 +738,18 @@ " warm start: on, polish: on, time_limit: off\n", "\n", "iter objective pri res dua res rho time\n", - " 1 0.0000e+00 1.02e+00 1.21e+02 1.00e-01 3.34e-04s\n", - " 125 1.6631e+03 2.07e-05 3.42e-04 7.12e+01 1.30e-03s\n", + " 1 0.0000e+00 1.02e+00 1.02e+02 1.00e-01 2.26e-04s\n", + " 125 1.6631e+03 2.07e-05 3.42e-04 7.12e+01 1.00e-03s\n", "\n", "status: solved\n", "solution polish: unsuccessful\n", "number of iterations: 125\n", "optimal objective: 1663.1222\n", - "run time: 1.65e-03s\n", + "run time: 1.17e-03s\n", "optimal rho estimate: 7.91e+01\n", "\n", - "CPU times: user 224 ms, sys: 7.49 ms, total: 232 ms\n", - "Wall time: 223 ms\n" + "CPU times: user 234 ms, sys: 8.58 ms, total: 242 ms\n", + "Wall time: 229 ms\n" ] } ], @@ -829,14 +794,14 @@ }, { "cell_type": "code", - "execution_count": 12, + "execution_count": 84, "metadata": {}, "outputs": [ { "data": { - "image/png": "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\n", + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAagAAACkCAYAAADCB7oPAAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAADh0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uMy4xLjMsIGh0dHA6Ly9tYXRwbG90bGliLm9yZy+AADFEAAAekklEQVR4nO3de1SUdf4H8PfMcJOLwJB4wajAS4oaIYSLEhLq6WSniPW44S3LzTVJc7U2W9NqkXJXEddbqXmM3H6t1k/x5/72V2kcL2luIxcL2ExItxJz5OoQjjLM8/uDZpphZmAEZp7vyPt1js7Mc5s3z3mGD9/vPM/3UUiSJIGIiEgwSrkDEBER2cMCRUREQmKBIiIiIbFAERGRkFigiIhISCxQREQkJC+5AxCRuLZu3Yri4mIEBwcjNze329vLycnBuXPncPfdd2P58uXm6Rs3bkRVVRW8vLwQHR2N+fPnw8vLuV9PWVlZ8PPzg1KphEqlwpo1a1yWk9yLBYqIHJo4cSIefPBBbNmypUe298gjj+D69es4fPiw1fQJEyZg0aJFAIC//vWvKCwsxJQpU6yW2bJlCyZOnIiYmBib7b7yyivo27dvj2TsKCe5FwsUETk0cuRIaLVaq2k//vgjdu7ciatXr8LX1xe/+93vEBER4dT2Ro8ejfLycpvpcXFx5udDhgxBbW1t94K7KCe5FwsUEd2U7du34+mnn8bAgQNx7tw5vP3223jllVd6ZNsGgwHHjx/H3Llzb2q9nJwcAMDkyZMxadIkl+ck92CBIiKn6fV6nD17FuvXrzdPMxgMAIB//etf2Lt3r806arUaK1ascGr7b7/9NkaMGIERI0YAAEpLS/Hee+8BAGpqavD111/Dz88P3t7eeP311wEA2dnZUKvVaGxsxOrVqzFo0CBERUW5NCe5BwsUETnNaDQiICAAa9eutZmXmJiIxMTELm/7gw8+wNWrVzF//nzztNjYWMTGxgJw/B2UWq0GAAQHByMhIQGVlZW48847XZaT3IenmROR0/z9/REeHo7PP/8cACBJEi5cuNDt7X766ac4c+YMlixZAqXS+V9Ler0e165dMz//8ssvERkZ6bKc5F4KjmZORI5s2LABFRUV0Ol0CA4OxvTp0zFq1Cjs2LEDDQ0NMBgMGD9+PKZNm+bU9latWoWLFy9Cr9cjKCgICxYsQGxsLB5//HH069cPfn5+ANpaOe23aa8FdfnyZaxbtw4A0NraigkTJiAjIwMAoNVqezwnuRcLFBERCYldfEREJCQWKCIiEhILFBERCcmjTzOvrq62O/22225DTU2Nm9PYxyz2eUqWQYMGuTmNWDzhM2bCTM4RMZOjzxlbUEREJCQWKCIiEhILFBERCYkFioiIhMQCRUREQhKqQBmNRvzhD3/okTtiEhGRZxOqQP3zn/90+oZiRER0axOmQNXW1qK4uBhpaWlyRyEiIgEIc6HuO++8g1mzZpmHzrfn8OHDOHz4MABgzZo1uO222+wu5+Xl5XCeuzGLfcxCRJ0RokAVFRUhODgYUVFRKC8vd7jcpEmTzLdzBuDwamiRrpRmFvs8JUtvH0mCSE5CFKizZ8/i9OnTKCkpwY0bN3Dt2jVs3LgRixcvljsaERHJRIgCNWPGDMyYMQMAUF5ejoMHD7I4ERH1csKcJEFERGRJiBaUpZiYGKtbOhMRUe/EFhQREQmJBYqIiITEAkVEREJigSIiIiEJd5IEETlWWlqKXbt2wWg0Ii0tDenp6VbzW1pasHnzZnz77bcICgrCkiVLEB4eDgDYv38/CgsLoVQq8eSTTyI2NlaOH4HIaWxBEXkIo9GInTt34o9//CPy8vJw4sQJ/PDDD1bLFBYWIiAgAJs2bcLUqVPx3nvvAQB++OEHnDx5EuvXr8eKFSuwc+dOGI1GOX4MIqexQBF5iMrKSgwYMAD9+/eHl5cXkpKSoNForJY5ffo0Jk6cCAAYN24cysrKIEkSNBoNkpKS4O3tjfDwcAwYMACVlZUy/BREzmOBIvIQdXV1CAsLM78OCwtDXV2dw2VUKhX8/f2h0+ls1lWr1TbrEomG30ERkZkn3jHAhJmcI2ImR1igiDyEWq1GbW2t+XVtbS3UarXdZcLCwtDa2orm5mYEBQXZrFtXV2ezLuCZdwwwYSbniJjJ0V0D2MVH5CGio6Nx6dIlaLVaGAwGnDx5EvHx8VbLjB07FkeOHAEAnDp1CjExMVAoFIiPj8fJkyfR0tICrVaLS5cuYciQITL8FETOYwuKyEOoVCo89dRTyMnJgdFoRGpqKm6//Xbs2bMH0dHRiI+PxwMPPIDNmzdj0aJFCAwMxJIlSwAAt99+O371q19h6dKlUCqVmDdvHpRK/n1KYlNIkiTJHaKrqqur7U4XqQnLLPZ5SpbefsNCT/iMmTCTc0TMxC4+IiLyKCxQREQkJBYoIiISEgsUEREJiQWKiIiExAJFRERCEuI6qJqaGmzZsgUNDQ1QKBSYNGkSHnroIbljUS+Rna3CM8/InYKI2hOiBaVSqTB79mzk5eUhJycHH3/8sc1tBIh6Um5ukPlx9WqVzGmIyB4hClRoaCiioqIAAH369EFERARHWiaXyM0NQm5uENavbytQpkciEo8QXXyWtFotzp8/b3ecME8caZlZ7HNnluzsthbSypWtWL/exzw9ImKQzfOXX27FypWtbslFRB0TqkDp9Xrk5uZi7ty58Pf3t5nviSMtM4t9rs6SmxuEZct0Vq2l5uZmAD4O11m6VIdnntHBMlZvH+qISE5CdPEBgMFgQG5uLpKTk5GYmCh3HPJgjrrwOurOu3ixGsuW6VyejYicJ0SBkiQJb731FiIiIvDwww/LHYc8kOVJD6ZCZNmFZ8/Fi20Dob78Mrv0iEQkRBff2bNncezYMURGRuKFF14AAGRmZiIuLk7mZCQ6U2Fy5qSHpUt15vlLl+rMjytX+kKQnk8isiBEgbr77ruxd+9euWOQhzAVpWXLdE534ZmWb/+87dG350MSUbcJUaCIOmPvpIfOmFpMptYSAJd/z6TX6/HTTz8hICAAfn5+Ln0volsdCxQJzbIL72ZaTEuX6tq1klznu+++w+HDh1FcXIwrV66Yp4eHhyM2NhaTJ09GZGSkSzMQ3YpYoEg4jrrwnDnpISJikFuL04YNG/DDDz8gKSkJixYtQkREBPr06YNr167h4sWLqKiowMaNGzF48GDz7deJyDksUCSUrnThmZ6bHt15unhycjLGjh1rMz0wMBDDhw/H8OHD8dhjj6GoqKhb79PU1IS8vDxcuXIF/fr1w+9//3sEBgZaLXPhwgXs2LED165dg1KpREZGBpKSkgAAW7ZsQUVFhfn6wqysLNx5553dykTkaixQJLueP+nBfSyL07lz5zB06FCbZSorK+0WsZtRUFCA0aNHIz09HQUFBSgoKMCsWbOslvHx8cGzzz6LgQMHoq6uDsuXL8c999yDgIAAAMDs2bMxbty4buUgcichroOi3ic7W2X1/dL69UFOX7e0dKnO3GJatsy9LaaOrF692u70nJycbm9bo9EgJSUFAJCSkgKNRmOzzKBBgzBw4EAAgFqtRnBwMK5evdrt9yaSi9MtqHfeeQcTJ05ktwB1mfWZeCoAQR0WFxG68JxhNBoBtF1wbvpncvnyZahU3R8tvbGxEaGhoQCAkJAQNDY2drh8ZWUlDAYD+vfvb572/vvv48MPP8SoUaMwc+ZMeHt726znieNdmjCTc0TM5IjTBcpoNCInJwd9+/ZFcnIykpOTERYW5spsXWL8371o8veHFHU3EBkNhUIhd6Rer6Mz8TpqNYnQheeMzMxM8/PHH3/cap5SqcRjjz3m1Hays7PR0NBgM739NhUKRYfHdX19PTZt2oSsrCwolW2dJDNmzEBISAgMBgO2bduGAwcOYNq0aTbrOjPepVRZAR/NMVy/pjdNsXqwyyauxYT2P4vi5/9M09s/Su3e6OfXvr6+uK6/1pbDvIxkm0vR7ol5+/amde/3h5+vL/R6/c95LPZT+5/BRvuf0c4ilvup/T+rda1X9vPza8vkLKvtWewrheLn97ec7nh/KZLSoLgj2u48R2NeOl2gnnrqKcydOxclJSU4fvw49u3bh6FDh+L+++9HYmKiMNd8SJUV+KmsuO3FHUOgfHQGFKPj5Q3VC3XlTDzLs/BMRCxI7W3evBmSJOHVV1/Fa6+9Zp6uUCjQt29f+Pg4HqDW0sqVKx3OCw4ORn19PUJDQ1FfX4++ffvaXa65uRlr1qxBZmYmhg0bZp5uan15e3sjNTUVBw8edCqTXY0NuPFVEaRWo53iYucXVEe/jG3mSQ4KjNQ2zbx9hdUDoMANlRKSUbItcJa5HBQ3q0JmOc3ioSuuK5WQJOMveSyL480WP3uFx1T4JACS8ZdHm23/8vq6Ugnp51Z/5yx+eNN+sXq0t98cxB8+GnBQoByuI0mdlnK7vv/+e2zcuBHfffcdfHx8MH78eEyfPh1qtborm+uS6upqu9NDvZSo/fSfkD76b6DmMhCXBGXm01CEuL/F19tHELfsprPHcv7Fi9XmbbhTR/tFlNHMd+/ejaCgIPNJEk1NTTYnSRgMBrz++usYO3Yspk6dajXPVNwkSUJ+fj68vb0xc+bMTt/X0WdMpOPahJmcI2ImR5+zmypQzc3NOHXqFI4fP47//Oc/SExMREpKCm677Tb84x//QFlZGdatW9djoTvT2YdHMhggHToA6eD7gEoFxSMzoLj/QSh83Te0jUgHgyuzmIqSqRXkLFNRAuRrLXWnQOXn5+PRRx9FSEiIw2UaGhpw4MABPPHEE13OqNPpkJeXh5qaGqvTzKuqqnDo0CEsWLAAx44dw5tvvonBgweb1zOdTv7aa6+ZT5i44447MH/+fKd6PViguoeZnNPtApWbm4szZ85gxIgRSElJQUJCgtWXrEajEXPnzsW7777bM4md4OyHR9JWw/hf24DyEiAoGIrEFChGjQUiIoFgtVV/vmRoAfTX2v5d1wM3rgMtN4DW1l+a0MDPfbDKn5vtPz8qlW3/FEpAqQD8A9FvxChhDoaePjC7MvyQqYC9/HIrmpubhejC606BOnToEPbt24fBgwdjxIgRGDRokPlC3UuXLqGiogLV1dXIyMhAWlqaK+K7FAtU9zCTc7r9HdTQoUMxb948h38pKpVK7Nixo2vpXEwRPgiqJa9B+qYcxk/2Qzryf5AO/0/bTJUK8P75OwJDC2Aw9Nwbj0kAXvtrz21PED03grj8xam7Jk+ejNTUVJw+fRolJSXQaDRobm5GQEAAIiMjMXnyZIwdO7ZHzuQj6m2cLlCPPPJIp8v4urHrrCsUw2KgGhYD6boeqPo3pMvVQH1tWwsJALy8AV8/wK8P0CegrSvQx7etgKlUba0jWHzZampRGVvbXhuNFo9GIChYrh+1x3EEcce8vLwwbtw4/Pvf/8a8efMwZMgQuSMR3RJ65UgSCl8/YOS9UIy8V+4oQvOUEcRFoVAosHbtWvj6+mLChAmYMGGCMCdZEHmiXlmgqGOeMIK4iObOnYs5c+agrKwMn332GVasWIHw8HAkJyfzTtFEXcACRQA8awRxkSmVSowZMwZjxoxBXV0dtm7dit27d7NAEXUBC1QvZ+rG86QRxEWm1+vxxRdf4MSJE6ioqMDIkSORlZUldywij8QC1Uu178Yz8YQRxEW1fv16lJSUICoqCuPHj0dWVpbDER+IqHPCFKjS0lLs2rULRqMRaWlpSE9P7/K2srNVaG7+5Qt+AA6fdzSvJ5Z74w3I8r72nms0XkhIuLnx8Dx1+CE5REdHY86cOR4zECeR6Lo81FFPMhqNeO655/Dyyy8jLCwML730Ep577jmrK+LtcXQRoekXruWoBo6eu3q569dvwNfXx+3v29FyHQ0/ZLmsqevOFcMPiXSxoCcMdSQXXqjbPczknG5fqOtKlZWVGDBggPnWAElJSdBoNJ0WKOqazrrxLO+1ZPlIROROQrSgTp06hdLSUixYsAAAcOzYMZw7dw7z5s2zWq79vWpu3LhhnpedrcLq1bxavyuuX7+B7Oy2fbdyZatb3tPLywuGnhy1oxs6yuLsSOS3KraguoeZnCN0C8pZHd2r5pln2v4B7OK7meWWLtWhpkZn3nfuOm5F+pCwi49ITEIUKLVajdraWvPr2tpat962ozdq341HRCQaIQpUdHQ0Ll26BK1WC7VajZMnT2Lx4sVd3p5ppGwAVmefOXru2uV8ZXpf2+caTQASEn4CwMJEROIT4jsoACguLkZ+fj6MRiNSU1ORkZHR6Tqe0D/OLPZ5Spbe3sXnCZ8xE2ZyjoiZhP8OKi4uDnFxcXLHICIiQSjlDkBERGSPMC0oInKsqakJeXl5uHLlitUt39v7zW9+g8jISABtXTkvvvgiAECr1WLDhg3Q6XSIiorCokWL4OXFjz+JjUcokQcoKCjA6NGjkZ6ejoKCAhQUFGDWrFk2y/n4+GDt2rU20//2t79h6tSpGD9+PLZv347CwkJMmTLFHdGJuoxdfEQeQKPRICUlBQCQkpICjUbj9LqSJKG8vBzjxo0DAEycOPGm1ieSC1tQRB6gsbERoaGhAICQkBA0NjbaXa6lpQXLly+HSqXCo48+ivvuuw86nQ7+/v5QqdpGC1Gr1airq7O7fvvRWhwNfOvl5SXcoLjM5BwRMznCAkUkiOzsbDQ0NNhMf/zxx61eKxQKKBQKu9vYunUr1Go1Ll++jD/96U+IjIyEv7+/0xk6Gq3FkoinKjOTc0TMJPxp5kS93cqVKx3OCw4ORn19PUJDQ1FfX+/wPlOmEVj69++PkSNH4sKFC0hMTERzczNaW1uhUqlQV1fHkVrII/A7KCIPEB8fj6NHjwIAjh49ioSEBJtlmpqa0NLSAgC4evUqzp49i8GDB0OhUCAmJganTp0CABw5cgTx8fHuC0/URWxBEXmA9PR05OXlobCw0HyaOQBUVVXh0KFDWLBgAS5evIjt27dDqVTCaDQiPT3dfMuamTNnYsOGDfj73/+Ou+66Cw888ICcPw6RU4QZ6qgrPGEYFmaxz1OycKgj8T9jJszkHBEzOfqcsYuPiIiExAJFRERCYoEiIiIhsUAREZGQWKCIiEhILFBERCQkFigiIhISCxQREQmJBYqIiIQk+1BHu3fvRlFREby8vNC/f38sXLgQAQEBcsciIiKZyd6CGjNmDHJzc7Fu3ToMHDgQ+/fvlzsSEREJQPYCdc8995hvpDZs2DCHN1IjIqLeRfYuPkuFhYVISkpyON8T7/bJLPYxCxF1xi0FqqM7hZrua7Nv3z6oVCokJyc73I4n3u2TWezzlCy9fTRzIjm5pUB1dKdQoO0GakVFRVi1apXDW1kTEVHvIvt3UKWlpThw4ABefPFF+Pr6yh2HiIgEIft3UDt37oTBYEB2djYAYOjQoZg/f77MqYiISG6yF6hNmzbJHYFIeE1NTcjLy8OVK1fMt3wPDAy0WqasrAz5+fnm19XV1Xjuuedw3333YcuWLaioqIC/vz8AICsrC3feeac7fwSimyZ7gSKizhUUFGD06NFIT09HQUEBCgoKMGvWLKtlRo0ahbVr1wJoK2iLFi3CPffcY54/e/ZsjBs3zq25ibpD9u+giKhzGo0GKSkpAICUlBRoNJoOlz916hTuvfdefq9LHo0tKCIP0NjYiNDQUABASEgIGhsbO1z+xIkTePjhh62mvf/++/jwww8xatQozJw5E97e3jbreeK1hibM5BwRMznCAkUkiI6uF7SkUCg6vByjvr4e3333nVX33owZMxASEgKDwYBt27bhwIEDmDZtms26nnitoQkzOUfETI6uN2SBIhJER9cLBgcHo76+HqGhoaivr0ffvn0dLvv555/jvvvug5fXLx9vU+vL29sbqampOHjwYM8FJ3IRhSRJktwhiKhju3fvRlBQkPkkiaamJpuTJExWrFiBzMxMjBo1yjzNVNwkSUJ+fj68vb0xc+ZMd8Un6pJb8iSJ5cuXyx3BjFnsY5abk56eji+//BKLFy/GV199hfT0dABAVVUV3nrrLfNyWq0WNTU1GDlypNX6GzduxLJly/D888/j6tWr+PWvf92tPCLuM2ZyjoiZHGEXH5EHCAoKwqpVq2ymR0dHIzo62vw6PDwc27Zts1nulVdecWk+Ile4JVtQRETk+VSvvvrqq3KHcIWoqCi5I5gxi33M4tlE3GfM5BwRM9nDkySIiEhI7OIjIiIhefRJEqWlpdi1axeMRiPS0tLMZzaZtLS0YPPmzfj2228RFBSEJUuWIDw8vMdz1NTUYMuWLWhoaIBCocCkSZPw0EMPWS1TXl6Ov/zlL+b3T0xMtHuhZE/IysqCn58flEolVCoV1qxZYzVfkiTs2rULJSUl8PX1xcKFC13S5K+urkZeXp75tVarxfTp0zF16lTzNFful61bt6K4uBjBwcHIzc0F4Nygq0DbPcr27dsHAMjIyMDEiRN7JNOtoLPPnRw6O+bdoTvHmzsz7d27F59++qn5WrrMzEzExcW5LdNNkTxUa2ur9Oyzz0o//vij1NLSIj3//PPS999/b7XMRx99JG3btk2SJEn67LPPpPXr17skS11dnVRVVSVJkiQ1NzdLixcvtslSVlYmvfHGGy55//YWLlwoNTY2OpxfVFQk5eTkSEajUTp79qz00ksvuTxTa2ur9Nvf/lbSarVW0125X8rLy6Wqqipp6dKl5mm7d++W9u/fL0mSJO3fv1/avXu3zXo6nU7KysqSdDqd1XNy7nMnh86OeXfo6vHm7kx79uyRDhw44NYcXeWxXXyVlZUYMGAA+vfvDy8vLyQlJdkMoHn69GnzX77jxo1DWVkZJBd85RYaGmpugfTp0wcRERGoq6vr8ffpKadPn8b9998PhUKBYcOG4aeffkJ9fb1L3/Orr77CgAED0K9fP5e+j6WRI0fa/LXqzKCrpaWlGDNmDAIDAxEYGIgxY8agtLTULZlF58znrrfq6vHm7kyexGO7+Orq6hAWFmZ+HRYWhnPnzjlcRqVSwd/fHzqdrsNhYrpLq9Xi/PnzGDJkiM28b775Bi+88AJCQ0Mxe/Zs3H777S7LkZOTAwCYPHmy1dhqQNt+sRwsMiwsDHV1debhcFzhxIkTGD9+vN157twvzgy62v7YUqvVQv/B4U7OfO7k0tExL5ebHeTXXT7++GMcO3YMUVFRmDNnjrBFzGMLlIj0ej1yc3Mxd+5c843hTO666y5s3boVfn5+KC4uxtq1a7Fx40aX5MjOzoZarUZjYyNWr16NQYMG2Yws4E4GgwFFRUWYMWOGzTx37pf2Oht0lTyHaMe8PaIcb1OmTDF/z7tnzx68++67WLhwocyp7PPYLj61Wo3a2lrz69raWqjVaofLtLa2orm5GUFBQS7JYzAYkJubi+TkZCQmJtrM9/f3h5+fHwAgLi4Ora2tuHr1qkuymPZDcHAwEhISUFlZaTPfcjRje/uuJ5WUlOCuu+5CSEiIzTx37hfgl0FXATgcdLX9sVVXV+fS/eNJnPncyaGzY14uzhxv7hYSEgKlUgmlUom0tDRUVVXJHckhjy1Q0dHRuHTpErRaLQwGA06ePIn4+HirZcaOHYsjR44AaLuBW0xMjEv+gpEkCW+99RYiIiJs7sFj0tDQYP7+q7KyEkaj0SXFUq/X49q1a+bnX375JSIjI62WiY+Px7FjxyBJEr755hv4+/vL1r3nrv1iEh8fj6NHjwIAjh49ioSEBJtlYmNjcebMGTQ1NaGpqQlnzpxBbGysyzJ5Emc+d+7mzDEvF2eON3ez/L75iy++cGmXend59IW6xcXFyM/Ph9FoRGpqKjIyMrBnzx5ER0cjPj4eN27cwObNm3H+/HkEBgZiyZIl6N+/f4/n+Prrr7Fq1SpERkaaC2BmZqa5lTJlyhR89NFH+OSTT6BSqeDj44M5c+Zg+PDhPZ7l8uXLWLduHYC2VuOECROQkZGBTz75xJxFkiTs3LkTZ86cgY+PDxYuXGg1nltP0uv1WLhwITZv3mzu9rTM4sr9smHDBlRUVECn0yE4OBjTp09HQkIC8vLyUFNTY3Xab1VVFQ4dOoQFCxYAAAoLC7F//34AbaeZp6am9kimW4G9z52cHB3z7nYzx5ucmcrLy3HhwgUoFAr069cP8+fPd+kfqN3h0QWKiIhuXR7bxUdERLc2FigiIhISCxQREQmJBYqIiITEAkVEREJigSIiIiGxQBERkZBYoIiISEgsULe4H3/8EU8++SS+/fZbAG3jys2bNw/l5eUyJyMi6hgL1C1uwIABmDlzJjZt2oTr16/jzTffREpKCmJiYuSORkTUIQ511Ev8+c9/hlarhUKhwBtvvAFvb2+5IxERdYgtqF4iLS0N33//PR588EEWJyLyCCxQvYBer0d+fj4eeOABfPDBB2hqapI7EhFRp1igeoFdu3YhKioKCxYsQFxcHLZv3y53JCKiTrFA3eI0Gg1KS0vx9NNPAwCeeOIJnD9/HsePH5c5GRFRx3iSBBERCYktKCIiEhILFBERCYkFioiIhMQCRUREQmKBIiIiIbFAERGRkFigiIhISCxQREQkJBYoIiIS0v8DYNDERrx2HakAAAAASUVORK5CYII=\n", "text/plain": [ - "
" + "
" ] }, "metadata": {}, @@ -847,8 +812,6 @@ "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", @@ -876,13 +839,13 @@ "# 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", + "# 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", + "# plt.subplot(2, 2, 4)\n", + "# plt.plot(cte_mpc)\n", + "# plt.ylabel('cte(t)')\n", "\n", "plt.tight_layout()\n", "plt.show()" @@ -897,7 +860,7 @@ }, { "cell_type": "code", - "execution_count": 25, + "execution_count": 99, "metadata": {}, "outputs": [ { @@ -911,23 +874,23 @@ "name": "stdout", "output_type": "stream", "text": [ - "CVXPY Optimization Time: Avrg: 0.1798s Max: 0.2277s Min: 0.1655s\n" + "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,4])\n", + " [0,0,2,4,3])\n", "\n", - "sim_duration = 50 #time steps\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.25\n", - "MIN_SPEED = 0.75\n", - "MAX_STEER_SPEED = 1.57/2\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", @@ -949,20 +912,15 @@ " \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", + " 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", - " 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", @@ -978,14 +936,14 @@ " #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 += 50*cp.sum_squares(f(x_bar[0,t],K)-x[1,t]) # cte\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], 10*np.eye(M))\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],10*np.eye(M))\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", @@ -1024,12 +982,12 @@ }, { "cell_type": "code", - "execution_count": 26, + "execution_count": 100, "metadata": {}, "outputs": [ { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ "
" ]