mpc_python_learn/notebook/MPC_cte_cvxpy.ipynb

1031 lines
126 KiB
Plaintext

{
"cells": [
{
"cell_type": "code",
"execution_count": 138,
"metadata": {},
"outputs": [],
"source": [
"import numpy as np\n",
"from scipy.integrate import odeint\n",
"from scipy.interpolate import interp1d\n",
"import cvxpy as cp\n",
"\n",
"import matplotlib.pyplot as plt\n",
"plt.style.use(\"ggplot\")\n",
"\n",
"import time"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"### kinematics model equations\n",
"\n",
"The variables of the model are:\n",
"\n",
"* $x$ coordinate of the robot\n",
"* $y$ coordinate of the robot\n",
"* $\\theta$ heading of the robot\n",
"\n",
"The inputs of the model are:\n",
"\n",
"* $v$ linear velocity of the robot\n",
"* $w$ angular velocity of the robot\n",
"\n",
"These are the differential equations f(x,u) of the model:\n",
"\n",
"* $\\dot{x} = v\\cos{\\theta}$ \n",
"* $\\dot{y} = v\\sin{\\theta}$\n",
"* $\\dot{\\theta} = w$\n",
"\n",
"Discretize with forward Euler Integration for time step dt:\n",
"\n",
"${x_{t+1}} = x_{t} + f(x,u)*dt$\n",
"\n",
"* ${x_{t+1}} = x_{t} + v_t\\cos{\\theta}*dt$\n",
"* ${y_{t+1}} = y_{t} + v_t\\sin{\\theta}*dt$\n",
"* ${\\theta_{t+1}} = \\theta_{t} + w_t*dt$\n",
"\n",
"----------------------\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 \\theta} \\\\\n",
"\\end{bmatrix}\n",
"\\quad\n",
"=\n",
"\\quad\n",
"\\begin{bmatrix}\n",
"0 & 0 & -v\\sin{\\theta} \\\\\n",
"0 & 0 & v\\cos{\\theta} \\\\\n",
"0 & 0 & 0\\\\\n",
"\\end{bmatrix}\n",
"\\quad\n",
"$\n",
"\n",
"and\n",
"\n",
"$\n",
"B = \n",
"\\quad\n",
"\\begin{bmatrix}\n",
"\\frac{\\partial f(x,u)}{\\partial v} & \\frac{\\partial f(x,u)}{\\partial w} \\\\\n",
"\\end{bmatrix}\n",
"\\quad\n",
"= \n",
"\\quad\n",
"\\begin{bmatrix}\n",
"\\cos{\\theta} & 0 \\\\\n",
"\\sin{\\theta} & 0 \\\\\n",
"0 & 1\n",
"\\end{bmatrix}\n",
"\\quad\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}) $\n",
"\n",
"**Errors** are:\n",
"* $\\psi$ heading error = $\\psi = \\theta_{ref} - \\theta$\n",
"* $cte$ crosstrack error = lateral distance of the robot from the track w.r.t robot frame, cte is a function of the track and x\n",
"\n",
"described by:"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"-----------------\n",
"[About Taylor Series Expansion](https://courses.engr.illinois.edu/ece486/fa2017/documents/lecture_notes/state_space_p2.pdf):\n",
"\n",
"In order to linearize general nonlinear systems, we will use the Taylor Series expansion of functions.\n",
"\n",
"Typically it is possible to assume that the system is operating about some nominal\n",
"state solution $\\bar{x}$ (possibly requires a nominal input $\\bar{u}$) called **equilibrium point**.\n",
"\n",
"Recall that the Taylor Series expansion of f(x) around the\n",
"point $\\bar{x}$ is given by:\n",
"\n",
"$f(x)=f(\\bar{x}) + \\frac{df(x)}{dx}|_{x=\\bar{x}}(x-\\bar{x})$ + higher order terms...\n",
"\n",
"For x sufficiently close to $\\bar{x}$, these higher order terms will be very close to zero, and so we can drop them.\n",
"\n",
"The extension to functions of multiple states and inputs is very similar to the above procedure.Suppose the evolution of state x\n",
"is given by:\n",
"\n",
"$\\dot{x} = f(x1, x2, . . . , xn, u1, u2, . . . , um) = Ax+Bu$\n",
"\n",
"Where:\n",
"\n",
"$ A =\n",
"\\quad\n",
"\\begin{bmatrix}\n",
"\\frac{\\partial f(x,u)}{\\partial x1} & ... & \\frac{\\partial f(x,u)}{\\partial xn} \\\\\n",
"\\end{bmatrix}\n",
"\\quad\n",
"$ and $ B = \\quad\n",
"\\begin{bmatrix}\n",
"\\frac{\\partial f(x,u)}{\\partial u1} & ... & \\frac{\\partial f(x,u)}{\\partial um} \\\\\n",
"\\end{bmatrix}\n",
"\\quad $\n",
"\n",
"Then:\n",
"\n",
"$f(x,u)=f(\\bar{x},\\bar{u}) + \\frac{df(x,u)}{dx}|_{x=\\bar{x}}(x-\\bar{x}) + \\frac{df(x,u)}{du}|_{u=\\bar{u}}(u-\\bar{u}) = f(\\bar{x},\\bar{u}) + A_{x=\\bar{x}}(x-\\bar{x}) + B_{u=\\bar{u}}(u-\\bar{u})$\n",
"\n",
"-----------------"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"### Kinematics Model"
]
},
{
"cell_type": "code",
"execution_count": 139,
"metadata": {},
"outputs": [],
"source": [
"# Control problem statement.\n",
"\n",
"N = 3 #number of state variables\n",
"M = 2 #number of control variables\n",
"T = 20 #Prediction Horizon\n",
"dt = 0.25 #discretization step"
]
},
{
"cell_type": "code",
"execution_count": 140,
"metadata": {},
"outputs": [],
"source": [
"def get_linear_model(x_bar,u_bar):\n",
" \"\"\"\n",
" \"\"\"\n",
" \n",
" x = x_bar[0]\n",
" y = x_bar[1]\n",
" theta = x_bar[2]\n",
" \n",
" v = u_bar[0]\n",
" w = u_bar[1]\n",
" \n",
" A = np.zeros((N,N))\n",
" A[0,2]=-v*np.sin(theta)\n",
" A[1,2]=v*np.cos(theta)\n",
" A_lin=np.eye(N)+dt*A\n",
" \n",
" B = np.zeros((N,M))\n",
" B[0,0]=np.cos(theta)\n",
" B[1,0]=np.sin(theta)\n",
" B[2,1]=1\n",
" B_lin=dt*B\n",
" \n",
" f_xu=np.array([v*np.cos(theta),v*np.sin(theta),w]).reshape(N,1)\n",
" C_lin = dt*(f_xu - np.dot(A,x_bar.reshape(N,1)) - np.dot(B,u_bar.reshape(M,1)))\n",
" \n",
" return A_lin,B_lin,C_lin"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Motion Prediction: using scipy intergration"
]
},
{
"cell_type": "code",
"execution_count": 141,
"metadata": {},
"outputs": [],
"source": [
"# Define process model\n",
"# This uses the continuous model \n",
"def kinematics_model(x,t,u):\n",
" \"\"\"\n",
" \"\"\"\n",
"\n",
" dxdt = u[0]*np.cos(x[2])\n",
" dydt = u[0]*np.sin(x[2])\n",
" dthetadt = u[1]\n",
"\n",
" dqdt = [dxdt,\n",
" dydt,\n",
" dthetadt]\n",
"\n",
" return dqdt\n",
"\n",
"def predict(x0,u):\n",
" \"\"\"\n",
" \"\"\"\n",
" \n",
" x_bar = np.zeros((N,T+1))\n",
" \n",
" x_bar[:,0] = x0\n",
" \n",
" # solve ODE\n",
" for t in range(1,T+1):\n",
"\n",
" tspan = [0,dt]\n",
" x_next = odeint(kinematics_model,\n",
" x0,\n",
" tspan,\n",
" args=(u[:,t-1],))\n",
"\n",
" x0 = x_next[1]\n",
" x_bar[:,t]=x_next[1]\n",
" \n",
" return x_bar"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Validate the model, here the status w.r.t a straight line with constant heading 0"
]
},
{
"cell_type": "code",
"execution_count": 142,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CPU times: user 6.71 ms, sys: 0 ns, total: 6.71 ms\n",
"Wall time: 5.35 ms\n"
]
}
],
"source": [
"%%time\n",
"\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:] = 1 #m/s\n",
"u_bar[1,:] = np.radians(-10) #rad/s\n",
"\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = 1\n",
"x0[2] = np.radians(0)\n",
"\n",
"x_bar=predict(x0,u_bar)"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Check the model prediction"
]
},
{
"cell_type": "code",
"execution_count": 143,
"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": 144,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CPU times: user 2.28 ms, sys: 0 ns, total: 2.28 ms\n",
"Wall time: 1.55 ms\n"
]
}
],
"source": [
"%%time\n",
"\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:] = 1 #m/s\n",
"u_bar[1,:] = np.radians(-10) #rad/s\n",
"\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = 1\n",
"x0[2] = np.radians(0)\n",
"\n",
"x_bar=np.zeros((N,T+1))\n",
"x_bar[:,0]=x0\n",
"\n",
"for t in range (1,T+1):\n",
" xt=x_bar[:,t-1].reshape(N,1)\n",
" ut=u_bar[:,t-1].reshape(M,1)\n",
" \n",
" A,B,C=get_linear_model(xt,ut)\n",
" \n",
" xt_plus_one = np.dot(A,xt)+np.dot(B,ut)+C\n",
" \n",
" x_bar[:,t]= np.squeeze(xt_plus_one)"
]
},
{
"cell_type": "code",
"execution_count": 145,
"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": [
"------------------\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": 146,
"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)-1\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 f(x,coeff):\n",
"# return round(coeff[0]*x**5+coeff[1]*x**4+coeff[2]*x**3+coeff[3]*x**2+coeff[4]*x**1+coeff[5]*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)\n",
"# def df(x,coeff):\n",
"# return round(5*coeff[0]*x**4 + 4*coeff[1]*x**3 +3*coeff[2]*x**2 + 2*coeff[3]*x**1 + coeff[4]*x**0,6)"
]
},
{
"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": 147,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"[0. 0. 0.]\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",
"\n",
"\n",
"print(x_bar[:,0])\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.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n",
" x_bar[:,t]= xt_plus_one\n",
"#################################################\n"
]
},
{
"cell_type": "code",
"execution_count": 148,
"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 = 241, constraints m = 281\n",
" nnz(P) + nnz(A) = 715\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.02e+02 1.00e-01 2.28e-04s\n",
" 125 1.6631e+03 2.07e-05 3.42e-04 7.12e+01 9.98e-04s\n",
"\n",
"status: solved\n",
"solution polish: unsuccessful\n",
"number of iterations: 125\n",
"optimal objective: 1663.1222\n",
"run time: 1.17e-03s\n",
"optimal rho estimate: 7.91e+01\n",
"\n",
"CPU times: user 196 ms, sys: 90 µs, total: 196 ms\n",
"Wall time: 194 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": 149,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 432x288 with 2 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",
"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": 162,
"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",
"/home/marcello/.local/lib/python3.6/site-packages/ipykernel_launcher.py:33: RankWarning: Polyfit may be poorly conditioned\n",
"/home/marcello/.local/lib/python3.6/site-packages/ipykernel_launcher.py:33: RankWarning: Polyfit may be poorly conditioned\n"
]
},
{
"name": "stdout",
"output_type": "stream",
"text": [
"CVXPY Optimization Time: Avrg: 0.1697s Max: 0.2498s Min: 0.1575s\n"
]
},
{
"name": "stderr",
"output_type": "stream",
"text": [
"/home/marcello/.local/lib/python3.6/site-packages/ipykernel_launcher.py:33: RankWarning: Polyfit may be poorly conditioned\n"
]
}
],
"source": [
"track = compute_path_from_wp([0,3,4,6,10,13],\n",
" [0,0,2,4,3,3],0.25)\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",
" K=road_curve(x_sim[:,sim_time],track)\n",
" \n",
" # dynamics starting state w.r.t vehicle frame\n",
" x_bar=np.zeros((N,T+1))\n",
" \n",
" #prediction for linearization of costrains\n",
" for t in range (1,T+1):\n",
" xt=x_bar[:,t-1].reshape(N,1)\n",
" ut=u_bar[:,t-1].reshape(M,1)\n",
" A,B,C=get_linear_model(xt,ut)\n",
" xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n",
" x_bar[:,t]= xt_plus_one\n",
" \n",
" #CVXPY Linear MPC problem statement\n",
" cost = 0\n",
" constr = []\n",
" x = cp.Variable((N, T+1))\n",
" u = cp.Variable((M, T))\n",
" \n",
" for t in range(T):\n",
"\n",
" #cost += 30*cp.sum_squares(x[2,t]-np.arctan(df(x_bar[0,t],K))) # psi\n",
" cost += 50*cp.sum_squares(x[2,t]-np.arctan2(df(x_bar[0,t],K),x_bar[0,t])) # psi\n",
" cost += 20*cp.sum_squares(f(x_bar[0,t],K)-x[1,t]) # cte\n",
"\n",
" # Actuation rate of change\n",
" if t < (T - 1):\n",
" cost += cp.quad_form(u[:, t + 1] - u[:, t], 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",
" # 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": 163,
"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
}