{ "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 v} & \\frac{\\partial f(x,u)}{\\partial \\theta} \\\\\n", "\\end{bmatrix}\n", "\\quad\n", "=\n", "\\displaystyle \\left[\\begin{matrix}0 & 0 & \\cos{\\left(\\theta \\right)} & - v \\sin{\\left(\\theta \\right)}\\\\0 & 0 & \\sin{\\left(\\theta \\right)} & v \\cos{\\left(\\theta \\right)}\\\\0 & 0 & 0 & 0\\\\0 & 0 & \\frac{\\tan{\\left(\\delta \\right)}}{L} & 0\\end{matrix}\\right]\n", "$\n", "\n", "and\n", "\n", "$\n", "B = \n", "\\quad\n", "\\begin{bmatrix}\n", "\\frac{\\partial f(x,u)}{\\partial a} & \\frac{\\partial f(x,u)}{\\partial \\delta} \\\\\n", "\\end{bmatrix}\n", "\\quad\n", "= \n", "\\displaystyle \\left[\\begin{matrix}0 & 0\\\\0 & 0\\\\1 & 0\\\\0 & \\frac{v \\left(\\tan^{2}{\\left(\\delta \\right)} + 1\\right)}{L}\\end{matrix}\\right]\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": "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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)')\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": 37, "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", ":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.2258s Max: 0.3213s Min: 0.2024s\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[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": 38, "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 }