{ "cells": [ { "cell_type": "code", "execution_count": 29, "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}) + \\frac{\\partial f(x,u)}{\\partial 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}) + B(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_t}dt & 0 \\\\\n", "\\sin{\\theta_t}dt & 0 \\\\\n", "0 & dt\n", "\\end{bmatrix}\n", "\\quad\n", "$\n", "\n", "are the *Jacobians* of the function \n", "\n", "So the discretized model is given by:\n", "\n", "$ x_{t+1} = x_t + (f(\\bar{x},\\bar{u}) + A(x_t-\\bar{x}) + B(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 $\n", "\n", "$ B' = dtB $\n", "\n", "$ C' = dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\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": 30, "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": 31, "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": 32, "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": 33, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "CPU times: user 4.29 ms, sys: 15 µs, total: 4.3 ms\n", "Wall time: 3.97 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": 34, "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": [ "the results seems valid:\n", "* the cte is correct\n", "* theta error is correct" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Motion Prediction: using the state space model" ] }, { "cell_type": "code", "execution_count": 35, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "CPU times: user 2.32 ms, sys: 131 µs, total: 2.45 ms\n", "Wall time: 2.03 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": 36, "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(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" ] }, { "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": 37, "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": [ "test it" ] }, { "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": 40, "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": 45, "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.1713s Max: 0.2654s Min: 0.1564s\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": 46, "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 }