mpc_python_learn/notebook/MPC_cte_cvxpy.ipynb

1096 lines
184 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",
"* $\\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": 2,
"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": 3,
"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": 4,
"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": 5,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CPU times: user 3.97 ms, sys: 0 ns, total: 3.97 ms\n",
"Wall time: 3.46 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": 6,
"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": 7,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CPU times: user 1.78 ms, sys: 679 µs, total: 2.46 ms\n",
"Wall time: 1.63 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": 8,
"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": 9,
"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": 10,
"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": 11,
"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.34e-04s\n",
" 125 1.6631e+03 2.07e-05 3.42e-04 7.12e+01 1.30e-03s\n",
"\n",
"status: solved\n",
"solution polish: unsuccessful\n",
"number of iterations: 125\n",
"optimal objective: 1663.1222\n",
"run time: 1.65e-03s\n",
"optimal rho estimate: 7.91e+01\n",
"\n",
"CPU times: user 224 ms, sys: 7.49 ms, total: 232 ms\n",
"Wall time: 223 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",
" cost += 10*cp.sum_squares(x[2,t]-np.arctan(df(x_bar[0,t],K))) # psi\n",
" cost += 500*cp.sum_squares(f(x_bar[0,t],K)-x[1,t]) # cte\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": 12,
"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": 25,
"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.1798s Max: 0.2277s Min: 0.1655s\n"
]
}
],
"source": [
"track = compute_path_from_wp([0,3,4,6,10],\n",
" [0,0,2,4,4])\n",
"\n",
"sim_duration = 50 #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/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",
" cost += 10*cp.sum_squares(x[2,t]-np.arctan(df(x_bar[0,t],K))) # psi\n",
" cost += 50*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], 10*np.eye(M))\n",
" \n",
" # Actuation effort\n",
" cost += cp.quad_form( u[:, t],10*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": 26,
"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
}