{ "cells": [ { "cell_type": "code", "execution_count": 71, "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", "* $\\theta$ heading of the robot\n", "\n", "The inputs of the model are:\n", "\n", "* $v$ linear velocity of the robot\n", "* $w$ angular velocity of the robot\n", "\n", "These are the differential equations f(x,u) of the model:\n", "\n", "* $\\dot{x} = v\\cos{\\theta}$ \n", "* $\\dot{y} = v\\sin{\\theta}$\n", "* $\\dot{\\theta} = w$\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", "* ${\\theta_{t+1}} = \\theta_{t} + w_t*dt$\n", "\n", "This Model is **non-linear** and **time variant**, to approximate its 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", "For the State Space model this can be rewritten as:\n", "\n", "$ f(\\bar{x},\\bar{u}) + A|_{x=\\bar{x},u=\\bar{u}}(x-\\bar{x}) + B|_{x=\\bar{x},u=\\bar{u}}(u-\\bar{u})$\n", "\n", "Where:\n", "\n", "$\n", "A =\n", "\\quad\n", "\\begin{bmatrix}\n", "\\frac{\\partial f(x,u)}{\\partial x} & \\frac{\\partial f(x,u)}{\\partial y} & \\frac{\\partial f(x,u)}{\\partial \\theta} \\\\\n", "\\end{bmatrix}\n", "\\quad\n", "=\n", "\\quad\n", "\\begin{bmatrix}\n", "0 & 0 & -v\\sin{\\theta} \\\\\n", "0 & 0 & v\\cos{\\theta} \\\\\n", "0 & 0 & 0\\\\\n", "\\end{bmatrix}\n", "\\quad\n", "$\n", "\n", "and\n", "\n", "$\n", "B = \n", "\\quad\n", "\\begin{bmatrix}\n", "\\frac{\\partial f(x,u)}{\\partial v} & \\frac{\\partial f(x,u)}{\\partial w} \\\\\n", "\\end{bmatrix}\n", "\\quad\n", "= \n", "\\quad\n", "\\begin{bmatrix}\n", "\\cos{\\theta} & 0 \\\\\n", "\\sin{\\theta} & 0 \\\\\n", "0 & 1\n", "\\end{bmatrix}\n", "\\quad\n", "$\n", "\n", "are the *Jacobians*.\n", "\n", "\n", "\n", "So the discretized model is given by:\n", "\n", "$ x_{t+1} = x_t + (f(\\bar{x},\\bar{u}) + A|_{x=\\bar{x}}(x_t-\\bar{x}) + B|_{u=\\bar{u}}(u_t-\\bar{u}) )dt $\n", "\n", "$ x_{t+1} = (I+dtA)x_t + dtBu_t +dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\bar{u}))$\n", "\n", "The LTI-equivalent kinematics model is:\n", "\n", "$ x_{t+1} = A'x_t + B' u_t + C' $\n", "\n", "with:\n", "\n", "$ A' = I+dtA|_{x=\\bar{x},u=\\bar{u}} $\n", "\n", "$ B' = dtB|_{x=\\bar{x},u=\\bar{u}} $\n", "\n", "$ C' = dt(f(\\bar{x},\\bar{u}) - A|_{x=\\bar{x},u=\\bar{u}}\\bar{x} - B|_{x=\\bar{x},u=\\bar{u}}\\bar{u}) $\n", "\n", "**Errors** are:\n", "* $\\psi$ heading error = $\\psi = \\theta_{ref} - \\theta$\n", "* $cte$ crosstrack error = lateral distance of the robot from the track w.r.t robot frame, cte is a function of the track and x\n", "\n", "described by:" ] }, { "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": 72, "metadata": {}, "outputs": [], "source": [ "# Control problem statement.\n", "\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" ] }, { "cell_type": "code", "execution_count": 73, "metadata": {}, "outputs": [], "source": [ "def get_linear_model(x_bar,u_bar):\n", " \"\"\"\n", " \"\"\"\n", " \n", " x = x_bar[0]\n", " y = x_bar[1]\n", " theta = x_bar[2]\n", " \n", " v = u_bar[0]\n", " w = u_bar[1]\n", " \n", " A = np.zeros((N,N))\n", " A[0,2]=-v*np.sin(theta)\n", " A[1,2]=v*np.cos(theta)\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_lin=dt*B\n", " \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" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Motion Prediction: using scipy intergration" ] }, { "cell_type": "code", "execution_count": 74, "metadata": {}, "outputs": [], "source": [ "# Define process model\n", "# This uses the continuous model \n", "def kinematics_model(x,t,u):\n", " \"\"\"\n", " \"\"\"\n", "\n", " dxdt = u[0]*np.cos(x[2])\n", " dydt = u[0]*np.sin(x[2])\n", " dthetadt = u[1]\n", "\n", " dqdt = [dxdt,\n", " dydt,\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": 75, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "CPU times: user 0 ns, sys: 6.46 ms, total: 6.46 ms\n", "Wall time: 5.05 ms\n" ] } ], "source": [ "%%time\n", "\n", "u_bar = np.zeros((M,T))\n", "u_bar[0,:] = 1 #m/s\n", "u_bar[1,:] = np.radians(-10) #rad/s\n", "\n", "x0 = np.zeros(N)\n", "x0[0] = 0\n", "x0[1] = 1\n", "x0[2] = 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": 76, "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": 77, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "CPU times: user 2.82 ms, sys: 106 µs, total: 2.93 ms\n", "Wall time: 2.04 ms\n" ] } ], "source": [ "%%time\n", "\n", "u_bar = np.zeros((M,T))\n", "u_bar[0,:] = 1 #m/s\n", "u_bar[1,:] = np.radians(-10) #rad/s\n", "\n", "x0 = np.zeros(N)\n", "x0[0] = 0\n", "x0[1] = 1\n", "x0[2] = 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": 78, "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": [ "------------------\n", "\n", "the kinematics model predictits psi and cte for constant heading references. So, for non-constant paths appropriate functions have to be developed.\n", "\n", "-----------------" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## PRELIMINARIES" ] }, { "cell_type": "code", "execution_count": 79, "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)\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": "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= MIN_SPEED]\n", "constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED]\n", "\n", "prob = cp.Problem(cp.Minimize(cost), constr)\n", "solution = prob.solve(solver=cp.OSQP, verbose=True)" ] }, { "cell_type": "code", "execution_count": 82, "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", "theta_mpc=np.array(x.value[2, :]).flatten()\n", "v_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((v_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(v_mpc)\n", "plt.ylabel('v(t)')\n", "#plt.xlabel('time')\n", "\n", "#plot w(t)\n", "# plt.subplot(2, 2, 3)\n", "# plt.plot(w_mpc)\n", "# 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", "\n", "# plt.subplot(2, 2, 4)\n", "# plt.plot(cte_mpc)\n", "# plt.ylabel('cte(t)')\n", "\n", "plt.tight_layout()\n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "full track demo" ] }, { "cell_type": "code", "execution_count": 83, "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.1777s Max: 0.2694s Min: 0.1558s\n" ] } ], "source": [ "# track = compute_path_from_wp([0,3,4,6,10],\n", "# [0,0,2,4,3])\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])\n", "sim_duration = 100 #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", " 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", " \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", " 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], 1*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", " # 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(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": 84, "metadata": {}, "outputs": [ { "data": { "image/png": "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\n", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "#plot trajectory\n", "grid = plt.GridSpec(2, 3)\n", "\n", "plt.figure(figsize=(15,10))\n", "\n", "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", "plt.axis(\"equal\")\n", "plt.ylabel('y')\n", "plt.xlabel('x')\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", "plt.tight_layout()\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 }