mpc_python_learn/notebook/MPC_cte_cvxpy.ipynb

1085 lines
179 KiB
Plaintext

{
"cells": [
{
"cell_type": "code",
"execution_count": 69,
"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",
"* $\\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",
"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",
"* $\\dot{\\psi} = -w$\n",
"* $\\dot{cte} = v\\sin{\\psi}$\n",
"\n",
"The **Continuous** State Space Model is\n",
"\n",
"$ {\\dot{x}} = Ax + Bu $\n",
"\n",
"with:\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} & \\frac{\\partial f(x,u)}{\\partial \\psi} & \\frac{\\partial f(x,u)}{\\partial cte} \\\\\n",
"\\end{bmatrix}\n",
"\\quad\n",
"=\n",
"\\quad\n",
"\\begin{bmatrix}\n",
"0 & 0 & -vsin(\\theta) & 0 & 0 \\\\\n",
"0 & 0 & vcos(\\theta) & 0 & 0 \\\\\n",
"0 & 0 & 0 & 0 & 0 \\\\\n",
"0 & 0 & 0 & 0 & 0 \\\\\n",
"0 & 0 & 0 & vcos(\\psi) & 0 \n",
"\\end{bmatrix}\n",
"\\quad $\n",
"\n",
"\n",
"$ B = \\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} & 0 \\\\\n",
"\\sin{\\theta_t} & 0 \\\\\n",
"0 & 1 \\\\\n",
"0 & -1 \\\\\n",
"\\sin{(\\psi_t)} & 0 \n",
"\\end{bmatrix}\n",
"\\quad $\n",
"\n",
"discretize with forward Euler Integration for time step 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",
"* ${\\psi_{t+1}} = \\psi_{t} - w_t*dt$\n",
"* ${cte_{t+1}} = cte_{t} + v_t\\sin{\\psi}*dt$\n",
"\n",
"The **Discrete** State Space Model is then:\n",
"\n",
"${x_{t+1}} = Ax_t + Bu_t $\n",
"\n",
"with:\n",
"\n",
"$\n",
"A = \\quad\n",
"\\begin{bmatrix}\n",
"1 & 0 & -v\\sin{\\theta}dt & 0 & 0 \\\\\n",
"0 & 1 & v\\cos{\\theta}dt & 0 & 0 \\\\\n",
"0 & 0 & 1 & 0 & 0 \\\\\n",
"0 & 0 & 0 & 1 & 0 \\\\\n",
"0 & 0 & 0 & vcos{(\\psi)}dt & 1 \n",
"\\end{bmatrix}\n",
"\\quad\n",
"$\n",
"\n",
"$\n",
"B = \\quad\n",
"\\begin{bmatrix}\n",
"\\cos{\\theta_t}dt & 0 \\\\\n",
"\\sin{\\theta_t}dt & 0 \\\\\n",
"0 & dt \\\\\n",
"0 & -dt \\\\\n",
"\\sin{\\psi_t}dt & 0 \n",
"\\end{bmatrix}\n",
"\\quad\n",
"$\n",
"\n",
"This State Space Model is **non-linear** (A,B are time changing), to linearize it the **Taylor's series expansion** is used around $\\bar{x}$ and $\\bar{u}$:\n",
"\n",
"$ \\dot{x} = f(x,u) \\approx f(\\bar{x},\\bar{u}) + A(x-\\bar{x}) + B(u-\\bar{u})$\n",
"\n",
"So:\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 Discrete linearized 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}) $"
]
},
{
"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": 70,
"metadata": {},
"outputs": [],
"source": [
"# Control problem statement.\n",
"\n",
"N = 5 #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": 71,
"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",
" psi = x_bar[3]\n",
" cte = x_bar[4]\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[4,3]=v*np.cos(psi)\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[3,1]=-1\n",
" B[4,0]=np.sin(psi)\n",
" B_lin=dt*B\n",
" \n",
" f_xu=np.array([v*np.cos(theta),v*np.sin(theta),w,-w,v*np.sin(-psi)]).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": 72,
"metadata": {},
"outputs": [],
"source": [
"# Define process 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",
" dpsidt = -u[1]\n",
" dctedt = u[0]*np.sin(-x[3])\n",
"\n",
" dqdt = [dxdt,\n",
" dydt,\n",
" dthetadt,\n",
" dpsidt,\n",
" dctedt]\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": 73,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CPU times: user 7 ms, sys: 0 ns, total: 7 ms\n",
"Wall time: 5.8 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",
"x0[3] = 0\n",
"x0[4] = 1\n",
"\n",
"x_bar=predict(x0,u_bar)"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Check the model prediction"
]
},
{
"cell_type": "code",
"execution_count": 74,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 432x288 with 4 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",
"plt.subplot(2, 2, 3)\n",
"plt.plot(np.degrees(x_bar[3,:]))\n",
"plt.ylabel('psi(t) [deg]')\n",
"#plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 4)\n",
"plt.plot(x_bar[4,:])\n",
"plt.ylabel('cte(t)')\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": 75,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CPU times: user 3.28 ms, sys: 461 µs, total: 3.74 ms\n",
"Wall time: 2.68 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",
"x0[3] = 0\n",
"x0[4] = 1\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(5,1)\n",
" ut=u_bar[:,t-1].reshape(2,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": 76,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 432x288 with 4 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(x_bar[2,:])\n",
"plt.ylabel('theta(t)')\n",
"#plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 3)\n",
"plt.plot(x_bar[3,:])\n",
"plt.ylabel('psi(t)')\n",
"#plt.xlabel('time')\n",
"\n",
"plt.subplot(2, 2, 4)\n",
"plt.plot(x_bar[4,:])\n",
"plt.ylabel('cte(t)')\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": 77,
"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<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} $\n",
"\n",
"#### Non-Linear MPC Formulation\n",
"\n",
"In general cases, the objective function is any non-differentiable non-linear function of states and inputs over a finite horizon T. In this case the constrains include nonlinear dynamics of motion.\n",
"\n",
"$\n",
"\\begin{equation}\n",
"\\begin{aligned}\n",
"\\min_{} \\quad & \\sum^{t+T}_{j=t} C(x_{j|t},{j|t})\\\\\n",
"\\textrm{s.t.} \\quad & x(0) = x0\\\\\n",
" & x_{j+1|t} = f(x_{j|t},u_{j|t}) \\quad \\textrm{for} \\quad t<j<t+T-1 \\\\\n",
"\\end{aligned}\n",
"\\end{equation}\n",
"$\n",
"\n",
"Other nonlinear constrains may be applied:\n",
"\n",
"$ g(x_{j|t},{j|t})<0 \\quad \\textrm{for} \\quad t<j<t+T-1 $"
]
},
{
"cell_type": "code",
"execution_count": 106,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"[ 0. 0. 0. -0.17453294 -1.015427 ]\n"
]
}
],
"source": [
"track = compute_path_from_wp([0,5,10],[0,0,2])\n",
"\n",
"# Constrains\n",
"MAX_SPEED = 2.5\n",
"MIN_SPEED = 0.5\n",
"MAX_STEER_SPEED = 1.57/2\n",
"\n",
"# Starting Condition\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = 1\n",
"x0[2] = np.radians(-10)\n",
"\n",
"#X0 is needed ONLY to initialize road curve\n",
"K=road_curve(x0,track)\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.0\n",
"\n",
"# Linearized Model for Prediction##############\n",
"x_bar=np.zeros((N,T+1))\n",
"\n",
"#starting state is 0,0,0,psi,cte\n",
"x_bar[0,0]=0\n",
"x_bar[1,0]=0\n",
"x_bar[2,0]=0\n",
"# x_bar[3,0]=x_bar[2,0]-np.arctan2(df(x_bar[0,0],K),x_bar[0,0])\n",
"x_bar[3,0]=x_bar[2,0]-np.arctan(df(x_bar[0,0],K))\n",
"x_bar[4,0]=f(x_bar[0,0],K)-x_bar[1,0]\n",
"\n",
"print(x_bar[:,0])\n",
"\n",
"for t in range (1,T+1):\n",
" xt=x_bar[:,t-1].reshape(5,1)\n",
" ut=u_bar[:,t-1].reshape(2,1)\n",
" \n",
" A,B,C=get_linear_model(xt,ut)\n",
" \n",
" xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n",
"# xt_plus_one[3]=xt_plus_one[2]-np.arctan2(df(xt_plus_one[0],K),xt_plus_one[0])\n",
" xt_plus_one[3]=xt_plus_one[2]-np.arctan(df(xt_plus_one[0],K))\n",
" xt_plus_one[4]=f(xt_plus_one[0],K)-xt_plus_one[1]\n",
" \n",
" x_bar[:,t]= xt_plus_one\n",
"#################################################\n"
]
},
{
"cell_type": "code",
"execution_count": 107,
"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 = 283, constraints m = 323\n",
" nnz(P) + nnz(A) = 857\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 1.02e+00 1.21e+02 1.00e-01 3.61e-04s\n",
" 125 1.4749e+03 9.83e-06 4.40e-03 7.08e+01 1.50e-03s\n",
"\n",
"status: solved\n",
"solution polish: unsuccessful\n",
"number of iterations: 125\n",
"optimal objective: 1474.8916\n",
"run time: 1.98e-03s\n",
"optimal rho estimate: 1.51e+01\n",
"\n",
"CPU times: user 230 ms, sys: 4.14 ms, total: 234 ms\n",
"Wall time: 230 ms\n"
]
}
],
"source": [
"%%time\n",
"\n",
"x = cp.Variable((N, T+1))\n",
"u = cp.Variable((M, T))\n",
"\n",
"#CVXPY Linear MPC problem statement\n",
"cost = 0\n",
"constr = []\n",
"\n",
"for t in range(T):\n",
" \n",
" # Cost function\n",
" cost += 10*cp.sum_squares( x[3, t]) # psi\n",
" cost += 500*cp.sum_squares( x[4, t]) # cte\n",
" \n",
" # Actuation effort\n",
" cost += cp.quad_form( u[:, t],1*np.eye(M))\n",
" \n",
" # Actuation rate of change\n",
" if t < (T - 1):\n",
" cost += cp.quad_form(u[:, t + 1] - u[:, t], 100*np.eye(M))\n",
" \n",
" # KINEMATICS constrains\n",
" A,B,C=get_linear_model(x_bar[:,t],u_bar[:,t])\n",
" constr += [x[:,t+1] == A*x[:,t] + B*u[:,t] + C.flatten()]\n",
" \n",
"# sums problem objectives and concatenates constraints.\n",
"constr += [x[:,0] == x_bar[:,0]] #<--watch out the start condition\n",
"constr += [u[0, :] <= MAX_SPEED]\n",
"constr += [u[0, :] >= 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": 108,
"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",
"theta_mpc=np.array(x.value[2, :]).flatten()\n",
"psi_mpc=np.array(x.value[3, :]).flatten()\n",
"cte_mpc=np.array(x.value[4, :]).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": 97,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CVXPY Optimization Time: Avrg: 0.1852s Max: 0.2253s Min: 0.1567s\n"
]
}
],
"source": [
"track = compute_path_from_wp([0,3,4,6],\n",
" [0,0,2,1])\n",
"\n",
"sim_duration = 20\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/2\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\n",
" x_bar=np.zeros((N,T+1))\n",
" x_bar[3,0]=x_bar[2,0]-np.arctan2(df(x_bar[0,0],K),x_bar[0,0])\n",
" x_bar[4,0]=f(x_bar[0,0],K)-x_bar[1,0]\n",
" \n",
" #x_bar[:,0]=x_sim[:,sim_time]\n",
" for t in range (1,T+1):\n",
" xt=x_bar[:,t-1].reshape(5,1)\n",
" ut=u_bar[:,t-1].reshape(2,1)\n",
"\n",
" A,B,C=get_linear_model(xt,ut)\n",
"\n",
" xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n",
"\n",
" xt_plus_one[3]=xt_plus_one[2]-np.arctan2(df(xt_plus_one[0],K),xt_plus_one[0])\n",
" xt_plus_one[4]=f(xt_plus_one[0],K)-xt_plus_one[1]\n",
" \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",
" # Tracking\n",
" cost += 10*cp.sum_squares( x[3, t]) # psi\n",
" cost += 50*cp.sum_squares( x[4, t]) # cte\n",
"\n",
" # Actuation rate of change\n",
" if t < (T - 1):\n",
" cost += cp.quad_form(u[:, t + 1] - u[:, t], 10*np.eye(M))\n",
" \n",
" # Actuation effort\n",
" cost += cp.quad_form( u[:, t],1*np.eye(M))\n",
" \n",
" # Constrains\n",
" A,B,C=get_linear_model(x_bar[:,t],u_bar[:,t])\n",
" constr += [x[:,t+1] == A*x[:,t] + B*u[:,t] + C.flatten()]\n",
"\n",
" # sums problem objectives and concatenates constraints.\n",
" constr += [x[:,0] == x_bar[:,0]] #<--watch out the start condition\n",
" constr += [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": 98,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 1080x720 with 3 Axes>"
]
},
"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
}