mpc_python_learn/notebooks/MPC_racecar_crosstrack-Copy...

1226 lines
185 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$ angular velocity of the robot\n",
"\n",
"These are the differential equations f(x,u) of the model:\n",
"\n",
"$\\dot{x} = f(x,u)$\n",
"\n",
"* $\\dot{x} = v\\cos{\\theta}$ \n",
"* $\\dot{y} = v\\sin{\\theta}$\n",
"* $\\dot{v} = a$\n",
"* $\\dot{\\theta} = \\frac{v\\tan{\\delta}}{L}$\n",
"\n",
"Discretize with forward Euler Integration for time step dt:\n",
"\n",
"${x_{t+1}} = x_{t} + f(x,u)dt$\n",
"\n",
"* ${x_{t+1}} = x_{t} + v_t\\cos{\\theta}dt$\n",
"* ${y_{t+1}} = y_{t} + v_t\\sin{\\theta}dt$\n",
"* ${v_{t+1}} = v_{t} + a_tdt$\n",
"* ${\\theta_{t+1}} = \\theta_{t} + \\frac{v\\tan{\\delta}}{L} dt$\n",
"\n",
"----------------------\n",
"\n",
"The Model is **non-linear** and **time variant**, but the Numerical Optimizer requires a Linear sets of equations. To approximate the equivalent **LTI** State space model, the **Taylor's series expansion** is used around $\\bar{x}$ and $\\bar{u}$ (at each time step):\n",
"\n",
"$ f(x,u) \\approx f(\\bar{x},\\bar{u}) + \\frac{\\partial f(x,u)}{\\partial x}|_{x=\\bar{x},u=\\bar{u}}(x-\\bar{x}) + \\frac{\\partial f(x,u)}{\\partial u}|_{x=\\bar{x},u=\\bar{u}}(u-\\bar{u})$\n",
"\n",
"This can be rewritten usibg the State Space model form Ax+Bu :\n",
"\n",
"$ f(\\bar{x},\\bar{u}) + A|_{x=\\bar{x},u=\\bar{u}}(x-\\bar{x}) + B|_{x=\\bar{x},u=\\bar{u}}(u-\\bar{u})$\n",
"\n",
"Where:\n",
"\n",
"$\n",
"A =\n",
"\\quad\n",
"\\begin{bmatrix}\n",
"\\frac{\\partial f(x,u)}{\\partial x} & \\frac{\\partial f(x,u)}{\\partial y} & \\frac{\\partial f(x,u)}{\\partial v} & \\frac{\\partial f(x,u)}{\\partial \\theta} \\\\\n",
"\\end{bmatrix}\n",
"\\quad\n",
"=\n",
"\\displaystyle \\left[\\begin{matrix}0 & 0 & \\cos{\\left(\\theta \\right)} & - v \\sin{\\left(\\theta \\right)}\\\\0 & 0 & \\sin{\\left(\\theta \\right)} & v \\cos{\\left(\\theta \\right)}\\\\0 & 0 & 0 & 0\\\\0 & 0 & \\frac{\\tan{\\left(\\delta \\right)}}{L} & 0\\end{matrix}\\right]\n",
"$\n",
"\n",
"and\n",
"\n",
"$\n",
"B = \n",
"\\quad\n",
"\\begin{bmatrix}\n",
"\\frac{\\partial f(x,u)}{\\partial a} & \\frac{\\partial f(x,u)}{\\partial \\delta} \\\\\n",
"\\end{bmatrix}\n",
"\\quad\n",
"= \n",
"\\displaystyle \\left[\\begin{matrix}0 & 0\\\\0 & 0\\\\1 & 0\\\\0 & \\frac{v \\left(\\tan^{2}{\\left(\\delta \\right)} + 1\\right)}{L}\\end{matrix}\\right]\n",
"$\n",
"\n",
"are the *Jacobians*.\n",
"\n",
"\n",
"\n",
"So the discretized model is given by:\n",
"\n",
"$ x_{t+1} = x_t + (f(\\bar{x},\\bar{u}) + A|_{x=\\bar{x}}(x_t-\\bar{x}) + B|_{u=\\bar{u}}(u_t-\\bar{u}) )dt $\n",
"\n",
"$ x_{t+1} = (I+dtA)x_t + dtBu_t +dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\bar{u}))$\n",
"\n",
"The LTI-equivalent kinematics model is:\n",
"\n",
"$ x_{t+1} = A'x_t + B' u_t + C' $\n",
"\n",
"with:\n",
"\n",
"$ A' = I+dtA|_{x=\\bar{x},u=\\bar{u}} $\n",
"\n",
"$ B' = dtB|_{x=\\bar{x},u=\\bar{u}} $\n",
"\n",
"$ C' = dt(f(\\bar{x},\\bar{u}) - A|_{x=\\bar{x},u=\\bar{u}}\\bar{x} - B|_{x=\\bar{x},u=\\bar{u}}\\bar{u}) $"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"-----------------\n",
"[About Taylor Series Expansion](https://courses.engr.illinois.edu/ece486/fa2017/documents/lecture_notes/state_space_p2.pdf):\n",
"\n",
"In order to linearize general nonlinear systems, we will use the Taylor Series expansion of functions.\n",
"\n",
"Typically it is possible to assume that the system is operating about some nominal\n",
"state solution $\\bar{x}$ (possibly requires a nominal input $\\bar{u}$) called **equilibrium point**.\n",
"\n",
"Recall that the Taylor Series expansion of f(x) around the\n",
"point $\\bar{x}$ is given by:\n",
"\n",
"$f(x)=f(\\bar{x}) + \\frac{df(x)}{dx}|_{x=\\bar{x}}(x-\\bar{x})$ + higher order terms...\n",
"\n",
"For x sufficiently close to $\\bar{x}$, these higher order terms will be very close to zero, and so we can drop them.\n",
"\n",
"The extension to functions of multiple states and inputs is very similar to the above procedure.Suppose the evolution of state x\n",
"is given by:\n",
"\n",
"$\\dot{x} = f(x1, x2, . . . , xn, u1, u2, . . . , um) = Ax+Bu$\n",
"\n",
"Where:\n",
"\n",
"$ A =\n",
"\\quad\n",
"\\begin{bmatrix}\n",
"\\frac{\\partial f(x,u)}{\\partial x1} & ... & \\frac{\\partial f(x,u)}{\\partial xn} \\\\\n",
"\\end{bmatrix}\n",
"\\quad\n",
"$ and $ B = \\quad\n",
"\\begin{bmatrix}\n",
"\\frac{\\partial f(x,u)}{\\partial u1} & ... & \\frac{\\partial f(x,u)}{\\partial um} \\\\\n",
"\\end{bmatrix}\n",
"\\quad $\n",
"\n",
"Then:\n",
"\n",
"$f(x,u)=f(\\bar{x},\\bar{u}) + \\frac{df(x,u)}{dx}|_{x=\\bar{x}}(x-\\bar{x}) + \\frac{df(x,u)}{du}|_{u=\\bar{u}}(u-\\bar{u}) = f(\\bar{x},\\bar{u}) + A_{x=\\bar{x}}(x-\\bar{x}) + B_{u=\\bar{u}}(u-\\bar{u})$\n",
"\n",
"-----------------"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"### Kinematics Model"
]
},
{
"cell_type": "code",
"execution_count": 2,
"metadata": {},
"outputs": [],
"source": [
"\"\"\"\n",
"Control problem statement.\n",
"\"\"\"\n",
"\n",
"N = 4 #number of state variables\n",
"M = 2 #number of control variables\n",
"T = 20 #Prediction Horizon\n",
"dt = 0.25 #discretization step"
]
},
{
"cell_type": "code",
"execution_count": 3,
"metadata": {},
"outputs": [],
"source": [
"def get_linear_model(x_bar,u_bar):\n",
" \"\"\"\n",
" Computes the LTI approximated state space model x' = Ax + Bu + C\n",
" \"\"\"\n",
" \n",
" L=0.3 #vehicle wheelbase\n",
" \n",
" x = x_bar[0]\n",
" y = x_bar[1]\n",
" v = x_bar[2]\n",
" theta = x_bar[3]\n",
" \n",
" a = u_bar[0]\n",
" delta = u_bar[1]\n",
" \n",
" A = np.zeros((N,N))\n",
" A[0,2]=np.cos(theta)\n",
" A[0,3]=-v*np.sin(theta)\n",
" A[1,2]=np.sin(theta)\n",
" A[1,3]=v*np.cos(theta)\n",
" A[3,2]=v*np.tan(delta)/L\n",
" A_lin=np.eye(N)+dt*A\n",
" \n",
" B = np.zeros((N,M))\n",
" B[2,0]=1\n",
" B[3,1]=v/(L*np.cos(delta)**2)\n",
" B_lin=dt*B\n",
" \n",
" f_xu=np.array([v*np.cos(theta), v*np.sin(theta), a,v*np.tan(delta)/L]).reshape(N,1)\n",
" C_lin = dt*(f_xu - np.dot(A,x_bar.reshape(N,1)) - np.dot(B,u_bar.reshape(M,1)))\n",
" \n",
" return np.round(A_lin,4), np.round(B_lin,4), np.round(C_lin,4)"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Motion Prediction: using scipy intergration"
]
},
{
"cell_type": "code",
"execution_count": 4,
"metadata": {},
"outputs": [],
"source": [
"# Define process model\n",
"# This uses the continuous model \n",
"def kinematics_model(x,t,u):\n",
" \"\"\"\n",
" Returns the set of ODE of the vehicle model.\n",
" \"\"\"\n",
" \n",
" L=0.3 #vehicle wheelbase\n",
" dxdt = x[2]*np.cos(x[3])\n",
" dydt = x[2]*np.sin(x[3])\n",
" dvdt = u[0]\n",
" dthetadt = x[2]*np.tan(u[1])/L\n",
"\n",
" dqdt = [dxdt,\n",
" dydt,\n",
" dvdt,\n",
" dthetadt]\n",
"\n",
" return dqdt\n",
"\n",
"def predict(x0,u):\n",
" \"\"\"\n",
" \"\"\"\n",
" \n",
" x_ = np.zeros((N,T+1))\n",
" \n",
" x_[:,0] = x0\n",
" \n",
" # solve ODE\n",
" for t in range(1,T+1):\n",
"\n",
" tspan = [0,dt]\n",
" x_next = odeint(kinematics_model,\n",
" x0,\n",
" tspan,\n",
" args=(u[:,t-1],))\n",
"\n",
" x0 = x_next[1]\n",
" x_[:,t]=x_next[1]\n",
" \n",
" return x_"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Validate the model, here the status w.r.t a straight line with constant heading 0"
]
},
{
"cell_type": "code",
"execution_count": 5,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CPU times: user 3.66 ms, sys: 83 µs, total: 3.74 ms\n",
"Wall time: 3.22 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 1.95 ms, sys: 4.06 ms, total: 6.01 ms\n",
"Wall time: 1.77 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": "iVBORw0KGgoAAAANSUhEUgAAAagAAAChCAYAAACSyiu8AAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAADh0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uMy4yLjIsIGh0dHA6Ly9tYXRwbG90bGliLm9yZy+WH4yJAAAgAElEQVR4nO3deXxU5dn/8c99spCEkGRIgkgQJIAKFC2YlLpgCgk8imCj9UFBQAiWKgIVWir0p4gPRtGaRsPqEtnUR7BIFEutjZSA5aENm0BQtiKiCCE72chy7t8fU1JoErKQmXMmud6vV15m5pw5853jYa6c7b6U1lojhBBC2IxhdQAhhBCiLlKghBBC2JIUKCGEELYkBUoIIYQtSYESQghhS1KghBBC2JK31QGEEM1XUlLC8uXLOXnyJEopHnvsMbp06UJycjJnz54lPDycmTNnEhgYaHVUIZpMyX1QQniuxYsX06dPH2JjY6mqquL8+fNs2LCBwMBA4uPjSUtLo7i4mHHjxlkdVYgmk0N8Qnio0tJSvvzyS4YOHQqAt7c37du3JzMzk5iYGABiYmLIzMy0MqYQzSaH+ITwUNnZ2QQFBbF06VJOnDhBZGQkEydOpLCwEIfDAYDD4aCoqMjipEI0j632oEzT5De/+Q0LFy60OooQtlddXc3x48cZPnw4L730Eu3atSMtLa3Rr09PT2fOnDnMmTPHhSmFaD5b7UFt2rSJiIgIysrKGjX/qVOn6nw+LCyMnJyclox2xeyWSfI07HKZunTp4uY0tYWGhhIaGkrv3r0B+PGPf0xaWhrBwcHk5+fjcDjIz88nKCioztfHxcURFxdX89hT/j3ZLQ/YL5On5anv35Nt9qByc3PZvXs3sbGxVkcRwiOEhIQQGhpaU1j2799P165diYqKIiMjA4CMjAyio6OtjClEs9lmD2rlypWMGzfusntP6enppKenA7Bw4ULCwsLqnM/b27veaVaxWybJ0zA7ZvpPCQkJpKSkUFVVRadOnZg6dSpaa5KTk9m8eTNhYWHMmjXL6piijTNLS5r1OlsUqF27dhEcHExkZCRZWVn1zvefhyTq22W02+4t2C+T5GmY3Q/xAVx77bV1nrOdN2+eBWmEuJSurERv/F9yt38GT7+CCnY06fW2KFCHDh1i586d7Nmzh4qKCsrKykhJSWHGjBlWRxNCCNEM+uRxzLeS4duvaTf0bip8fJu8DFsUqLFjxzJ27FgAsrKy2LhxoxQnIYTwQLq6Gv3JevTG96B9IMa0pwiOHdGsIyS2KFBCCCE8nz79LeZbr8Dxw6io21EPPYoKrPsq0sawXYHq168f/fr1szqGEEKIRtKmid78MfqD1eDbDjVlNkb04Cteru0KlBBCCM+hc85grkyBQ/uhfxTGhGmokI4tsmwpUEIIIZpMa43+/C/otamgQD08HXVbHEqpFnsPKVBCCCGaRBfkYq5eAvt3wvX9MSb9EhXaqcXfRwqUEEKIRtFaozO3od9ZDlUVqAenoIaMQBmuGZRICpQQQogG6XNF6HeWoXf9DSKvx5j0BKpzhEvfUwqUEEKIy9J7/465ejGUlqDum4Aafi/Ky8vl7ysFSgghRJ10aQl67Zvo7Z9B12sxZv4P6poebnt/KVBCCCFq0Qf3Yq5Kgfw81IjRqFEPoLx93JpBCpQQQoga+nw5ev1K9F83QecIjDkvoiKvtySLFCghhBAA6KMHnUMVnT2NirsHde94lG87y/JIgRJCiDZOV1agP3wX/ekG6BiO8etE1PX9rY4lBUoIIdoyfeKYsy3GqW9Qg4ejRieg/AKsjgVIgRJCiDZJV1Wh//QH9B/XQmAwxoxnUP1vtjrWJaRACSFEG6NPfeM813TiKGpQDGrMFFT7DlbHqkUKlBBCtBHarEanb0RvWAN+fhiPPom6+TarY9VLCpQQQrQB+uxpzBWvwJGDcNOPMCY8jgpyWB3rsqRACSFEK6a1Rm/9M/r9t8AwUJOeQN0ypEXbYriKFCghhGildF4O5qpFcHAP9LkJY+IMVMdwq2M1mhQoIYRoZbTWmDv+in73daiuQj30KCrmLo/Ya7qYFCghhGhFdFEBham/R+/YAr36OJsJdupidaxmsUWBysnJYcmSJRQUFKCUIi4ujhEjRlgdSwghPIre/X+Yby/lfFkp6v5JqGH3oAzXt8VwFVsUKC8vL8aPH09kZCRlZWXMmTOHG2+8ka5du1odTQghbE+XFKPfe92519StJ6HPPUtBQJDVsa6YLQqUw+HA4XBe7ujv709ERAR5eXlSoIRogGmazJkzh44dOzJnzhyKi4tJTk7m7NmzhIeHM3PmTAIDA62OKVxIH9jtvBCiKB816kHUiNF4d+4MOTlWR7tirmkkfwWys7M5fvw4vXr1sjqKELa3adMmIiL+3XY7LS2N/v37k5KSQv/+/UlLS7MwnXAlXV6G+fZSzFfng38Axm9fxrhnLMrbFvsdLcJWn6S8vJykpCQmTpxIQEDtwQrT09NJT08HYOHChYSFhdW5HG9v73qnWcVumSRPw+yY6WK5ubns3r2b++67j48//hiAzMxM5s+fD0BMTAzz589n3LhxFqYUrqAPZ2GufBVyzjjbr8c/hPLxtTpWi7NNgaqqqiIpKYnBgwczaNCgOueJi4sjLi6u5nFOPbuwYWFh9U6zit0ySZ6GXS5Tly7NvyqqqKiIrVu3snv3bk6cOEFpaSkBAQF0796dH/7wh/zkJz8hKKjh8wcrV65k3LhxlJWV1TxXWFhYc7jc4XBQVFTU7JzCfnRlBTrtbfRfPoSwqzBmv4Dq3dfqWC5jiwKltWb58uVEREQwcuRIq+MI4TLvvvsu27ZtY8CAAQwdOpSIiAj8/f0pKyvju+++4+DBgzz55JPcfvvtPPTQQ/UuZ9euXQQHBxMZGUlWVlazsnjqEQm75QH3ZKo8+iWFry7A/PZr/O+8l8AJj2P4190Ww27rqLl5bFGgDh06xNatW+nWrRuzZ88GYMyYMQwcONDiZEK0LIfDQUpKCj4+PrWm9ejRg9tvv52Kigo2b9582eUcOnSInTt3smfPHioqKigrKyMlJYXg4GDy8/NxOBzk5+dfdk/MU49I2C0PuDaTrqpC/3EdetM6CHJgPPEsFf0GkFdSCiWlbs/THA3lqe+IhC0K1A033MC6deusjiGEy9111101vxcUFBASElJrntLSUu68887LLmfs2LGMHTsWgKysLDZu3MiMGTNYs2YNGRkZxMfHk5GRQXR0dMt+AOFW+rsTzmaC3/zTOX7egz9HBbSdqzJtdxWfEG3FL3/5yzqfnzlzZrOXGR8fz759+5gxYwb79u0jPj6+2csS1tFmNeYn6zGfmwn5uRhTf4uRMLNNFSewyR6UEG2R1rrWc6WlpRhG0/5u7NevH/369QOgQ4cOzJs3r0XyCWvo7FPOZoLHvoKBt2CMm4rqEGx1LEtIgRLCzR577DEAKioqan6/oLi4mNtus28DOeE62jTRGX9C/2EleHujHvkV6kd3eNwAry1JCpQQbjZ9+nS01rzwwgtMnz79kmkhISFXdAm78Ew69yzmqhT48gv4wUCMCdNRjlCrY1lOCpQQbta3r/O+ldTUVNq1a2dxGmElrTV6+2b02jfA1Kjxj6MGD2/Te00Xk4skhHCjTZs2UVlZCVBvcaqsrGTTpk3ujCUsoAvzMZckole+CtdEYjzzKsYd/yXF6SKyByWEGxUUFDBjxgwGDBhA37596dKlC35+fpSXl3Pq1CkOHjzInj17iImJsTqqcCG983PMd5bB+fOoByajho5CNfHimLZACpQQbjR27FhGjhzJli1b2Lx5M9988w0lJSUEBgbSrVs3BgwYwJgxY+jQoYPVUYUL6JJz6HeWozO3QY/rMCY9gbpaujbUp9UVKPP//kpB1i6qKyqcTyjD+ZeJYYDhBV5e4O0N3j7OHx9f8PEBX1/wbQft/FHtnP/FLwD8/cG/PQS0b5WDMQr3CwoK4p577uGee+6xOopwI70vE3P1YiguQsWPQ935M5SX5zYTdIdWV6AoKaL69HdQVeV8rDXarAbThOrqf/1UOadXVkBVZa1F1L475V+8faB9BwhoD4EdIDAIFRgEgUEQFAIdglFBIRDSEYId4N9ejicL0cbpslL0ulT053+BiO4YM55BdYu0OpZHaHUFyoj7KaEPTm70OFRaa2eRqqiA8+VQUe78b3k5lJehy0uhrARKL/wUo0vOQUkxZH+PPvYVFBc5CyD/Udx8fFH/nYAxRNrXi9pKS0t5//33OXjwIOfOnbvkxt1ly5ZZmEy0FP3VPsyVKZCXg7rrftSoMag6xmEUdWt1BaqplFL/OsznC+1rDyPSmP0fbZpQWgznCqEwH12YD4V5UJiPiujW8qFFq/Dmm2+Sl5fH/fffz6JFi5g+fTofffRRve1mhOfQ58+jN6xGf7YROnXBeHIhqucNVsfyOG2+QLUEZRjOw3yBQXD1NY0qakLs27eP5ORkOnTogGEYREdH07NnT1588UVpO+PB9LGvMFe8Cme+Q8WOQt07wXleWzSZFCghLKK1rukc7efnR0lJCSEhIZw+fdriZKI5dGUl+uP30H9aD45QjFkLUH1usjqWR2t0gVq1ahUxMTFce+21LowjRNvRvXt3Dh48SP/+/bnhhhtITU3Fz8+Pq6++2upoookqjx/B/P0z8O3XqNviUKMnowLaWx3L4zW6QFVXV5OYmEhQUBCDBw9m8ODBhIbKWFFCNNcvfvGLmgsjEhISePfddykpKWHatGkWJxONpaur0Z+sJ+/j96B9B4xpT6Nukh5cLaXRBSohIYGJEyeyZ88etm3bxgcffEDv3r254447GDRoEH5+fq7MKUSrU1RURO/evQHnvVGPPvooAEePHrUylmgk/f23mCtegeOHaXd7LJU/m+S87US0mCaNrWEYBjfffDNPPPEEiYmJFBUVsXTpUn7+85+zfPly8vLyXJVTiFbnueeeq/P5xMRENycRTaFNEzP9I8wFT0D296gpswn51QIpTi7QpIskSktL2bFjB9u2bePEiRMMGjSIyZMnExYWxscff8zzzz/Pyy+/7KqsQrQK5oV75rSu+bngzJkzeMnoAralc84472s6tB/6R2FMmIYK6Wh1rFar0QUqKSmJL774gj59+jBs2DCio6PxueiGswkTJjBx4kRXZBSiVRkzZkzN7w8++OAl0wzD4N5773V3JNEArTX687+g16aCAvXwdOfFEDJSjEs1ukD17t2byZMnExISUud0wzB44403mh1k7969rFixAtM0iY2NJT4+vtnLEsLOFi9ejNaa+fPn8+yzz6K1RimFUoqgoCB8fWXMRzvRBbmYq5fA/p1wfX+MSb9EhXayOlab0OgC1ZiBLZvbfM00TVJTU3nqqacIDQ1l7ty5REVF0bWrjPIrWp/w8HAAli5dCji3/8LCQhwOh5WxxH/QWqP/sRX97mtQVYF6cApqyAhpi+FGtrhR9+jRo3Tu3JmrrroKgFtvvZXMzEwpUKJVKykp4c0332THjh14e3uzZs0adu7cydGjR2sd+hPupc8VOvs17doOkdc722J0jrA6VptjiwKVl5d3yT1VoaGhHDlypFnLmjcviCNHvKmstNc9Wj4+9sokeRp2881ezJ3ruuW/8cYbtG/fnqVLlzJr1iwArrvuOlavXi0FykJ679+dbTFKS1D3TUANv1faYljEFgXq4quYLqjr5GN6ejrp6ekALFy4kLCwsFrz+Pt7oZS65AIOO7BbJsnTMMNQdW5jLWX//v289tpreHv/+59hUFAQhYWFLntPUT9dWoJe+yZ6+2fQtQfGrP9Bde1hdaw2zRYFKjQ0lNzc3JrHubm5dR6Pj4uLIy4uruZxXS015s6FsLCwRrfbcBe7ZZI8Dbtcpi5dulzx8gMCAjh37twl23pOTo6ci7KAPrgXc1UKFOSh7h6NGvkAyttefzC1RbY429ezZ0++//57srOzqaqqYvv27URFRVkdSwiXio2NJSkpiQMHDqC15vDhwyxZsoRhw4ZZHa3N0OfLMd9djpk8D3zbYcx5CSN+nBQnm7DFHpSXlxcJCQkkJiZimiZDhgzhmmuusTqWEC7105/+FB8fH1JTU6murmbZsmXExcUxYkTjGlzm5OSwZMkSCgoKUErVvLa4uJjk5GTOnj1LeHg4M2fOJDCwdq+ztk4f/dI5VFH296i4e1D3jkf5SlsMO7FFgQIYOHAgAwcOtDqGEG6jlOLuu+/m7rvvbtbrvby8GD9+PJGRkZSVlTFnzhxuvPFGtmzZQv/+/YmPjyctLY20tDTGjRvXwuk9l66sQH/4LvrTNOgYhvHrRNT1/a2OJepgmwIlRFt06tQpvv76a8rLyy95fujQoQ2+1uFw1Jyv8vf3JyIigry8PDIzM5k/fz4AMTExzJ8/XwrUv+gTxzDfSoZT36AGD0eNTkD5BVgdS9RDCpQQFvnggw9Yv3493bt3r3WTe2MK1MWys7M5fvw4vXr1uuSmX4fDQVFRUYtl9lS6qgr9pz+g/7gWAoMxZjyD6n+z1bFEA6RACWGRTZs28fzzz9O9e/crWk55eTlJSUlMnDixpkNvYzTmtg0Ab29vl15u31RNzVN18jiFKQuoOvoVfncMp8MjszA6tOzI456+jlytuXmkQAlhEV9fXyIirmx0gqqqKpKSkhg8eDCDBg0CIDg4mPz8fBwOB/n5+QQF1f1l3JjbNsB+twA0No82q9HpH6E3vA1+/hiPPknlzbeRd74Czrfs5/HUdeQuDeWp77YNW1xmLkRbYZpmzc8DDzzAW2+9RX5+/iXPX2jH0RCtNcuXLyciIoKRI0fWPB8VFUVGRgYAGRkZREe3vQ6v+uxpzJf/H/r9FfCDgRjPLkLdfJvVsUQTyR6UEG50cauNCz777LNaz61du7bBZR06dIitW7fSrVs3Zs+eXbP8+Ph4kpOT2bx5M2FhYTXDKLUFWmv01j+j338LDAM16QnULUOkLYaHkgIlhBstXrwYcH6R7tixg1tuueWS6Vpr/v73vzdqWTfccAPr1q2rc9q8efOuLKgH0nk5mKsXQdYe6HMTxsQZqI7hVscSV0AKlBBudKHVBsD69evrbGPzwQcfMGrUKHfG8mhaa/SOLej/fR2qq1APPYqKuUv2mloBKVBCuNmBAwcAqK6urvn9gjNnzuDv729FLI+kiwow314Ke3ZArz7OZoKdrnycRGEPUqCEcLNly5YBUFlZWfM7OEeWCAkJISEhwapoHkXv3o65ZimUl6Lun4Qadg/KkLYYrYkUKCHcbMmSJYDzfNS0adMsTuN5zOIizNTfo3dsgW49MRJmoiK6WR1LuIAUKCEsIsWp6fSB3eS+vQRdkIcaNQY14r9R3vI11lrJ/1khhO3p8jL0+yvQWz/B65oeGI/NRXXvZXUs4WJSoIQQtqYPH8Bc8SrkZqP+615CE2aQW3TO6ljCDaRACSFsSVecR6e9jU7/CMKuwpj9Aqp333/1bJIC1RZIgRJC2I4+fsTZTPD7k6ifjED97GGUn1x+39ZIgRJC2IauqkT/cR160/sQ5MB44llUvwFWxxIWkQIlhLAF/d0JZzPBb/6J+vEQ1JifowKkVX1bJgVKCGEpbVajP01Df/gO+LfHmPpb1IAfWx1L2IAUKCGEZfSZU85zTce+goG3YIybiuoQbHUsYROWF6g1a9awa9cuvL29ueqqq5g6dSrt27e3OpYQwoW0aaK3bEKvXwnePqhHfoX60R0ywKu4hOUF6sYbb2Ts2LF4eXnx9ttvs2HDBsaNG2d1LCGEi+jcs5irUuDLL5zNBCdMRzlCrY4lbMjyAnXTTTfV/H7dddexY8cOC9MIIVxFa43evhm99g0wNWr846jBw2WvSdTL8gJ1sc2bN3PrrbdaHUMI0cJ0YT7mmiXwxT/guh84mwmGd7Y6lrA5txSoBQsWUFBQUOv5Bx98kOjoaMDZpM3Ly4vBgwfXu5z09HTS09MBWLhwIWFhYXXO5+3tXe80q9gtk+RpmB0zeSK983PMd5ZBeTlq9GRU7CiUYVgdS3gAtxSop59++rLTt2zZwq5du5g3b95ld/fj4uKIi4ureZyTk1PnfGFhYfVOs4rdMkmehl0uU5cu0hSvIbrkHPqd5ejMbXBtb4yEJ1BXX2N1LOFBLD/Et3fvXj788EOeffZZ2rVrZ3UcIUQL0PsyMVcvhuIi1E8fQt11P8pLmgmKprG8QKWmplJVVcWCBQsA6N27N1OmTLE4lRCiOXRZKXpdKvrzv0BEd4wZz6C6RVodS3goywvUokWLrI4ghGgB+qt9mCtTIC/Hucc0agzKx8fqWMKDWV6ghBCeTZ8/j96wGv3ZRujUBePJhaieN1gdS7QCUqCEEM2mj33lbCZ45jvn1Xn3TkDJuWTRQqRACSGaTFdWoj9+D/2n9eAIxZi1ANXnpoZfKEQTSIESQjSJPnnc2Rbj269Rt8WhHngE5R9gdSzRCkmBEqIV2rt3LytWrMA0TWJjY4mPj7/iZerqavQn69Eb34PADhjTnkbdFN0CaYWomxQoIVoZ0zRJTU3lqaeeIjQ0lLlz5xIVFUXXrl2bvUz9/bfOvaavj6CiB6PG/gIVGNSCqYWoTQqUEK3M0aNH6dy5M1dddRUAt956K5mZmc0qUNo0Kd24FnPNMvBth5oyGyO6/uHIhGhJUqCEaGXy8vIIDf13+4rQ0FCOHDnS5OVosxrzlfmc+/IL6B+FMWEaKqRjS0YV4rKkQAnRymitaz1X1xiXjRl8ueTmW/AeNgrfn9xlm7YYdhzE126ZWkseKVBCtDKhoaHk5ubWPM7NzcXhcNSar1GDL8eMsN1AvnbLA/bL5Gl56ht8Wca8F6KV6dmzJ99//z3Z2dlUVVWxfft2oqKirI4lRJPJHpQQrYyXlxcJCQkkJiZimiZDhgzhmmukzYXwPFKghGiFBg4cyMCBA62OIcQVUbquM6pCCCGExVrlOag5c+ZYHaEWu2WSPA2zYyYr2G092C0P2C9Ta8nTKguUEEIIzycFSgghhC15zZ8/f77VIVwhMtJ+babtlknyNMyOmaxgt/Vgtzxgv0ytIY9cJCGEEMKW5BCfEEIIW/Lo+6Aa6nmjtWbFihXs2bOHdu3aMXXqVJft9ubk5LBkyRIKCgpQShEXF8eIESMumScrK4uXXnqJTp06ATBo0CDuv/9+l+S54PHHH8fPzw/DMPDy8mLhwoWXTHfnOjp16hTJyck1j7Ozsxk9ejR33313zXPuWEdLly5l9+7dBAcHk5SUBEBxcTHJycmcPXuW8PBwZs6cSWBgYK3XuqLPkl3Z8bM2tD272pVsO+7MtG7dOj777DOCgpwtUcaMGeO2++Lq+y5s1nrSHqq6ulpPmzZNnz59WldWVupf//rX+uTJk5fMs2vXLp2YmKhN09SHDh3Sc+fOdVmevLw8fezYMa211qWlpXrGjBm18hw4cEC/8MILLstQl6lTp+rCwsJ6p7tzHV2surpaP/LIIzo7O/uS592xjrKysvSxY8f0rFmzap5bs2aN3rBhg9Za6w0bNug1a9bUmbmhba61sOtnbWh7drXmbjvuzrR27Vr94YcfujXHBfV9FzZnPXnsIb6Le954e3vX9Ly52M6dO7njjjtQSnHddddRUlJCfn6+S/I4HI6aPQ9/f38iIiLIy8tzyXu1JHeuo4vt37+fzp07Ex4e7vL3+k99+/at9ZdbZmYmMTExAMTExNTalqBx21xr0ZY+a1M0d9txdyYr1fdd2Jz15LGH+BrT8yYvL++SId5DQ0PJy8urc2TnlpSdnc3x48fp1atXrWmHDx9m9uzZOBwOxo8f75Yx0hITEwEYNmzYJaNXg3Xr6G9/+xu33XZbndOsWEeFhYU1n9nhcFBUVFRrnpbqs+QJ7PxZL7c9W6Ex244V/vznP7N161YiIyOZMGGCJUXs4u/C5qwnjy1QuhE9bxozT0srLy8nKSmJiRMnEhAQcMm0Hj16sHTpUvz8/Ni9eze/+93vSElJcWmeBQsW0LFjRwoLC3nuuefo0qULffv2rZluxTqqqqpi165djB07ttY0K9ZRY1mxrqxi18/a0PYsnIYPH15z7nbt2rWsXr2aqVOnujXD5b4LG8tjD/E1pudNaGjoJT1I6uuL01KqqqpISkpi8ODBDBo0qNb0gIAA/Pz8AOdgntXV1S7/a6tjR2cH1ODgYKKjozl69Ogl0929jgD27NlDjx49CAkJqTXNinUEzvVz4dBmfn5+zcnlizW2z1JrYNfP2tD2bIXGbDvuFhISgmEYGIZBbGwsx44dc+v71/Vd2Jz15LEFqjE9b6Kioti6dStaaw4fPkxAQIDL/pFprVm+fDkRERGMHDmyznkKCgpq/jI9evQopmnSoUMHl+QB518wZWVlNb/v27ePbt26XTKPO9fRBZc7vOfudXRBVFQUGRkZAGRkZBAdHV1rnrbUZ8mOn7Ux27MVGrPtuNvF55H/8Y9/uLXdSn3fhc1ZTx59o+7u3btZtWpVTc+b++67j08//RRw7uJqrUlNTeWLL77A19eXqVOn0rNnT5dk+eqrr5g3bx7dunWrORQyZsyYmr2T4cOH88knn/Dpp5/i5eWFr68vEyZM4Prrr3dJHoAzZ87w8ssvA1BdXc3tt99u6ToCOH/+PI899hiLFy+u2e2/OI871tErr7zCwYMHOXfuHMHBwYwePZro6GiSk5PJyckhLCyMWbNmERgYSF5eHq+99hpz584F6t7mWiu7fdb6tmd3asq2Y2WmrKwsvv76a5RShIeHM2XKFLftAdf3Xdi7d+8mryePLlBCCCFaL489xCeEEKJ1kwIlhBDClqRACSGEsCUpUEIIIWxJCpQQQghbkgIlhBDClqRACSGEsCUpUEIIIWxJClQbcvr0aSZNmsQ///lPwDli9eTJk8nKyrI4mRBC1CYFqg3p3LkzDz30EIsWLeL8+fMsW7aMmJgY+vXrZ3U0IYSoRYY6aoNefPFFsrOzUUrxwgsv4OPjY3UkIYSoRfag2qDY2FhOnjzJnXfeKcVJCGFbUqDamPLyclatWsXQoUN5//33KS4utjqSEELUSQpUG28dINUAAACESURBVLNixQp69OjBo48+ysCBA3n99detjiSEEHWSAtWGZGZmsnfvXqZMmQLAww8/zPHjx9m2bZvFyYQQoja5SEIIIYQtyR6UEEIIW5ICJYQQwpakQAkhhLAlKVBCCCFsSQqUEEIIW5ICJYQQwpakQAkhhLAlKVBCCCFsSQqUEEIIW/r/95628IoYP0wAAAAASUVORK5CYII=\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",
" return np.vstack((final_xp,final_yp))\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.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",
" Computes the polynomial coefficents of the path ahead, in vehicle frame.\n",
" \"\"\"\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[3]) - dy * np.sin(-state[3]),\n",
" dy * np.cos(-state[3]) + dx * np.sin(-state[3]) ))\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",
" \"\"\"\n",
" Evaluates rank 3 polynomial\n",
" \"\"\"\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",
"# \"\"\"\n",
"# Evaluates rank 5 polynomial\n",
"# \"\"\"\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",
" \"\"\"\n",
" Evaluates derivative of rank 3 polynomial\n",
" \"\"\"\n",
" return round(3*coeff[0]*x**2 + 2*coeff[1]*x**1 + coeff[2]*x**0,6)\n",
"\n",
"# def df(x,coeff):\n",
"# \"\"\"\n",
"# Evaluates derivative of rank 5 polynomial\n",
"# \"\"\"\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} $"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"# Problem Formulation: Study case\n",
"\n",
"In this case, the objective function to minimize is given by: \n",
"\n",
"$\n",
"\\begin{equation}\n",
"\\begin{aligned}\n",
"\\min_{} \\quad & \\sum^{t+T-1}_{j=t} cte_{j|t,ref}^TQcte_{j,t,ref} + \\psi_{j|t,ref}^TP\\psi_{j|t,ref} + (v_{j|t} - v_{j|t,ref})^TK(v_{j|t} - v_{j|t,ref}) + u^T_{j|t}Ru_{j|t} \\\\\n",
"\\textrm{s.t.} \\quad & x(0) = x0\\\\\n",
" & x_{j+1|t} = Ax_{j|t}+Bu_{j|t} \\quad \\textrm{for} \\quad t<j<t+T-1 \\\\\n",
" & a_{MIN} < a_{j|t} < a_{MAX} \\quad \\textrm{for} \\quad t<j<t+T-1 \\\\\n",
" & \\delta_{MIN} < \\delta_{j|t} < \\delta_{MAX} \\quad \\textrm{for} \\quad t<j<t+T-1 \\\\\n",
"\\end{aligned}\n",
"\\end{equation}\n",
"$\n",
"\n",
"The terns the sum of the **cross-track error**, **heading error**, **velocity error**, **actuaction effort**.\n",
"\n",
"Where R,P,K,Q are the cost matrices used to tune the response.\n",
"\n",
"## Error Formulation\n",
"\n",
"The track can be represented by fitting a curve trough its waypoints, using the vehicle position as reference\n",
"\n",
"![mpc](img/fitted_poly.png)\n",
"\n",
"A fitted cubic poly has the form:\n",
"\n",
"$\n",
"f = K_0 * x^3 + K_1 * x^2 + K_2 * x + K_3\n",
"$\n",
"\n",
"The derivative of a fitted cubic poly has the form:\n",
"\n",
"$\n",
"f' = 3.0 * K_0 * x^2 + 2.0 * K_1 * x + K_2\n",
"$\n",
"\n",
"\n",
"* **crosstrack error** cte: desired y-position - y-position of vehicle -> this is the value of the fitted polynomial\n",
"\n",
"* **heading error** epsi: desired heading - heading of vehicle -> is the inclination of tangent to the fitted polynomial\n",
"\n",
"Then using the fitted polynomial representation in vehicle frame the errors can be easily computed as:\n",
"\n",
"$\n",
"cte = f(px) \\\\\n",
"\\psi = -atan(f`(px)) \\\\\n",
"$"
]
},
{
"cell_type": "code",
"execution_count": 10,
"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 = 282, constraints m = 343\n",
" nnz(P) + nnz(A) = 910\n",
"settings: linear system solver = qdldl,\n",
" eps_abs = 1.0e-04, eps_rel = 1.0e-04,\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.04e+00 1.04e+02 1.00e-01 3.23e-04s\n",
" 50 3.3426e+00 2.85e-07 4.93e-08 1.00e-01 6.84e-04s\n",
"\n",
"status: solved\n",
"solution polish: unsuccessful\n",
"number of iterations: 50\n",
"optimal objective: 3.3426\n",
"run time: 9.06e-04s\n",
"optimal rho estimate: 1.76e-01\n",
"\n",
"CPU times: user 226 ms, sys: 5.12 ms, total: 231 ms\n",
"Wall time: 234 ms\n"
]
}
],
"source": [
"%%time\n",
"\n",
"MAX_SPEED = 1.25\n",
"MIN_SPEED = 0.75\n",
"MAX_STEER = 1.57\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.5)\n",
"\n",
"# Starting Condition\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = -0.25\n",
"x0[2] = 0.0\n",
"x0[3] = np.radians(-0)\n",
" \n",
"#starting guess\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:]=0.5\n",
"u_bar[1,:]=0.1\n",
"\n",
"K=road_curve(x0,track)\n",
"\n",
"# dynamics starting state w.r.t vehicle frame\n",
"x_bar=np.zeros((N,T+1))\n",
"x_bar[2]=x0[2]\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",
"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 += 1*cp.sum_squares(x[2,t]-1.0) # move car to \n",
" cost += 100*cp.sum_squares(x[3,t]-np.arctan(df(x_bar[0,t],K))) # psi\n",
" cost += 1*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], 1*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 += [x[2, :] <= MAX_SPEED]\n",
"# constr += [x[2, :] >= MIN_SPEED]\n",
"constr += [cp.abs(u[0, :]) <= MAX_ACC]\n",
"constr += [cp.abs(u[1, :]) <= 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": 11,
"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",
"w_mpc=np.array(u.value[1, :]).flatten()\n",
"\n",
"#simulate robot state trajectory for optimized U\n",
"x_traj=predict(x0, np.vstack((a_mpc,w_mpc)))\n",
"\n",
"#plt.figure(figsize=(15,10))\n",
"#plot trajectory\n",
"plt.subplot(2, 2, 1)\n",
"plt.plot(track[0,:],track[1,:],\"b+\")\n",
"plt.plot(x_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(a_mpc)\n",
"plt.ylabel('a(t)')\n",
"#plt.xlabel('time')\n",
"\n",
"\n",
"plt.subplot(2, 2, 4)\n",
"plt.plot(theta_mpc)\n",
"plt.ylabel('theta(t)')\n",
"\n",
"plt.subplot(2, 2, 3)\n",
"plt.plot(v_mpc)\n",
"plt.ylabel('v(t)')\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"full track demo"
]
},
{
"cell_type": "code",
"execution_count": 50,
"metadata": {},
"outputs": [
{
"name": "stderr",
"output_type": "stream",
"text": [
"<ipython-input-9-526b0e6cd302>:29: RuntimeWarning: invalid value encountered in true_divide\n",
" v /= np.linalg.norm(v)\n",
"<ipython-input-50-8fcc0dfd7424>:34: RankWarning: Polyfit may be poorly conditioned\n",
" K=road_curve(x_sim[:,sim_time],track)\n"
]
},
{
"name": "stdout",
"output_type": "stream",
"text": [
"CVXPY Optimization Time: Avrg: 0.2259s Max: 0.3524s Min: 0.2046s\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.5)\n",
"\n",
"# track = compute_path_from_wp([0,5,7.5,10,12,13,13,10],\n",
"# [0,0,2.5,2.5,0,0,5,10],0.5)\n",
"\n",
"sim_duration = 175 #time steps\n",
"opt_time=[]\n",
"\n",
"x_sim = np.zeros((N,sim_duration))\n",
"u_sim = np.zeros((M,sim_duration-1))\n",
"\n",
"MAX_SPEED = 1.25\n",
"MIN_SPEED = 0.75\n",
"MAX_STEER = 1.57/2\n",
"MAX_ACC = 1.0\n",
"\n",
"# Starting Condition\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = -0.25\n",
"x0[2] = 0\n",
"x0[3] = 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\n",
"u_bar[1,:]=0.01\n",
"\n",
"for sim_time in range(sim_duration-1):\n",
" \n",
" iter_start=time.time()\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",
" x_bar[2,0]=x_sim[2,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",
" 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[3,t]-np.arctan(df(x_bar[0,t],K))) # psi\n",
" cost += 20*cp.sum_squares(f(x_bar[0,t],K)-x[1,t]) # cte\n",
" cost += 10*cp.sum_squares(1.-x[2,t]) # desired v\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",
" # 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 += [x[2, :] <= MAX_SPEED]\n",
" constr += [x[2, :] >= 0.0]\n",
" constr += [cp.abs(u[0, :]) <= MAX_ACC]\n",
" constr += [cp.abs(u[1, :]) <= 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": 51,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 1080x720 with 5 Axes>"
]
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"#plot trajectory\n",
"grid = plt.GridSpec(4, 5)\n",
"\n",
"plt.figure(figsize=(15,10))\n",
"\n",
"plt.subplot(grid[0:4, 0:4])\n",
"plt.plot(track[0,:],track[1,:],\"b+\")\n",
"plt.plot(x_sim[0,:],x_sim[1,:])\n",
"plt.axis(\"equal\")\n",
"plt.ylabel('y')\n",
"plt.xlabel('x')\n",
"\n",
"plt.subplot(grid[0, 4])\n",
"plt.plot(u_sim[0,:])\n",
"plt.ylabel('a(t) [m/ss]')\n",
"\n",
"plt.subplot(grid[1, 4])\n",
"plt.plot(x_sim[2,:])\n",
"plt.ylabel('v(t) [m/s]')\n",
"\n",
"plt.subplot(grid[2, 4])\n",
"plt.plot(np.degrees(u_sim[1,:]))\n",
"plt.ylabel('delta(t) [deg/s]')\n",
"\n",
"plt.subplot(grid[3, 4])\n",
"plt.plot(x_sim[3,:])\n",
"plt.ylabel('theta(t) [m/s]')\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## OBSTACLE AVOIDANCE\n",
"see dccp paper for reference"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"import dccp\n",
"track = compute_path_from_wp([0,3,4,6,10,13],\n",
" [0,0,2,4,3,3],0.25)\n",
"\n",
"obstacles=np.array([[4,6],[2,4]])\n",
"obstacle_radius=0.5\n",
"\n",
"def to_vehic_frame(pt,pos_x,pos_y,theta):\n",
" dx = pt[0] - pos_x\n",
" dy = pt[1] - pos_y\n",
"\n",
" return [dx * np.cos(-theta) - dy * np.sin(-theta),\n",
" dy * np.cos(-theta) + dx * np.sin(-theta)]\n",
" \n",
"# track = compute_path_from_wp([0,5,7.5,10,12,13,13,10],\n",
"# [0,0,2.5,2.5,0,0,5,10],0.5)\n",
"\n",
"sim_duration = 80 #time steps\n",
"opt_time=[]\n",
"\n",
"x_sim = np.zeros((N,sim_duration))\n",
"u_sim = np.zeros((M,sim_duration-1))\n",
"\n",
"MAX_SPEED = 1.25\n",
"MIN_SPEED = 0.75\n",
"MAX_STEER_SPEED = 1.57\n",
"\n",
"# Starting Condition\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = -0.25\n",
"x0[2] = np.radians(-0)\n",
"x_sim[:,0]=x0\n",
" \n",
"#starting guess\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:]=0.5*(MAX_SPEED+MIN_SPEED)\n",
"u_bar[1,:]=0.00\n",
"\n",
"for sim_time in range(sim_duration-1):\n",
" \n",
" iter_start=time.time()\n",
" \n",
" #compute coefficients\n",
" K=road_curve(x_sim[:,sim_time],track)\n",
" \n",
" #compute opstacles in ref frame\n",
" o_=[]\n",
" for j in range(2):\n",
" o_.append(to_vehic_frame(obstacles[:,j],x_sim[0,sim_time],x_sim[1,sim_time],x_sim[2,sim_time]) )\n",
" \n",
" # dynamics starting state w.r.t vehicle frame\n",
" x_bar=np.zeros((N,T+1))\n",
" \n",
" #prediction for linearization of costrains\n",
" for t in range (1,T+1):\n",
" xt=x_bar[:,t-1].reshape(N,1)\n",
" ut=u_bar[:,t-1].reshape(M,1)\n",
" A,B,C=get_linear_model(xt,ut)\n",
" xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n",
" x_bar[:,t]= xt_plus_one\n",
" \n",
" #CVXPY Linear MPC problem statement\n",
" cost = 0\n",
" constr = []\n",
" x = cp.Variable((N, T+1))\n",
" u = cp.Variable((M, T))\n",
" \n",
" #Prediction Horizon\n",
" for t in range(T):\n",
"\n",
" #cost += 30*cp.sum_squares(x[2,t]-np.arctan(df(x_bar[0,t],K))) # psi\n",
" cost += 50*cp.sum_squares(x[2,t]-np.arctan2(df(x_bar[0,t],K),x_bar[0,t])) # psi\n",
" cost += 20*cp.sum_squares(f(x_bar[0,t],K)-x[1,t]) # cte\n",
"\n",
" # Actuation rate of change\n",
" if t < (T - 1):\n",
" cost += cp.quad_form(u[:, t + 1] - u[:, t], 100*np.eye(M))\n",
" \n",
" # Actuation effort\n",
" cost += cp.quad_form( u[:, t],1*np.eye(M))\n",
" \n",
" # Kinrmatics Constrains (Linearized model)\n",
" A,B,C=get_linear_model(x_bar[:,t],u_bar[:,t])\n",
" constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()]\n",
" \n",
" # Obstacle Avoidance Contrains\n",
" for j in range(2):\n",
" constr += [ cp.norm(x[0:2,t]-o_[j],2) >= obstacle_radius ]\n",
"\n",
" # sums problem objectives and concatenates constraints.\n",
" constr += [x[:,0] == x_bar[:,0]] #<--watch out the start condition\n",
" constr += [u[0, :] <= MAX_SPEED]\n",
" constr += [u[0, :] >= MIN_SPEED]\n",
" constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED]\n",
" \n",
" # Solve\n",
" prob = cp.Problem(cp.Minimize(cost), constr)\n",
" solution = prob.solve(method=\"dccp\", verbose=False)\n",
" \n",
" #retrieved optimized U and assign to u_bar to linearize in next step\n",
" u_bar=np.vstack((np.array(u.value[0, :]).flatten(),\n",
" (np.array(u.value[1, :]).flatten())))\n",
" \n",
" u_sim[:,sim_time] = u_bar[:,0]\n",
" \n",
" # Measure elpased time to get results from cvxpy\n",
" opt_time.append(time.time()-iter_start)\n",
" \n",
" # move simulation to t+1\n",
" tspan = [0,dt]\n",
" x_sim[:,sim_time+1] = odeint(kinematics_model,\n",
" x_sim[:,sim_time],\n",
" tspan,\n",
" args=(u_bar[:,0],))[1]\n",
" \n",
"print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n",
" np.max(opt_time),\n",
" np.min(opt_time))) "
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"#plot trajectory\n",
"grid = plt.GridSpec(2, 3)\n",
"\n",
"plt.figure(figsize=(15,10))\n",
"\n",
"ax=plt.subplot(grid[0:2, 0:2])\n",
"plt.plot(track[0,:],track[1,:],\"b+\")\n",
"plt.plot(x_sim[0,:],x_sim[1,:])\n",
"#obstacles\n",
"circle1=plt.Circle((obstacles[0,0], obstacles[1,0]), obstacle_radius, color='r')\n",
"circle2=plt.Circle((obstacles[0,1], obstacles[1,1]), obstacle_radius, color='r')\n",
"plt.axis(\"equal\")\n",
"plt.ylabel('y')\n",
"plt.xlabel('x')\n",
"\n",
"ax.add_artist(circle1)\n",
"ax.add_artist(circle2)\n",
"\n",
"plt.subplot(grid[0, 2])\n",
"plt.plot(u_sim[0,:])\n",
"plt.ylabel('v(t) [m/s]')\n",
"\n",
"plt.subplot(grid[1, 2])\n",
"plt.plot(np.degrees(u_sim[1,:]))\n",
"plt.ylabel('w(t) [deg/s]')\n",
"\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": []
}
],
"metadata": {
"kernelspec": {
"display_name": "Python [conda env:.conda-jupyter] *",
"language": "python",
"name": "conda-env-.conda-jupyter-py"
},
"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
}