mpc_python_learn/notebooks/MPC_racecar_tracking.ipynb

1219 lines
186 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 2.77 ms, sys: 767 µs, total: 3.54 ms\n",
"Wall time: 2.99 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.99 ms, sys: 0 ns, total: 2.99 ms\n",
"Wall time: 1.91 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": 9,
"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] = 0.0 #stop? #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://borrelli.me.berkeley.edu/pdfpub/IV_KinematicMPC_jason.pdf\n",
"\n",
"$\n",
"\\begin{equation}\n",
"\\begin{aligned}\n",
"\\min_{} \\quad & \\sum^{t+T-1}_{j=t} (x_{j} - x_{j,ref})^TQ(x_{j} - x_{j,ref}) + \\sum^{t+T-1}_{j=t+1} u^T_{j}Ru_{j} + (u_{j} - u_{j-1})^T(u_{j} - u_{j-1}) \\\\\n",
"\\textrm{s.t.} \\quad & x(0) = x0\\\\\n",
" & x_{j+1} = Ax_{j}+Bu_{j} \\quad \\textrm{for} \\quad t<j<t+T-1 \\\\\n",
" & u_{MIN} < u_{j} < u_{MAX} \\quad \\textrm{for} \\quad t<j<t+T-1 \\\\\n",
" & \\dot{u}_{MIN} < \\frac{(u_{j} - u_{j-1})}{ts} < \\dot{u}_{MAX} \\quad \\textrm{for} \\quad t+1<j<t+T-1 \\\\\n",
"\\end{aligned}\n",
"\\end{equation}\n",
"$\n",
"\n",
"\n",
"Where R,P,Q are the cost matrices used to tune the response.\n"
]
},
{
"cell_type": "code",
"execution_count": 21,
"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.57e-04s\n",
" 175 1.7545e+02 5.84e-05 5.89e-05 6.89e+00 1.81e-03s\n",
"\n",
"status: solved\n",
"solution polish: unsuccessful\n",
"number of iterations: 175\n",
"optimal objective: 175.4495\n",
"run time: 2.16e-03s\n",
"optimal rho estimate: 6.44e+00\n",
"\n",
"CPU times: user 117 ms, sys: 2 µs, total: 117 ms\n",
"Wall time: 114 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",
"# for t in range(T):\n",
"# if t < (T - 1):\n",
"# constr += [cp.abs(u[0,t] - u[0,t-1])/DT <= MAX_ACC] #max acc\n",
"# constr += [cp.abs(u[1,t] - u[1,t-1])/DT <= 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": 22,
"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,delta_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": 31,
"metadata": {},
"outputs": [
{
"name": "stderr",
"output_type": "stream",
"text": [
"/home/marcello/.conda/envs/jupyter/lib/python3.8/site-packages/cvxpy/problems/problem.py:1054: UserWarning: Solution may be inaccurate. Try another solver, adjusting the solver settings, or solve with verbose=True for more information.\n",
" warnings.warn(\n"
]
},
{
"name": "stdout",
"output_type": "stream",
"text": [
"CVXPY Optimization Time: Avrg: 0.1672s Max: 0.2519s Min: 0.1402s\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 = 200 #time steps\n",
"opt_time=[]\n",
"\n",
"x_sim = np.zeros((N,sim_duration))\n",
"u_sim = np.zeros((M,sim_duration-1))\n",
"\n",
"MAX_SPEED = 1.5 #m/s\n",
"MAX_ACC = 1.0 #m/ss\n",
"MAX_DACC = 1.0 #m/sss\n",
"MAX_STEER = np.radians(30) #rad\n",
"MAX_DSTEER = np.radians(30) #rad/s\n",
"\n",
"REF_VEL = 1.0 #m/s\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.0 #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",
" constr+= [cp.abs(u[0, t + 1] - u[0, t]) <= MAX_DACC * DT] #max acc rate of change\n",
" constr += [cp.abs(u[1, t + 1] - u[1, t]) <= MAX_DSTEER * DT] #max steer rate of change\n",
"\n",
" # Kinrmatics Constrains (Linearized model)\n",
" A,B,C = get_linear_model(x_bar[:,t], u_bar[:,t])\n",
" constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()]\n",
"\n",
" # 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": 33,
"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) [rad]')\n",
"\n",
"plt.subplot(grid[3, 4])\n",
"plt.plot(x_sim[3,:])\n",
"plt.ylabel('theta(t) [rad]')\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## 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
}