mpc_python_learn/notebooks/MPC_racecar_tracking.ipynb

1202 lines
187 KiB
Plaintext

{
"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",
"* $a$ acceleration of the robot\n",
"* $\\delta$ steering 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": [
"\"\"\"\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.25 #discretization step"
]
},
{
"cell_type": "code",
"execution_count": 3,
"metadata": {},
"outputs": [],
"source": [
"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)"
]
},
{
"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",
" 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_"
]
},
{
"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.49 ms, sys: 0 ns, total: 3.49 ms\n",
"Wall time: 3 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": [
"<Figure size 432x288 with 2 Axes>"
]
},
"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 2.17 ms, sys: 379 µs, total: 2.55 ms\n",
"Wall time: 1.76 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": [
"<Figure size 432x288 with 2 Axes>"
]
},
"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": 31,
"metadata": {},
"outputs": [],
"source": [
"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",
" final_xp=np.append(final_xp,fx(interp_range))\n",
" final_yp=np.append(final_yp,fy(interp_range))\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 get_ref_trajectory(state, path, target_v):\n",
" \"\"\"\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",
"\n",
" xref[0, 0] = path[0,ind] #X\n",
" xref[1, 0] = path[1,ind] #Y\n",
" xref[2, 0] = target_v #sp[ind] #V\n",
" xref[3, 0] = path[2,ind] #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",
" xref[0, i] = path[0,ind + dind]\n",
" xref[1, i] = path[1,ind + dind]\n",
" xref[2, i] = target_v #sp[ind + dind]\n",
" xref[3, i] = path[2,ind + dind]\n",
" dref[0, i] = 0.0\n",
" else:\n",
" xref[0, i] = path[0,ncourse - 1]\n",
" xref[1, i] = path[1,ncourse - 1]\n",
" xref[2, i] = target_v #sp[ncourse - 1]\n",
" xref[3, i] = path[2,ncourse - 1]\n",
" dref[0, i] = 0.0\n",
"\n",
" return xref, dref"
]
},
{
"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<j<t+T-1 \\\\\n",
"\\end{aligned}\n",
"\\end{equation}\n",
"$\n",
"\n",
"Other linear constrains may be applied,for instance on the control variable:\n",
"\n",
"$ U_{MIN} < u_{j|t} < U_{MAX} \\quad \\textrm{for} \\quad t<j<t+T-1 $\n",
"\n",
"The objective fuction accounts for quadratic error on deviation from 0 of the state and the control inputs sequences. Q and R are the **weight matrices** and are used to tune the response.\n",
"\n",
"Because the goal is tracking a **reference signal** such as a trajectory, the objective function is rewritten as:\n",
"\n",
"$\n",
"\\begin{equation}\n",
"\\begin{aligned}\n",
"\\min_{} \\quad & \\sum^{t+T-1}_{j=t} \\delta x^T_{j|t}Q\\delta x_{j|t} + u^T_{j|t}Ru_{j|t}\n",
"\\end{aligned}\n",
"\\end{equation}\n",
"$\n",
"\n",
"where the error w.r.t desired state is accounted for:\n",
"\n",
"$ \\delta x = x_{j,t,ref} - x_{j,t} $"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"# Problem Formulation: Study case\n",
"\n",
"In this case, the objective function to minimize is given by:\n",
"\n",
"https://www.notion.so/Academic-Papers-65e231322112442d80e32c617826b69e#feb1ff08484d43c0b20797c855356e5b\n",
"\n",
"$\n",
"\\begin{equation}\n",
"\\begin{aligned}\n",
"\\min_{} \\quad & \\sum^{t+T-1}_{j=t} cte_{j|t,ref}^TQcte_{j,t,ref} + \\psi_{j|t,ref}^TP\\psi_{j|t,ref} + (v_{j|t} - v_{j|t,ref})^TK(v_{j|t} - v_{j|t,ref}) + 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<j<t+T-1 \\\\\n",
" & a_{MIN} < a_{j|t} < a_{MAX} \\quad \\textrm{for} \\quad t<j<t+T-1 \\\\\n",
" & \\delta_{MIN} < \\delta_{j|t} < \\delta_{MAX} \\quad \\textrm{for} \\quad t<j<t+T-1 \\\\\n",
"\\end{aligned}\n",
"\\end{equation}\n",
"$\n",
"\n",
"\n",
"Where R,P,K,Q are the cost matrices used to tune the response.\n"
]
},
{
"cell_type": "code",
"execution_count": 43,
"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 = 322, constraints m = 404\n",
" nnz(P) + nnz(A) = 1051\n",
"settings: linear system solver = qdldl,\n",
" eps_abs = 1.0e-05, eps_rel = 1.0e-05,\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 5.08e+00 5.08e+02 1.00e-01 3.55e-04s\n",
" 175 1.7545e+02 5.84e-05 5.89e-05 6.89e+00 1.77e-03s\n",
"\n",
"status: solved\n",
"solution polish: unsuccessful\n",
"number of iterations: 175\n",
"optimal objective: 175.4495\n",
"run time: 2.96e-03s\n",
"optimal rho estimate: 6.44e+00\n",
"\n",
"CPU times: user 116 ms, sys: 37 µs, total: 116 ms\n",
"Wall time: 116 ms\n"
]
}
],
"source": [
"%%time\n",
"\n",
"MAX_SPEED = 1.5 #m/s\n",
"MAX_STEER = np.radians(30) #rad\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.05)\n",
"\n",
"# Starting Condition\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0 #x\n",
"x0[1] = -0.25 #y\n",
"x0[2] = 0.0 #v\n",
"x0[3] = np.radians(-0) #yaw\n",
" \n",
"#starting guess\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:] = MAX_ACC/2 #a\n",
"u_bar[1,:] = 0.1 #delta\n",
"\n",
"# dynamics starting state w.r.t world frame\n",
"x_bar = np.zeros((N,T+1))\n",
"x_bar[:,0] = x0\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([10,10,10,10]) #state error cost\n",
"Qf = np.diag([10,10,10,10]) #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",
"x_ref, d_ref = get_ref_trajectory(x_bar[:,0] ,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",
"\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]] #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",
"prob = cp.Problem(cp.Minimize(cost), constr)\n",
"solution = prob.solve(solver=cp.OSQP, verbose=True)"
]
},
{
"cell_type": "code",
"execution_count": 44,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 432x288 with 4 Axes>"
]
},
"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",
"delta_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_ref[0,:],x_ref[1,:],\"g+\")\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, 3)\n",
"plt.plot(a_mpc)\n",
"plt.ylabel('a_in(t)')\n",
"#plt.xlabel('time')\n",
"\n",
"\n",
"plt.subplot(2, 2, 2)\n",
"plt.plot(theta_mpc)\n",
"plt.ylabel('theta(t)')\n",
"\n",
"plt.subplot(2, 2, 4)\n",
"plt.plot(delta_mpc)\n",
"plt.ylabel('d_in(t)')\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"full track demo"
]
},
{
"cell_type": "code",
"execution_count": 52,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CVXPY Optimization Time: Avrg: 0.1121s Max: 0.1404s Min: 0.1029s\n"
]
}
],
"source": [
"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",
"# 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 = 175 #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_STEER = np.radians(30) #rad\n",
"MAX_ACC = 1.0\n",
"REF_VEL=1.0\n",
"\n",
"# Starting Condition\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0 #x\n",
"x0[1] = -0.25 #y\n",
"x0[2] = 0.0 #v\n",
"x0[3] = np.radians(-0) #yaw\n",
" \n",
"#starting guess\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:] = MAX_ACC/2 #a\n",
"u_bar[1,:] = 0.1 #delta\n",
"\n",
"for sim_time in range(sim_duration-1):\n",
" \n",
" iter_start=time.time()\n",
" \n",
" # dynamics starting state\n",
" x_bar = np.zeros((N,T+1))\n",
" x_bar[:,0] = x_sim[:,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,0]) #state error cost\n",
" Qf = np.diag([10,10,10,10]) #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",
" x_ref, d_ref = get_ref_trajectory(x_bar[:,0] ,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",
"\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]] #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": 53,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 1080x720 with 5 Axes>"
]
},
"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 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.8.5"
}
},
"nbformat": 4,
"nbformat_minor": 4
}