From a9acb2723879a259794268a609f55380eb4a0c77 Mon Sep 17 00:00:00 2001 From: mcarfagno Date: Fri, 1 May 2020 16:40:00 +0100 Subject: [PATCH] Improving road-curve MPC --- notebook/MPC_cte_cvxpy.ipynb | 85 +++-- notebook/MPC_scipy_v2.ipynb | 616 ------------------------------ notebook/MPC_tracking_cvxpy.ipynb | 48 +-- notebook/equations.ipynb | 75 ++-- 4 files changed, 123 insertions(+), 701 deletions(-) delete mode 100644 notebook/MPC_scipy_v2.ipynb diff --git a/notebook/MPC_cte_cvxpy.ipynb b/notebook/MPC_cte_cvxpy.ipynb index 7d2b8ef..1473304 100644 --- a/notebook/MPC_cte_cvxpy.ipynb +++ b/notebook/MPC_cte_cvxpy.ipynb @@ -2,7 +2,7 @@ "cells": [ { "cell_type": "code", - "execution_count": 69, + "execution_count": 1, "metadata": {}, "outputs": [], "source": [ @@ -199,7 +199,7 @@ }, { "cell_type": "code", - "execution_count": 70, + "execution_count": 2, "metadata": {}, "outputs": [], "source": [ @@ -213,7 +213,7 @@ }, { "cell_type": "code", - "execution_count": 71, + "execution_count": 3, "metadata": {}, "outputs": [], "source": [ @@ -259,7 +259,7 @@ }, { "cell_type": "code", - "execution_count": 72, + "execution_count": 4, "metadata": {}, "outputs": [], "source": [ @@ -314,15 +314,15 @@ }, { "cell_type": "code", - "execution_count": 73, + "execution_count": 5, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "CPU times: user 7 ms, sys: 0 ns, total: 7 ms\n", - "Wall time: 5.8 ms\n" + "CPU times: user 3.97 ms, sys: 0 ns, total: 3.97 ms\n", + "Wall time: 3.46 ms\n" ] } ], @@ -352,7 +352,7 @@ }, { "cell_type": "code", - "execution_count": 74, + "execution_count": 6, "metadata": {}, "outputs": [ { @@ -411,15 +411,15 @@ }, { "cell_type": "code", - "execution_count": 75, + "execution_count": 7, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "CPU times: user 3.28 ms, sys: 461 µs, total: 3.74 ms\n", - "Wall time: 2.68 ms\n" + "CPU times: user 1.78 ms, sys: 679 µs, total: 2.46 ms\n", + "Wall time: 1.63 ms\n" ] } ], @@ -453,7 +453,7 @@ }, { "cell_type": "code", - "execution_count": 76, + "execution_count": 8, "metadata": {}, "outputs": [ { @@ -521,7 +521,7 @@ }, { "cell_type": "code", - "execution_count": 77, + "execution_count": 9, "metadata": {}, "outputs": [], "source": [ @@ -686,7 +686,7 @@ }, { "cell_type": "code", - "execution_count": 106, + "execution_count": 10, "metadata": {}, "outputs": [ { @@ -749,7 +749,7 @@ }, { "cell_type": "code", - "execution_count": 107, + "execution_count": 11, "metadata": {}, "outputs": [ { @@ -773,18 +773,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.61e-04s\n", - " 125 1.4749e+03 9.83e-06 4.40e-03 7.08e+01 1.50e-03s\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", "\n", "status: solved\n", "solution polish: unsuccessful\n", "number of iterations: 125\n", - "optimal objective: 1474.8916\n", - "run time: 1.98e-03s\n", - "optimal rho estimate: 1.51e+01\n", + "optimal objective: 1663.1222\n", + "run time: 1.65e-03s\n", + "optimal rho estimate: 7.91e+01\n", "\n", - "CPU times: user 230 ms, sys: 4.14 ms, total: 234 ms\n", - "Wall time: 230 ms\n" + "CPU times: user 224 ms, sys: 7.49 ms, total: 232 ms\n", + "Wall time: 223 ms\n" ] } ], @@ -801,9 +801,11 @@ "for t in range(T):\n", " \n", " # Cost function\n", - " cost += 10*cp.sum_squares( x[3, t]) # psi\n", - " cost += 500*cp.sum_squares( x[4, t]) # cte\n", - " \n", + " #cost += 10*cp.sum_squares( x[3, t]) # psi\n", + " #cost += 500*cp.sum_squares( x[4, t]) # cte\n", + " \n", + " cost += 10*cp.sum_squares(x[2,t]-np.arctan(df(x_bar[0,t],K))) # psi\n", + " cost += 500*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", @@ -827,12 +829,12 @@ }, { "cell_type": "code", - "execution_count": 108, + "execution_count": 12, "metadata": {}, "outputs": [ { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ "
" ] @@ -895,22 +897,29 @@ }, { "cell_type": "code", - "execution_count": 97, + "execution_count": 25, "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.1852s Max: 0.2253s Min: 0.1567s\n" + "CVXPY Optimization Time: Avrg: 0.1798s Max: 0.2277s Min: 0.1655s\n" ] } ], "source": [ - "track = compute_path_from_wp([0,3,4,6],\n", - " [0,0,2,1])\n", + "track = compute_path_from_wp([0,3,4,6,10],\n", + " [0,0,2,4,4])\n", "\n", - "sim_duration = 20\n", + "sim_duration = 50 #time steps\n", "opt_time=[]\n", "\n", "x_sim = np.zeros((N,sim_duration))\n", @@ -966,15 +975,17 @@ " 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[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", "\n", " # Actuation rate of change\n", " if t < (T - 1):\n", " cost += cp.quad_form(u[:, t + 1] - u[:, t], 10*np.eye(M))\n", " \n", " # Actuation effort\n", - " cost += cp.quad_form( u[:, t],1*np.eye(M))\n", + " cost += cp.quad_form( u[:, t],10*np.eye(M))\n", " \n", " # Constrains\n", " A,B,C=get_linear_model(x_bar[:,t],u_bar[:,t])\n", @@ -1013,12 +1024,12 @@ }, { "cell_type": "code", - "execution_count": 98, + "execution_count": 26, "metadata": {}, "outputs": [ { "data": { - "image/png": "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\n", + "image/png": "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\n", "text/plain": [ "
" ] diff --git a/notebook/MPC_scipy_v2.ipynb b/notebook/MPC_scipy_v2.ipynb deleted file mode 100644 index a74a033..0000000 --- a/notebook/MPC_scipy_v2.ipynb +++ /dev/null @@ -1,616 +0,0 @@ -{ - "cells": [ - { - "cell_type": "code", - "execution_count": 4, - "metadata": {}, - "outputs": [], - "source": [ - "import numpy as np\n", - "import matplotlib.pyplot as plt\n", - "plt.style.use(\"ggplot\")\n", - "import time\n", - "from scipy.interpolate import interp1d\n", - "from scipy.integrate import odeint\n", - "from scipy.optimize import minimize" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "differential drive kinematics model equations" - ] - }, - { - "cell_type": "code", - "execution_count": 5, - "metadata": {}, - "outputs": [], - "source": [ - "#Preliminaries\n", - "def compute_path_from_wp(start_xp, start_yp, step = 0.1):\n", - " final_xp=[]\n", - " final_yp=[]\n", - " delta = step #[m]\n", - "\n", - " for idx in range(len(start_xp)-1):\n", - " section_len = np.sum(np.sqrt(np.power(np.diff(start_xp[idx:idx+2]),2)+np.power(np.diff(start_yp[idx:idx+2]),2)))\n", - "\n", - " interp_range = np.linspace(0,1,np.floor(section_len/delta).astype(int))\n", - " \n", - " fx=interp1d(np.linspace(0,1,2),start_xp[idx:idx+2],kind=1)\n", - " fy=interp1d(np.linspace(0,1,2),start_yp[idx:idx+2],kind=1)\n", - " \n", - " final_xp=np.append(final_xp,fx(interp_range))\n", - " final_yp=np.append(final_yp,fy(interp_range))\n", - "\n", - " return np.vstack((final_xp,final_yp))\n", - "\n", - "def get_nn_idx(state,path):\n", - "\n", - " dx = state[0]-path[0,:]\n", - " dy = state[1]-path[1,:]\n", - " dist = np.sqrt(dx**2 + dy**2)\n", - " nn_idx = np.argmin(dist)\n", - "\n", - " try:\n", - " v = [path[0,nn_idx+1] - path[0,nn_idx],\n", - " path[1,nn_idx+1] - path[1,nn_idx]] \n", - " v /= np.linalg.norm(v)\n", - "\n", - " d = [path[0,nn_idx] - state[0],\n", - " path[1,nn_idx] - state[1]]\n", - "\n", - " if np.dot(d,v) > 0:\n", - " target_idx = nn_idx\n", - " else:\n", - " target_idx = nn_idx+1\n", - "\n", - " except IndexError as e:\n", - " target_idx = nn_idx\n", - "\n", - " return target_idx\n", - "\n", - "def road_curve(state,track):\n", - " \n", - " #given vehicle pos find lookahead waypoints\n", - " nn_idx=get_nn_idx(state,track)\n", - " LOOKAHED=6\n", - " lk_wp=track[:,nn_idx:nn_idx+LOOKAHED]\n", - "\n", - " #trasform lookahead waypoints to vehicle ref frame\n", - " dx = lk_wp[0,:] - state[0]\n", - " dy = lk_wp[1,:] - state[1]\n", - "\n", - " wp_vehicle_frame = np.vstack(( dx * np.cos(-state[2]) - dy * np.sin(-state[2]),\n", - " dy * np.cos(-state[2]) + dx * np.sin(-state[2]) ))\n", - "\n", - " #fit poly\n", - " return np.polyfit(wp_vehicle_frame[0,:], wp_vehicle_frame[1,:], 3, rcond=None, full=False, w=None, cov=False)\n", - "\n", - "def f(x,coeff):\n", - " return round(coeff[0]*x**3 + coeff[1]*x**2 + coeff[2]*x**1 + coeff[3]*x**0,6)\n", - "\n", - "def df(x,coeff):\n", - " return round(3*coeff[0]*x**2 + 2*coeff[1]*x**1 + coeff[2]*x**0,6)" - ] - }, - { - "cell_type": "code", - "execution_count": 58, - "metadata": {}, - "outputs": [], - "source": [ - "from math import cos\n", - "# Define process model\n", - "def kinematics_model(xt,ut,K,dt=0.1):\n", - "\n", - " #current state\n", - " xp = xt[0]\n", - " yp = xt[1]\n", - " theta = xt[2]\n", - " etheta = xt[4]\n", - "\n", - " vt = ut[0]\n", - " wt = ut[1]\n", - "\n", - " #next state\n", - " xtp = xp + vt*cos(theta)*dt\n", - " ytp = yp + vt*np.sin(theta)*dt\n", - " thetatp = theta + wt*dt\n", - " ctetp = f(xp,K) - yp + vt*np.sin(etheta)*dt\n", - " ethetatp = theta - np.arctan(df(xp,K)) + wt*dt\n", - " \n", - " dqdt = [xtp,ytp,thetatp,ctetp,ethetatp]\n", - " return dqdt" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "simulate" - ] - }, - { - "cell_type": "code", - "execution_count": 63, - "metadata": {}, - "outputs": [], - "source": [ - "# time points\n", - "t = np.arange(0, 40, 0.1)\n", - "\n", - "#fake inputs\n", - "# u = [v(t),\n", - "# w(t)]\n", - "u = np.zeros((2,len(t)))\n", - "u[0,100:]=0.4\n", - "u[1,200:]=0.1\n", - "u[1,300:]=-0.0" - ] - }, - { - "cell_type": "code", - "execution_count": 64, - "metadata": {}, - "outputs": [], - "source": [ - "track = compute_path_from_wp([0,5,10],[0,0,2])\n", - "\n", - "# initial conditions\n", - "q0 = np.array([0,0,0,0,0])\n", - "K = road_curve(q0,track)\n", - "q0[3] = f(q0[0],K)\n", - "q0[4] = - np.arctan(df(q0[0],K))\n", - "\n", - "# store solution\n", - "x = np.empty_like(t)\n", - "y = np.empty_like(t)\n", - "theta = np.empty_like(t)\n", - "cte = np.empty_like(t)\n", - "psi = np.empty_like(t)\n", - "\n", - "# record initial conditions\n", - "x[0] = q0[0]\n", - "y[0] = q0[1]\n", - "theta[0] = q0[2]\n", - "cte[0] = q0[3]\n", - "psi[0] = q0[4]\n", - "\n", - "# solve ODE\n", - "for i in range(1,len(t)):\n", - " # span for next time step\n", - " q_t = kinematics_model(q0,u[:,i-1],K,dt=0.1)\n", - "\n", - " # store solution for plotting\n", - " x[i] = q_t[0]\n", - " y[i] = q_t[1]\n", - " theta[i] = q_t[2]\n", - " cte[i] = q_t[3]\n", - " psi[i] = q_t[4]\n", - " # next initial condition\n", - " q0 = q_t" - ] - }, - { - "cell_type": "code", - "execution_count": 65, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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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,y)\n", - "plt.scatter(track[0,:],track[1,:])\n", - "plt.ylabel('y')\n", - "plt.xlabel('x')\n", - "\n", - "#plot x(t)\n", - "plt.subplot(2, 2, 2)\n", - "plt.plot(t,theta)\n", - "plt.ylabel('theta(t)')\n", - "#plt.xlabel('time')\n", - "\n", - "\n", - "#plot y(t)\n", - "plt.subplot(2, 2, 3)\n", - "plt.plot(t,cte)\n", - "plt.ylabel('cte(t)')\n", - "#plt.xlabel('time')\n", - "\n", - "#plot theta(t)\n", - "plt.subplot(2, 2, 4)\n", - "plt.plot(t,psi)\n", - "plt.ylabel('psi(t)')\n", - "#plt.xlabel('time')\n", - "#plt.legend(loc='best')\n", - "\n", - "plt.tight_layout()\n", - "plt.show()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "mpc" - ] - }, - { - "cell_type": "code", - "execution_count": 75, - "metadata": {}, - "outputs": [], - "source": [ - "# Define Objective function\n", - "def objective(u_hat,*args):\n", - " \"\"\"\n", - " Computes objective function\n", - " \n", - " :param u_hat: array_like, input [v,w\n", - " v,w\n", - " ...]\n", - " \"\"\"\n", - " \n", - " #undo input flattening\n", - " u_hat = u_hat.reshape(2, -1).T\n", - " se = np.zeros(PRED_HZN) #squared_errors\n", - " \n", - " # Prediction\n", - " for k in range(PRED_HZN):\n", - " \n", - " # Initialize state for prediction\n", - " if k==0:\n", - " q_hat0 = args[0]\n", - " K=args[1] #road curve\n", - " \n", - " # Clamp control horizon\n", - " elif k>CTRL_HZN:\n", - " u_hat[k,:] = u_hat[CTRL_HZN,:]\n", - " \n", - " #DEBUG\n", - "# print(\"k : {}\".format(k))\n", - "# print(\"q_hat0 : {}\".format(q_hat0))\n", - "# print(\"ts : {}\".format(ts_hat))\n", - "# print(\"u_hat : {}\".format(u_hat[k,:]))\n", - " \n", - " q_hat = kinematics_model(q_hat0,u_hat[k,:],K,dt=0.1)\n", - " cte=q_hat[3]\n", - " psi=q_hat[4]\n", - " \n", - " q_hat0 = q_hat[:]\n", - "\n", - " if k >0:\n", - " delta_u_hat = np.sum(u_hat[k,:]-u_hat[k-1,:])\n", - " else:\n", - " delta_u_hat = 0\n", - "\n", - " se[k] = 100 * (cte)**2 + 15 *(psi)**2 + 15 * (delta_u_hat)**2\n", - "\n", - " # Sum of Squared Error calculation\n", - " obj = np.sum(se[1:])\n", - " return obj" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "TODO: add heading error" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "test optimization" - ] - }, - { - "cell_type": "code", - "execution_count": 76, - "metadata": {}, - "outputs": [], - "source": [ - "#PARAMS\n", - "v=1.5\n", - "vb=0.5\n", - "wb=0.5\n", - "\n", - "# Define horizons\n", - "PRED_HZN = 20 # Prediction Horizon\n", - "CTRL_HZN = 15 # Control Horizon\n", - "\n", - "delta_t_hat = 0.1 #time step" - ] - }, - { - "cell_type": "code", - "execution_count": 77, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - " fun: 84.46152413856359\n", - " jac: array([-1.65424156, -5.46248531, -4.66883278, -3.61091423, -7.25656319,\n", - " -9.97307396, -7.68648052, -5.46970558, -3.82968616, 0.67185783,\n", - " -1.15515804, -1.96808815, 1.28362656, -2.83778381, -0.42825508,\n", - " -0.31342316, 0. , 0. , 0. , 0. ,\n", - " 38.85329056, 29.67042637, 24.17370987, 19.24147987, 10.30806732,\n", - " 3.07283115, 1.61050224, 0.68769073, -0.09304619, 2.58471298,\n", - " -0.30147457, -1.62229347, 1.39114475, -2.71041679, -0.22286892,\n", - " 1.22416592, 0. , 0. , 0. , 0. ])\n", - " message: 'Iteration limit exceeded'\n", - " nfev: 5103\n", - " nit: 101\n", - " njev: 101\n", - " status: 9\n", - " success: False\n", - " x: array([ 1.64242978, 1.69757121, 1.81361202, 1.90182763, 1.90182763,\n", - " 1.90182763, 1.90182763, 1.90182763, 1.83511965, 1.84792843,\n", - " 1.68088567, 1.43951262, 1.44726228, 1.25067572, 1.25506942,\n", - " 1.37310177, 1.37310177, 1.37310177, 1.37310177, 1.37310177,\n", - " -0.5 , -0.5 , -0.49058099, -0.47680101, -0.47680101,\n", - " -0.47680101, -0.38569852, -0.26192364, -0.07803742, 0.00765328,\n", - " 0.14826226, 0.33421738, 0.29494089, 0.39434771, 0.37513876,\n", - " 0.25069961, 0.25069961, 0.25069961, 0.25069961, 0.25069961])\n", - "time elapsed: 3.1107125282287598\n" - ] - } - ], - "source": [ - "starting_pos=np.array([0,0.25,0.15])\n", - "track = compute_path_from_wp([0,5,10],[0,0,2])\n", - "K = road_curve(starting_pos,track)\n", - "\n", - "# initial conditions\n", - "q0 = np.array([0,0,0,0,0])\n", - "q0[3] = f(q0[0],K)\n", - "q0[4] = - np.arctan(df(q0[0],K))\n", - "\n", - "#starting guess\n", - "u_hat0 = np.zeros((PRED_HZN,2))\n", - "u_hat0[:,0]=v\n", - "u_hat0[:,1]=0.1\n", - "u_hat0=u_hat0.flatten(\"F\")\n", - "\n", - "bnds=((v-2*vb,v+vb),)\n", - "for i in range (PRED_HZN-1):\n", - " bnds=bnds+((v-2*vb,v+vb),)\n", - " \n", - "bnds=bnds+((-wb,wb),)\n", - "for i in range (PRED_HZN-1):\n", - " bnds=bnds+((-wb,wb),)\n", - "\n", - "# print(u_hat0)\n", - "# print(u_hat0.reshape(2, -1).T)\n", - "\n", - "start = time.time()\n", - "\n", - "solution = minimize(objective,u_hat0,args=(q0[:],K,),method='SLSQP',bounds=bnds,options={'maxiter':100})\n", - "\n", - "end = time.time()\n", - "\n", - "print(solution)\n", - "print(\"time elapsed: {}\".format(end-start))" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "check what the optimizer returns" - ] - }, - { - "cell_type": "code", - "execution_count": 78, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "u=solution.x.reshape(2,-1).T\n", - "x=[]\n", - "y=[]\n", - "theta=[]\n", - "x.append(starting_pos[0])\n", - "y.append(starting_pos[1])\n", - "theta.append(starting_pos[2])\n", - "\n", - "for i in range(1,np.shape(u)[0]):\n", - " \n", - " # store solution for plotting\n", - " x.append(x[-1]+u[i,0]*np.cos(theta[-1])*0.1)\n", - " y.append(y[-1]+u[i,0]*np.sin(theta[-1])*0.1)\n", - " theta.append(theta[-1]+u[i,1]*0.1)\n", - " \n", - "plt.plot(x,y)\n", - "plt.plot(track[0,:],track[1,:])\n", - "plt.ylabel('y')\n", - "plt.xlabel('x')\n", - "\n", - "plt.tight_layout()\n", - "plt.show()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "compute MPC on the whole path" - ] - }, - { - "cell_type": "code", - "execution_count": 83, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "SCIPY Optimization Time: Avrg: 0.2300s Max: 3.1533s Min: 0.0260s\n" - ] - } - ], - "source": [ - "curr_pos=np.array([0,0.25,0.15])\n", - "start_wpx=[0,5,7.5,8,10,15]\n", - "start_wpy=[0,0,5,10,10,12]\n", - "track = compute_path_from_wp(start_wpx,start_wpy)\n", - "x=[]\n", - "y=[]\n", - "theta=[]\n", - "x.append(curr_pos[0])\n", - "y.append(curr_pos[1])\n", - "theta.append(curr_pos[2])\n", - "\n", - "opt_time=[]\n", - "\n", - "# Initialize input for prediction horizon\n", - "# u=[v1,v2,...,vp\n", - "# w1,w2,...,wp]\n", - "\n", - "# Initial guess \n", - "# u_hat0=[v1,v2,..vp,w1,w2,...,wp]\n", - "# uhat0 -> u_hat=optimize(obj,u_hat0)\n", - "\n", - "u_hat0 = np.zeros((PRED_HZN,2))\n", - "u_hat0[:,0]=v\n", - "u_hat0[:,1]=0.01\n", - "u_hat0=u_hat0.flatten(\"F\")\n", - "\n", - "# Optimization Bounds\n", - "# bnds=((v1_min,v1_max),...,(vp_min,vp_max),(w1_min,w1_max),...,(wp_min,wp_max))\n", - "\n", - "bnds=((v-2*vb,v+vb),)\n", - "for i in range (1,PRED_HZN):\n", - " bnds=bnds+((v-2*vb,v+vb),)\n", - " \n", - "bnds=bnds+((-wb,wb),)\n", - "for i in range (1,PRED_HZN):\n", - " bnds=bnds+((-wb,wb),)\n", - "\n", - "#while np.sum(np.abs(q[-1,0:2]-path[-1,0:2]))>0.1:\n", - "for i in range(50): \n", - " \n", - " start = time.time()\n", - " K = road_curve(curr_pos,track)\n", - " \n", - " # initial conditions for opt.\n", - " q0 = np.array([0,0,0,0,0])\n", - " q0[3] = f(q0[0],K)\n", - " q0[4] = - np.arctan(df(q0[0],K))\n", - "\n", - " #MPC LOOP\n", - " u_hat = minimize(objective,\n", - " u_hat0,\n", - " args=(q0,K,),\n", - " method='SLSQP',\n", - " bounds=bnds,\n", - " options={'maxiter':100}\n", - " ).x\n", - " \n", - " end = time.time()\n", - " opt_time.append(end-start)\n", - " \n", - " # store solution for plotting\n", - " x.append(x[-1]+u[0,0]*np.cos(theta[-1])*0.1)\n", - " y.append(y[-1]+u[0,0]*np.sin(theta[-1])*0.1)\n", - " theta.append(theta[-1]+u[0,1]*0.1)\n", - " \n", - " next_pos = [x[-1],y[-1],theta[-1]]\n", - " \n", - " # next initial condition\n", - " curr_pos=next_pos\n", - " u_hat0=u_hat\n", - "\n", - "print(\"SCIPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n", - " np.max(opt_time),\n", - " np.min(opt_time))) " - ] - }, - { - "cell_type": "code", - "execution_count": 84, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "plt.figure(figsize=(15,10))\n", - "\n", - "plt.plot(x[:],y[:])\n", - "plt.plot(track[0,:],track[1,:])\n", - "plt.ylabel('y')\n", - "plt.xlabel('x')\n", - "\n", - "plt.tight_layout()\n", - "\n", - "plt.show()" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.6.9" - } - }, - "nbformat": 4, - "nbformat_minor": 4 -} diff --git a/notebook/MPC_tracking_cvxpy.ipynb b/notebook/MPC_tracking_cvxpy.ipynb index 2ba65d1..f656400 100644 --- a/notebook/MPC_tracking_cvxpy.ipynb +++ b/notebook/MPC_tracking_cvxpy.ipynb @@ -9,7 +9,7 @@ }, { "cell_type": "code", - "execution_count": 2, + "execution_count": 1, "metadata": {}, "outputs": [], "source": [ @@ -218,7 +218,7 @@ }, { "cell_type": "code", - "execution_count": 3, + "execution_count": 2, "metadata": {}, "outputs": [], "source": [ @@ -235,7 +235,7 @@ }, { "cell_type": "code", - "execution_count": 4, + "execution_count": 3, "metadata": {}, "outputs": [], "source": [ @@ -281,7 +281,7 @@ }, { "cell_type": "code", - "execution_count": 5, + "execution_count": 4, "metadata": {}, "outputs": [], "source": [ @@ -336,15 +336,15 @@ }, { "cell_type": "code", - "execution_count": 6, + "execution_count": 5, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "CPU times: user 7.87 ms, sys: 0 ns, total: 7.87 ms\n", - "Wall time: 7.41 ms\n" + "CPU times: user 3.96 ms, sys: 0 ns, total: 3.96 ms\n", + "Wall time: 3.32 ms\n" ] } ], @@ -374,7 +374,7 @@ }, { "cell_type": "code", - "execution_count": 7, + "execution_count": 6, "metadata": {}, "outputs": [ { @@ -433,15 +433,15 @@ }, { "cell_type": "code", - "execution_count": 8, + "execution_count": 7, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "CPU times: user 1.8 ms, sys: 650 µs, total: 2.45 ms\n", - "Wall time: 1.79 ms\n" + "CPU times: user 0 ns, sys: 2.57 ms, total: 2.57 ms\n", + "Wall time: 1.64 ms\n" ] } ], @@ -475,7 +475,7 @@ }, { "cell_type": "code", - "execution_count": 9, + "execution_count": 8, "metadata": {}, "outputs": [ { @@ -536,7 +536,7 @@ }, { "cell_type": "code", - "execution_count": 10, + "execution_count": 9, "metadata": {}, "outputs": [], "source": [ @@ -626,7 +626,7 @@ }, { "cell_type": "code", - "execution_count": 11, + "execution_count": 10, "metadata": {}, "outputs": [], "source": [ @@ -664,7 +664,7 @@ }, { "cell_type": "code", - "execution_count": 12, + "execution_count": 11, "metadata": {}, "outputs": [ { @@ -707,7 +707,7 @@ }, { "cell_type": "code", - "execution_count": 13, + "execution_count": 12, "metadata": {}, "outputs": [], "source": [ @@ -745,7 +745,7 @@ }, { "cell_type": "code", - "execution_count": 14, + "execution_count": 13, "metadata": {}, "outputs": [ { @@ -873,15 +873,15 @@ }, { "cell_type": "code", - "execution_count": 28, + "execution_count": 14, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "CPU times: user 219 ms, sys: 3.99 ms, total: 223 ms\n", - "Wall time: 217 ms\n" + "CPU times: user 128 ms, sys: 5.53 ms, total: 133 ms\n", + "Wall time: 138 ms\n" ] } ], @@ -972,7 +972,7 @@ }, { "cell_type": "code", - "execution_count": 29, + "execution_count": 15, "metadata": {}, "outputs": [ { @@ -1043,7 +1043,7 @@ }, { "cell_type": "code", - "execution_count": 23, + "execution_count": 18, "metadata": {}, "outputs": [ { @@ -1057,7 +1057,7 @@ "name": "stdout", "output_type": "stream", "text": [ - "CVXPY Optimization Time: Avrg: 0.1416s Max: 0.2571s Min: 0.1279s\n" + "CVXPY Optimization Time: Avrg: 0.1425s Max: 0.1900s Min: 0.1292s\n" ] } ], @@ -1177,7 +1177,7 @@ }, { "cell_type": "code", - "execution_count": 24, + "execution_count": 19, "metadata": {}, "outputs": [ { diff --git a/notebook/equations.ipynb b/notebook/equations.ipynb index f46b8ed..89a970e 100644 --- a/notebook/equations.ipynb +++ b/notebook/equations.ipynb @@ -9,7 +9,7 @@ }, { "cell_type": "code", - "execution_count": 1, + "execution_count": 9, "metadata": {}, "outputs": [ { @@ -26,7 +26,7 @@ "[0, 0, 0, v*cos(psi), 0]])" ] }, - "execution_count": 1, + "execution_count": 9, "metadata": {}, "output_type": "execute_result" } @@ -50,7 +50,7 @@ }, { "cell_type": "code", - "execution_count": 121, + "execution_count": 10, "metadata": {}, "outputs": [ { @@ -67,7 +67,7 @@ "[ sin(psi), 0]])" ] }, - "execution_count": 121, + "execution_count": 10, "metadata": {}, "output_type": "execute_result" } @@ -95,7 +95,7 @@ }, { "cell_type": "code", - "execution_count": 98, + "execution_count": 11, "metadata": {}, "outputs": [], "source": [ @@ -148,9 +148,18 @@ }, { "cell_type": "code", - "execution_count": 110, + "execution_count": 12, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "/home/marcello/.local/lib/python3.6/site-packages/IPython/core/interactiveshell.py:3331: RankWarning: Polyfit may be poorly conditioned\n", + " exec(code_obj, self.user_global_ns, self.user_ns)\n" + ] + } + ], "source": [ "#define track\n", "wp=np.array([0,5,6,10,11,15, 0,0,2,2,0,4]).reshape(2,-1)\n", @@ -160,7 +169,7 @@ "state=[3.5,0.5,np.radians(30)]\n", "\n", "#given vehicle pos find lookahead waypoints\n", - "nn_idx=get_nn_idx(state,track) #index ox closest wp\n", + "nn_idx=get_nn_idx(state,track)-1 #index ox closest wp, take the previous to have a straighter line\n", "LOOKAHED=6\n", "lk_wp=track[:,nn_idx:nn_idx+LOOKAHED]\n", "\n", @@ -172,24 +181,27 @@ " dy * np.cos(-state[2]) + dx * np.sin(-state[2]) ))\n", "\n", "#fit poly\n", - "coeff=np.polyfit(wp_vehicle_frame[0,:], wp_vehicle_frame[1,:], 3, rcond=None, full=False, w=None, cov=False)\n", + "coeff=np.polyfit(wp_vehicle_frame[0,:], wp_vehicle_frame[1,:], 5, rcond=None, full=False, w=None, cov=False)\n", "\n", + "#def f(x,coeff):\n", + "# return coeff[0]*x**3+coeff[1]*x**2+coeff[2]*x**1+coeff[3]*x**0\n", "def f(x,coeff):\n", - " return coeff[0]*x**3+coeff[1]*x**2+coeff[2]*x**1+coeff[3]*x**0" + " return coeff[0]*x**5+coeff[1]*x**4+coeff[2]*x**3+coeff[3]*x**2+coeff[4]*x**1+coeff[5]*x**0" ] }, { "cell_type": "code", - "execution_count": 111, + "execution_count": 13, "metadata": {}, "outputs": [ { "data": { "text/plain": [ - "array([-0.12829547, 0.96144073, -1.47313104, -0.47433648])" + "array([ 0.10275887, 0.03660033, -0.21750601, 0.03551043, -0.53861442,\n", + " -0.58083993])" ] }, - "execution_count": 111, + "execution_count": 13, "metadata": {}, "output_type": "execute_result" } @@ -200,12 +212,25 @@ }, { "cell_type": "code", - "execution_count": 113, + "execution_count": 20, "metadata": {}, "outputs": [ { "data": { - "image/png": "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\n", + "text/plain": [ + "(-0.7501943063424155,\n", + " 15.750194306342419,\n", + " -0.3404752506209626,\n", + " 4.2088127135203335)" + ] + }, + "execution_count": 20, + "metadata": {}, + "output_type": "execute_result" + }, + { + "data": { + "image/png": "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\n", "text/plain": [ "
" ] @@ -218,21 +243,23 @@ "import matplotlib.pyplot as plt\n", "plt.style.use(\"ggplot\")\n", "\n", - "x=np.arange(0,3,0.001) #interp range of curve \n", + "x=np.arange(0,2,0.001) #interp range of curve \n", "\n", "# VEHICLE REF FRAME\n", - "plt.subplot(2,1,1)\n", + "ax1=plt.subplot(2,1,1)\n", + "ax1.set_title('parametrized curve, vehicle ref frame')\n", "plt.scatter(0,0)\n", "plt.scatter(wp_vehicle_frame[0,:],wp_vehicle_frame[1,:])\n", "plt.plot(x,[f(xs,coeff) for xs in x])\n", "plt.axis('equal')\n", "\n", "# MAP REF FRAME\n", - "plt.subplot(2,1,2)\n", + "ax2=plt.subplot(2,1,2)\n", + "ax2.set_title('waypoints, map ref frame')\n", "plt.scatter(state[0],state[1])\n", "plt.scatter(track[0,:],track[1,:])\n", "plt.scatter(track[0,nn_idx:nn_idx+LOOKAHED],track[1,nn_idx:nn_idx+LOOKAHED])\n", - "plt.axis('equal');" + "plt.axis('equal')" ] }, { @@ -246,7 +273,7 @@ "cell_type": "markdown", "metadata": {}, "source": [ - "* **crosstrack error** cte -> desired y-position - y-position of vehicle: this is the bias term of the fitted polynomial (road curve)\n", + "* **crosstrack error** cte -> desired y-position - y-position of vehicle: this is the value of the fitted polynomial (road curve)\n", " \n", "$\n", "f = K_0 * x^3 + K_1 * x^2 + K_2 * x + K_3\n", @@ -276,15 +303,15 @@ }, { "cell_type": "code", - "execution_count": 119, + "execution_count": 15, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "-0.47433647872956336\n", - "55.83031014720696\n" + "0.03551042807053904\n", + "12.271049217491628\n" ] } ], @@ -316,7 +343,7 @@ "* $cte_{delay} = cte + v * sin(epsi) * dt$\n", "* $epsi_{delay} = epsi - w * dt$\n", "\n", - "Note that the current position and heading is always 0; this is becouse the path is parametrized to vehicle reference frame" + "Note that the starting position and heading is always 0; this is becouse the path is parametrized to **vehicle reference frame**" ] }, {