{ "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": "code", "execution_count": 2, "metadata": {}, "outputs": [], "source": [ "\"\"\"\n", "Control problem statement.\n", "\"\"\"\n", "\n", "N = 4 #number of state variables\n", "M = 2 #number of control variables\n", "T = 20 #Prediction Horizon\n", "DT = 0.2 #discretization step\n", "\n", "def get_linear_model(x_bar,u_bar):\n", " \"\"\"\n", " Computes the LTI approximated state space model x' = Ax + Bu + C\n", " \"\"\"\n", " \n", " L=0.3 #vehicle wheelbase\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)\n", "\n", "\"\"\"\n", "the ODE is used to update the simulation given the mpc results\n", "I use this insted of using the LTI twice\n", "\"\"\"\n", "def kinematics_model(x,t,u):\n", " \"\"\"\n", " Returns the set of ODE of the vehicle model.\n", " \"\"\"\n", " \n", " L=0.3 #vehicle wheelbase\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_ = np.zeros((N,T+1))\n", " \n", " x_[:,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_[:,t]=x_next[1]\n", " \n", " return x_\n", "\n", "\n", "\"\"\"\n", "MODIFIED TO INCLUDE FRAME TRANSFORMATION\n", "\"\"\"\n", "def compute_path_from_wp(start_xp, start_yp, step = 0.1):\n", " \"\"\"\n", " Computes a reference path given a set of waypoints\n", " \"\"\"\n", " \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", " # watch out to duplicate points!\n", " final_xp=np.append(final_xp,fx(interp_range)[1:])\n", " final_yp=np.append(final_yp,fy(interp_range)[1:])\n", " \n", " dx = np.append(0, np.diff(final_xp))\n", " dy = np.append(0, np.diff(final_yp))\n", " theta = np.arctan2(dy, dx)\n", "\n", " return np.vstack((final_xp,final_yp,theta))\n", "\n", "\n", "def get_nn_idx(state,path):\n", " \"\"\"\n", " Computes the index of the waypoint closest to vehicle\n", " \"\"\"\n", "\n", " dx = state[0]-path[0,:]\n", " dy = state[1]-path[1,:]\n", " dist = np.hypot(dx,dy)\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 normalize_angle(angle):\n", " \"\"\"\n", " Normalize an angle to [-pi, pi]\n", " \"\"\"\n", " while angle > np.pi:\n", " angle -= 2.0 * np.pi\n", "\n", " while angle < -np.pi:\n", " angle += 2.0 * np.pi\n", "\n", " return angle\n", "\n", "def get_ref_trajectory(state, path, target_v):\n", " \"\"\"\n", " modified reference in robot frame\n", " \"\"\"\n", " xref = np.zeros((N, T + 1))\n", " dref = np.zeros((1, T + 1))\n", " \n", " #sp = np.ones((1,T +1))*target_v #speed profile\n", " \n", " ncourse = path.shape[1]\n", "\n", " ind = get_nn_idx(state, path)\n", " dx=path[0,ind] - state[0]\n", " dy=path[1,ind] - state[1]\n", " \n", " xref[0, 0] = dx * np.cos(-state[3]) - dy * np.sin(-state[3]) #X\n", " xref[1, 0] = dy * np.cos(-state[3]) + dx * np.sin(-state[3]) #Y\n", " xref[2, 0] = target_v #V\n", " xref[3, 0] = normalize_angle(path[2,ind]- state[3]) #Theta\n", " dref[0, 0] = 0.0 # steer operational point should be 0\n", " \n", " dl = 0.05 # Waypoints spacing [m]\n", " travel = 0.0\n", " \n", " for i in range(T + 1):\n", " travel += abs(target_v) * DT #current V or target V?\n", " dind = int(round(travel / dl))\n", " \n", " if (ind + dind) < ncourse:\n", " dx=path[0,ind + dind] - state[0]\n", " dy=path[1,ind + dind] - state[1]\n", " \n", " xref[0, i] = dx * np.cos(-state[3]) - dy * np.sin(-state[3])\n", " xref[1, i] = dy * np.cos(-state[3]) + dx * np.sin(-state[3])\n", " xref[2, i] = target_v #sp[ind + dind]\n", " xref[3, i] = normalize_angle(path[2,ind + dind] - state[3])\n", " dref[0, i] = 0.0\n", " else:\n", " dx=path[0,ncourse - 1] - state[0]\n", " dy=path[1,ncourse - 1] - state[1]\n", " \n", " xref[0, i] = dx * np.cos(-state[3]) - dy * np.sin(-state[3])\n", " xref[1, i] = dy * np.cos(-state[3]) + dx * np.sin(-state[3])\n", " xref[2, i] = 0.0 #stop? #sp[ncourse - 1]\n", " xref[3, i] = normalize_angle(path[2,ncourse - 1] - state[3])\n", " dref[0, i] = 0.0\n", "\n", " return xref, dref" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## SMOOTHEN PATH\n", "\n", "I use a corner smoothing tecnique to help the line-finding proplem -> this way the line does not change from 0 to pi/2 instantly" ] }, { "cell_type": "code", "execution_count": 3, "metadata": {}, "outputs": [], "source": [ "from scipy.signal import savgol_filter\n", "def compute_path_from_wp(start_xp, start_yp, step = 0.1):\n", " \"\"\"\n", " Computes a reference path given a set of waypoints\n", " \"\"\"\n", " \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", " # watch out to duplicate points!\n", " final_xp=np.append(final_xp,fx(interp_range)[1:])\n", " final_yp=np.append(final_yp,fy(interp_range)[1:])\n", " \n", " \"\"\"this smoothens up corners\"\"\"\n", " window_size = 7 # Smoothening filter window\n", " final_xp = savgol_filter(final_xp, window_size, 1)\n", " final_yp = savgol_filter(final_yp, window_size, 1)\n", " \n", " dx = np.append(0, np.diff(final_xp))\n", " dy = np.append(0, np.diff(final_yp))\n", " theta = np.arctan2(dy, dx)\n", "\n", " return np.vstack((final_xp,final_yp,theta))\n" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## V3 Add track constraints\n", "inspried from -> https://arxiv.org/pdf/1711.07300.pdf\n", "\n", "explanation here...\n", "\n", "benefits:\n", "* add a soft form of obstacle aoidance" ] }, { "cell_type": "code", "execution_count": 4, "metadata": {}, "outputs": [ { "data": { "text/plain": [ "[]" ] }, "execution_count": 4, "metadata": {}, "output_type": "execute_result" }, { "data": { "image/png": "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\n", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "def generate_track_bounds(track,width=0.5):\n", " \"\"\"\n", " in world frame\n", " \"\"\"\n", " bounds_low=np.zeros((2, track.shape[1]))\n", " bounds_upp=np.zeros((2, track.shape[1]))\n", " \n", " for idx in range(track.shape[1]):\n", " x = track[0,idx]\n", " y = track [1,idx]\n", " th = track [2,idx]\n", " \n", " \"\"\"\n", " trasform the points\n", " \"\"\"\n", " bounds_upp[0, idx] = 0 * np.cos(th) - width * np.sin(th) + x #X\n", " bounds_upp[1, idx] = 0 * np.sin(th) + width * np.cos(th) + y #Y\n", " \n", " bounds_low[0, idx] = 0 * np.cos(th) - (-width) * np.sin(th) + x #X\n", " bounds_low[1, idx] = 0 * np.sin(th) + (-width) * np.cos(th) + y #Y\n", " \n", " return bounds_low, bounds_upp\n", "\n", "track = compute_path_from_wp([0,3,4,6,10,12,14,6,1,0],\n", " [0,0,2,4,3,3,-2,-6,-2,-2],0.05)\n", "\n", "lower, upper = generate_track_bounds(track)\n", "\n", "plt.figure(figsize=(15,10))\n", "\n", "plt.plot(track[0,:],track[1,:],\"b-\")\n", "plt.plot(lower[0,:],lower[1,:],\"g-\")\n", "plt.plot(upper[0,:],upper[1,:],\"r-\")" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "the points can be used to generate the **halfplane constrains** for each reference point.\n", "the issues (outliers points) should be gone after we are in vehicle frame...\n", "\n", "the halfplane constrains are defined given the line equation:\n", "\n", "**lower halfplane**\n", "$$ a1x_1 + b1x_2 = c1 \\rightarrow a1x_1 + b1x_2 \\leq c1$$\n", "\n", "**upper halfplane**\n", "$$ a2x_1 - b2x_2 = c2 \\rightarrow a2x_1 + b2x_2 \\leq c2$$\n", "\n", "we want to combine this in matrix form:\n", "\n", "$$\n", "\\begin{bmatrix}\n", "x_1 \\\\\n", "x_2 \n", "\\end{bmatrix}\n", "\\begin{bmatrix}\n", "a_1 & a_2\\\\\n", "b_1 & b_2\n", "\\end{bmatrix}\n", "\\leq\n", "\\begin{bmatrix}\n", "c_1 \\\\\n", "c_2 \n", "\\end{bmatrix}\n", "$$\n", "\n", "becouse our track points have known heading the coefficients can be computed from:\n", "\n", "$$ y - y' = \\frac{sin(\\theta)}{cos(\\theta)}(x - x') $$\n", "\n", "we have:\n", "\n", "$$\n", "-tan(\\theta)x + y = - tan(\\theta)x' + y'\n", "$$\n", "where:\n", "* $ a = -tan(\\theta) $\n", "* $ b = 1 $\n", "* $ c = - tan(\\theta)x' + y' $" ] }, { "cell_type": "code", "execution_count": 5, "metadata": {}, "outputs": [ { "data": { "text/plain": [ "(-2.0, 2.0)" ] }, "execution_count": 5, "metadata": {}, "output_type": "execute_result" }, { "data": { "image/png": "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\n", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "import numpy as np\n", "import matplotlib.pyplot as plt\n", "plt.style.use(\"ggplot\")\n", "\n", "def get_coeff(x,y,theta):\n", " m = np.sin(theta)/np.cos(theta)\n", " return(-m,1,y-m*x)\n", "\n", "#test -> assume point 10,1,pi/6\n", "#coeff = get_coeff(1,-1, np.pi/2)\n", "coeff = get_coeff(1,-1, np.pi/4)\n", "y = []\n", "pts = np.linspace(0,20,100)\n", "\n", "for x in pts:\n", " y.append((-coeff[0]*x+coeff[2])/coeff[1])\n", " \n", "plt.figure(figsize=(5,5))\n", "plt.plot(pts,y,\"b-\")\n", "\n", "plt.xlim((-2, 2))\n", "plt.ylim((-2, 2))" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## WARN TANGENT BREAKS AROUND PI/2?\n", "force the equation to x = val" ] }, { "cell_type": "code", "execution_count": 6, "metadata": {}, "outputs": [ { "data": { "text/plain": [ "(-2.0, 2.0)" ] }, "execution_count": 6, "metadata": {}, "output_type": "execute_result" }, { "data": { "image/png": "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\n", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "# def get_coeff(x,y,theta):\n", " \n", "# if (theta - np.pi/2) < 0.01:\n", "# #print (\"WARN -> theta is 90, tan is: \" + str(theta))\n", "# # eq is x = val\n", "# m = 0\n", "# return (1,1e-6,x)\n", "# else:\n", "# m = np.sin(theta)/np.cos(theta)\n", "# return(-m,1,y-m*x)\n", " \n", "#test -> assume point 10,1,pi/6\n", "coeff = get_coeff(1,-1, np.pi/2)\n", "y = []\n", "pts = np.linspace(0,20,100)\n", "\n", "for x in pts:\n", " y.append((-coeff[0]*x+coeff[2])/coeff[1])\n", " \n", "plt.figure(figsize=(5,5))\n", "\n", "plt.plot(pts,y,\"b-\")\n", "plt.axis(\"equal\")\n", "plt.xlim((-2, 2))\n", "plt.ylim((-2, 2))" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "becouse the controller uses vhicle reference frame this rquire adapting -> the semiplane constraints must be gathetered from **x_ref points**\n", "\n", "*low and up are w.r.t vehicle y axis*" ] }, { "cell_type": "code", "execution_count": 7, "metadata": {}, "outputs": [], "source": [ "def get_track_constrains(x_ref, width=0.5):\n", " \"\"\"\n", " x_ref has hape (4,T) -> [x,y,v,theta]_ref \n", " \"\"\"\n", " \n", " #1-> get the upper and lower points\n", " pts_low=np.zeros((3, x_ref.shape[1]))\n", " pts_upp=np.zeros((3, x_ref.shape[1]))\n", " \n", " for idx in range(x_ref.shape[1]):\n", " x = x_ref [0, idx]\n", " y = x_ref [1, idx]\n", " th = x_ref [3, idx]\n", " \n", " \"\"\"\n", " trasform the points\n", " \"\"\"\n", " pts_upp[0, idx] = 0 * np.cos(th) - width * np.sin(th) + x #X\n", " pts_upp[1, idx] = 0 * np.sin(th) + width * np.cos(th) + y #Y\n", " pts_upp[2, idx] = th #heading\n", " \n", " pts_low[0, idx] = 0 * np.cos(th) - (-width) * np.sin(th) + x #X\n", " pts_low[1, idx] = 0 * np.sin(th) + (-width) * np.cos(th) + y #Y\n", " pts_low[2, idx] = th #heading\n", " \n", " #get coefficients ->(a,b,c)\n", " coeff_low=np.zeros((3, x_ref.shape[1]))\n", " coeff_upp=np.zeros((3, x_ref.shape[1]))\n", " \n", " for idx in range(pts_upp.shape[1]):\n", " f = get_coeff(pts_low[0,idx],pts_low[1,idx],pts_low[2,idx])\n", " coeff_low[0,idx]=f[0]\n", " coeff_low[1,idx]=f[1]\n", " coeff_low[2,idx]=f[2]\n", " \n", " f = get_coeff(pts_upp[0,idx],pts_upp[1,idx],pts_upp[2,idx])\n", " coeff_upp[0,idx]=f[0]\n", " coeff_upp[1,idx]=f[1]\n", " coeff_upp[2,idx]=f[2]\n", " \n", " return coeff_low, coeff_upp\n", " " ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## MPC INTEGRATION\n", "\n", "compare the results with and without" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "simpe u-turn test\n", "\n", "## 1-> NO BOUNDS" ] }, { "cell_type": "code", "execution_count": 8, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "CVXPY Optimization Time: Avrg: 0.1719s Max: 0.2054s Min: 0.1581s\n" ] } ], "source": [ "track = compute_path_from_wp([0,3,3,0],\n", " [0,0,1,1],0.05)\n", "\n", "track_lower, track_upper = generate_track_bounds(track,0.12)\n", "\n", "sim_duration = 50 #time steps\n", "opt_time=[]\n", "\n", "x_sim = np.zeros((N,sim_duration))\n", "u_sim = np.zeros((M,sim_duration-1))\n", "\n", "MAX_SPEED = 1.5 #m/s\n", "MAX_ACC = 1.0 #m/ss\n", "MAX_D_ACC = 1.0 #m/sss\n", "MAX_STEER = np.radians(30) #rad\n", "MAX_D_STEER = np.radians(30) #rad/s\n", "\n", "REF_VEL = 0.5 #m/s\n", "\n", "# Starting Condition\n", "x0 = np.zeros(N)\n", "x0[0] = 0 #x\n", "x0[1] = -0.05 #y\n", "x0[2] = 0.0 #v\n", "x0[3] = np.radians(-0) #yaw\n", "x_sim[:,0] = x0 #simulation_starting conditions\n", " \n", "#starting guess\n", "u_bar = np.zeros((M,T))\n", "u_bar[0,:] = MAX_ACC/2 #a\n", "u_bar[1,:] = 0.0 #delta\n", " \n", "for sim_time in range(sim_duration-1):\n", " \n", " iter_start = time.time()\n", " \n", " # dynamics starting state w.r.t. robot are always null except vel \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", " x = cp.Variable((N, T+1))\n", " u = cp.Variable((M, T))\n", " cost = 0\n", " constr = []\n", "\n", " # Cost Matrices\n", " Q = np.diag([20,20,10,20]) #state error cost\n", " Qf = np.diag([30,30,30,30]) #state final error cost\n", " R = np.diag([10,10]) #input cost\n", " R_ = np.diag([10,10]) #input rate of change cost\n", "\n", " #Get Reference_traj\n", " #dont use x0 in this case\n", " x_ref, d_ref = get_ref_trajectory(x_sim[:,sim_time] ,track, REF_VEL)\n", " \n", " #Prediction Horizon\n", " for t in range(T):\n", "\n", " # Tracking Error\n", " cost += cp.quad_form(x[:,t] - x_ref[:,t], Q)\n", "\n", " # Actuation effort\n", " cost += cp.quad_form(u[:,t], R)\n", "\n", " # Actuation rate of change\n", " if t < (T - 1):\n", " cost += cp.quad_form(u[:,t+1] - u[:,t], R_)\n", " constr+= [cp.abs(u[0, t + 1] - u[0, t])/DT <= MAX_D_ACC] #max acc rate of change\n", " constr += [cp.abs(u[1, t + 1] - u[1, t])/DT <= MAX_D_STEER] #max steer rate of change\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", " #Final Point tracking\n", " cost += cp.quad_form(x[:, T] - x_ref[:, T], Qf)\n", "\n", " # sums problem objectives and concatenates constraints.\n", " constr += [x[:,0] == x_bar[:,0]] #starting condition\n", " constr += [x[2,:] <= MAX_SPEED] #max speed\n", " constr += [x[2,:] >= 0.0] #min_speed (not really needed)\n", " constr += [cp.abs(u[0,:]) <= MAX_ACC] #max acc\n", " constr += [cp.abs(u[1,:]) <= MAX_STEER] #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": 9, "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(track_lower[0,:],track_lower[1,:],\"g-\")\n", "plt.plot(track_upper[0,:],track_upper[1,:],\"r-\")\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) [rad]')\n", "\n", "plt.subplot(grid[3, 4])\n", "plt.plot(x_sim[3,:])\n", "plt.ylabel('theta(t) [rad]')\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## 2-> WITH BOUNDS\n", "if there is 90 deg turn the optimization fails!\n", "if speed is too high it also fails ..." ] }, { "cell_type": "code", "execution_count": 12, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "CVXPY Optimization Time: Avrg: 0.1803s Max: 0.2286s Min: 0.1630s\n" ] } ], "source": [ "WIDTH=0.18\n", "REF_VEL = 0.4 #m/s\n", "\n", "computed_coeff = []\n", "\n", "track = compute_path_from_wp([0,3,3,0],\n", " [0,0,1,1],0.05)\n", "\n", "track_lower, track_upper = generate_track_bounds(track,WIDTH)\n", "\n", "sim_duration = 200 #time steps\n", "opt_time=[]\n", "\n", "x_sim = np.zeros((N,sim_duration))\n", "u_sim = np.zeros((M,sim_duration-1))\n", "\n", "MAX_SPEED = 1.5 #m/s\n", "MAX_ACC = 1.0 #m/ss\n", "MAX_D_ACC = 1.0 #m/sss\n", "MAX_STEER = np.radians(30) #rad\n", "MAX_D_STEER = np.radians(30) #rad/s\n", "\n", "\n", "# Starting Condition\n", "x0 = np.zeros(N)\n", "x0[0] = 0 #x\n", "x0[1] = WIDTH/2 #y\n", "x0[2] = 0.0 #v\n", "x0[3] = np.radians(-0) #yaw\n", "x_sim[:,0] = x0 #simulation_starting conditions\n", " \n", "#starting guess\n", "u_bar = np.zeros((M,T))\n", "u_bar[0,:] = MAX_ACC/2 #a\n", "u_bar[1,:] = 0.0 #delta\n", " \n", "for sim_time in range(sim_duration-1):\n", " \n", " iter_start = time.time()\n", " \n", " # dynamics starting state w.r.t. robot are always null except vel \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", " x = cp.Variable((N, T+1))\n", " u = cp.Variable((M, T))\n", " cost = 0\n", " constr = []\n", "\n", " # Cost Matrices\n", " Q = np.diag([20,20,10,20]) #state error cost\n", " Qf = np.diag([30,30,30,30]) #state final error cost\n", " R = np.diag([10,10]) #input cost\n", " R_ = np.diag([10,10]) #input rate of change cost\n", "\n", " #Get Reference_traj\n", " #dont use x0 in this case\n", " x_ref, d_ref = get_ref_trajectory(x_sim[:,sim_time] ,track, REF_VEL)\n", " \n", " #Prediction Horizon\n", " for t in range(T):\n", "\n", " # Tracking Error\n", " cost += cp.quad_form(x[:,t] - x_ref[:,t], Q)\n", "\n", " # Actuation effort\n", " cost += cp.quad_form(u[:,t], R)\n", "\n", " # Actuation rate of change\n", " if t < (T - 1):\n", " cost += cp.quad_form(u[:,t+1] - u[:,t], R_)\n", " constr+= [cp.abs(u[0, t + 1] - u[0, t])/DT <= MAX_D_ACC] #max acc rate of change\n", " constr += [cp.abs(u[1, t + 1] - u[1, t])/DT <= MAX_D_STEER] #max steer rate of change\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", " #Final Point tracking\n", " cost += cp.quad_form(x[:, T] - x_ref[:, T], Qf)\n", "\n", " # sums problem objectives and concatenates constraints.\n", " constr += [x[:,0] == x_bar[:,0]] #starting condition\n", " constr += [x[2,:] <= MAX_SPEED] #max speed\n", " constr += [x[2,:] >= 0.0] #min_speed (not really needed)\n", " constr += [cp.abs(u[0,:]) <= MAX_ACC] #max acc\n", " constr += [cp.abs(u[1,:]) <= MAX_STEER] #max steer\n", " \n", " #Track constrains\n", " low,upp = get_track_constrains(x_ref,WIDTH)\n", " computed_coeff.append((low,upp))\n", " for ii in range(low.shape[1]):\n", " constr += [low[0,ii]*x[0,ii] + x[1,ii] >= low[2,ii]]\n", " #constr += [upp[0,ii]*x[0,ii] + x[1,ii] <= upp[2,ii]]\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": 19, "metadata": {}, "outputs": [ { "data": { "image/png": "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\n", "text/plain": [ "
" ] }, "metadata": { "needs_background": "light" }, "output_type": "display_data" } ], "source": [ "%matplotlib inline\n", "#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(track_lower[0,:],track_lower[1,:],\"g.\")\n", "plt.plot(track_upper[0,:],track_upper[1,:],\"r.\")\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", "\n", "plt.subplot(grid[2, 4])\n", "plt.plot(np.degrees(u_sim[1,:]))\n", "plt.ylabel('delta(t) [rad]')\n", "\n", "plt.subplot(grid[3, 4])\n", "plt.plot(x_sim[3,:])\n", "plt.ylabel('theta(t) [rad]')\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## VISUALIZE THE COMPUTED HALF-PLANES" ] }, { "cell_type": "code", "execution_count": 14, "metadata": {}, "outputs": [ { "data": { "image/png": "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\n", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "import numpy as np\n", "import matplotlib.pyplot as plt\n", "plt.style.use(\"ggplot\")\n", "\n", "\n", "def plot_low_upp(low, up):\n", " \"\"\"\n", " low and upp arre arrays of shape (3,N)\n", " each column represent the couefficient at each\n", " step of the optimization\n", " \"\"\"\n", " \n", " #for low,up in zip(low, up):\n", " for idx in range(low.shape[1]):\n", " \n", " ll = low[:,idx]\n", " uu = up[:,idx]\n", " \n", " x = np.linspace(-2,2,100)\n", "\n", " #low\n", " y = []\n", " for xx in x:\n", " y.append((-ll[0]*xx+ll[2])/ll[1])\n", "\n", " plt.plot(x,y,\"b-\")\n", "\n", " #high\n", " y = []\n", " for xx in x:\n", " y.append((-uu[0]*xx+uu[2])/uu[1])\n", "\n", " plt.plot(x,y,\"r-\")\n", "\n", " plt.xlim((-2, 2))\n", " plt.ylim((-2, 2))\n", "\n", "def plot_lines():\n", " \"\"\"\n", " sample randomly from computed coeff\n", " and plot grid\n", " \"\"\"\n", " \n", " plt.figure(figsize=(15,15))\n", " indices = np.random.choice(len(computed_coeff), 9)\n", "\n", " for i in range(len(indices)):\n", " plt.subplot(3,3,i+1)\n", " plt.title(\"t = \"+str(indices[i]))\n", " plot_low_upp(computed_coeff[indices[i]][0]\n", " ,computed_coeff[indices[i]][1])\n", " \n", " plt.tight_layout()\n", " plt.show()\n", "\n", "plot_lines()" ] }, { "cell_type": "code", "execution_count": null, "metadata": {}, "outputs": [], "source": [] } ], "metadata": { "kernelspec": { "display_name": "Python [conda env:.conda-jupyter] *", "language": "python", "name": "conda-env-.conda-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.5" } }, "nbformat": 4, "nbformat_minor": 4 }