mpc_python_learn/notebooks/MPC_racecar_tracking.ipynb

1210 lines
186 KiB
Plaintext

{
"cells": [
{
"cell_type": "code",
"execution_count": 1,
"metadata": {},
"outputs": [],
"source": [
"import numpy as np\n",
"from scipy.integrate import odeint\n",
"from scipy.interpolate import interp1d\n",
"import cvxpy as cp\n",
"\n",
"import matplotlib.pyplot as plt\n",
"plt.style.use(\"ggplot\")\n",
"\n",
"import time"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"### kinematics model equations\n",
"\n",
"The variables of the model are:\n",
"\n",
"* $x$ coordinate of the robot\n",
"* $y$ coordinate of the robot\n",
"* $v$ velocity of the robot\n",
"* $\\theta$ heading of the robot\n",
"\n",
"The inputs of the model are:\n",
"\n",
"* $a$ acceleration of the robot\n",
"* $\\delta$ steering of the robot\n",
"\n",
"These are the differential equations f(x,u) of the model:\n",
"\n",
"$\\dot{x} = f(x,u)$\n",
"\n",
"* $\\dot{x} = v\\cos{\\theta}$ \n",
"* $\\dot{y} = v\\sin{\\theta}$\n",
"* $\\dot{v} = a$\n",
"* $\\dot{\\theta} = \\frac{v\\tan{\\delta}}{L}$\n",
"\n",
"Discretize with forward Euler Integration for time step dt:\n",
"\n",
"${x_{t+1}} = x_{t} + f(x,u)dt$\n",
"\n",
"* ${x_{t+1}} = x_{t} + v_t\\cos{\\theta}dt$\n",
"* ${y_{t+1}} = y_{t} + v_t\\sin{\\theta}dt$\n",
"* ${v_{t+1}} = v_{t} + a_tdt$\n",
"* ${\\theta_{t+1}} = \\theta_{t} + \\frac{v\\tan{\\delta}}{L} dt$\n",
"\n",
"----------------------\n",
"\n",
"The Model is **non-linear** and **time variant**, but the Numerical Optimizer requires a Linear sets of equations. To approximate the equivalent **LTI** State space model, the **Taylor's series expansion** is used around $\\bar{x}$ and $\\bar{u}$ (at each time step):\n",
"\n",
"$ f(x,u) \\approx f(\\bar{x},\\bar{u}) + \\frac{\\partial f(x,u)}{\\partial x}|_{x=\\bar{x},u=\\bar{u}}(x-\\bar{x}) + \\frac{\\partial f(x,u)}{\\partial u}|_{x=\\bar{x},u=\\bar{u}}(u-\\bar{u})$\n",
"\n",
"This can be rewritten usibg the State Space model form Ax+Bu :\n",
"\n",
"$ f(\\bar{x},\\bar{u}) + A|_{x=\\bar{x},u=\\bar{u}}(x-\\bar{x}) + B|_{x=\\bar{x},u=\\bar{u}}(u-\\bar{u})$\n",
"\n",
"Where:\n",
"\n",
"$\n",
"A =\n",
"\\quad\n",
"\\begin{bmatrix}\n",
"\\frac{\\partial f(x,u)}{\\partial x} & \\frac{\\partial f(x,u)}{\\partial y} & \\frac{\\partial f(x,u)}{\\partial v} & \\frac{\\partial f(x,u)}{\\partial \\theta} \\\\\n",
"\\end{bmatrix}\n",
"\\quad\n",
"=\n",
"\\displaystyle \\left[\\begin{matrix}0 & 0 & \\cos{\\left(\\theta \\right)} & - v \\sin{\\left(\\theta \\right)}\\\\0 & 0 & \\sin{\\left(\\theta \\right)} & v \\cos{\\left(\\theta \\right)}\\\\0 & 0 & 0 & 0\\\\0 & 0 & \\frac{\\tan{\\left(\\delta \\right)}}{L} & 0\\end{matrix}\\right]\n",
"$\n",
"\n",
"and\n",
"\n",
"$\n",
"B = \n",
"\\quad\n",
"\\begin{bmatrix}\n",
"\\frac{\\partial f(x,u)}{\\partial a} & \\frac{\\partial f(x,u)}{\\partial \\delta} \\\\\n",
"\\end{bmatrix}\n",
"\\quad\n",
"= \n",
"\\displaystyle \\left[\\begin{matrix}0 & 0\\\\0 & 0\\\\1 & 0\\\\0 & \\frac{v \\left(\\tan^{2}{\\left(\\delta \\right)} + 1\\right)}{L}\\end{matrix}\\right]\n",
"$\n",
"\n",
"are the *Jacobians*.\n",
"\n",
"\n",
"\n",
"So the discretized model is given by:\n",
"\n",
"$ x_{t+1} = x_t + (f(\\bar{x},\\bar{u}) + A|_{x=\\bar{x}}(x_t-\\bar{x}) + B|_{u=\\bar{u}}(u_t-\\bar{u}) )dt $\n",
"\n",
"$ x_{t+1} = (I+dtA)x_t + dtBu_t +dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\bar{u}))$\n",
"\n",
"The LTI-equivalent kinematics model is:\n",
"\n",
"$ x_{t+1} = A'x_t + B' u_t + C' $\n",
"\n",
"with:\n",
"\n",
"$ A' = I+dtA|_{x=\\bar{x},u=\\bar{u}} $\n",
"\n",
"$ B' = dtB|_{x=\\bar{x},u=\\bar{u}} $\n",
"\n",
"$ C' = dt(f(\\bar{x},\\bar{u}) - A|_{x=\\bar{x},u=\\bar{u}}\\bar{x} - B|_{x=\\bar{x},u=\\bar{u}}\\bar{u}) $"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"-----------------\n",
"[About Taylor Series Expansion](https://courses.engr.illinois.edu/ece486/fa2017/documents/lecture_notes/state_space_p2.pdf):\n",
"\n",
"In order to linearize general nonlinear systems, we will use the Taylor Series expansion of functions.\n",
"\n",
"Typically it is possible to assume that the system is operating about some nominal\n",
"state solution $\\bar{x}$ (possibly requires a nominal input $\\bar{u}$) called **equilibrium point**.\n",
"\n",
"Recall that the Taylor Series expansion of f(x) around the\n",
"point $\\bar{x}$ is given by:\n",
"\n",
"$f(x)=f(\\bar{x}) + \\frac{df(x)}{dx}|_{x=\\bar{x}}(x-\\bar{x})$ + higher order terms...\n",
"\n",
"For x sufficiently close to $\\bar{x}$, these higher order terms will be very close to zero, and so we can drop them.\n",
"\n",
"The extension to functions of multiple states and inputs is very similar to the above procedure.Suppose the evolution of state x\n",
"is given by:\n",
"\n",
"$\\dot{x} = f(x1, x2, . . . , xn, u1, u2, . . . , um) = Ax+Bu$\n",
"\n",
"Where:\n",
"\n",
"$ A =\n",
"\\quad\n",
"\\begin{bmatrix}\n",
"\\frac{\\partial f(x,u)}{\\partial x1} & ... & \\frac{\\partial f(x,u)}{\\partial xn} \\\\\n",
"\\end{bmatrix}\n",
"\\quad\n",
"$ and $ B = \\quad\n",
"\\begin{bmatrix}\n",
"\\frac{\\partial f(x,u)}{\\partial u1} & ... & \\frac{\\partial f(x,u)}{\\partial um} \\\\\n",
"\\end{bmatrix}\n",
"\\quad $\n",
"\n",
"Then:\n",
"\n",
"$f(x,u)=f(\\bar{x},\\bar{u}) + \\frac{df(x,u)}{dx}|_{x=\\bar{x}}(x-\\bar{x}) + \\frac{df(x,u)}{du}|_{u=\\bar{u}}(u-\\bar{u}) = f(\\bar{x},\\bar{u}) + A_{x=\\bar{x}}(x-\\bar{x}) + B_{u=\\bar{u}}(u-\\bar{u})$\n",
"\n",
"-----------------"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"### Kinematics Model"
]
},
{
"cell_type": "code",
"execution_count": 2,
"metadata": {},
"outputs": [],
"source": [
"\"\"\"\n",
"Control problem statement.\n",
"\"\"\"\n",
"\n",
"N = 4 #number of state variables\n",
"M = 2 #number of control variables\n",
"T = 20 #Prediction Horizon\n",
"DT = 0.25 #discretization step"
]
},
{
"cell_type": "code",
"execution_count": 3,
"metadata": {},
"outputs": [],
"source": [
"def get_linear_model(x_bar,u_bar):\n",
" \"\"\"\n",
" Computes the LTI approximated state space model x' = Ax + Bu + C\n",
" \"\"\"\n",
" \n",
" L=0.3 #vehicle wheelbase\n",
" \n",
" x = x_bar[0]\n",
" y = x_bar[1]\n",
" v = x_bar[2]\n",
" theta = x_bar[3]\n",
" \n",
" a = u_bar[0]\n",
" delta = u_bar[1]\n",
" \n",
" A = np.zeros((N,N))\n",
" A[0,2]=np.cos(theta)\n",
" A[0,3]=-v*np.sin(theta)\n",
" A[1,2]=np.sin(theta)\n",
" A[1,3]=v*np.cos(theta)\n",
" A[3,2]=v*np.tan(delta)/L\n",
" A_lin=np.eye(N)+DT*A\n",
" \n",
" B = np.zeros((N,M))\n",
" B[2,0]=1\n",
" B[3,1]=v/(L*np.cos(delta)**2)\n",
" B_lin=DT*B\n",
" \n",
" f_xu=np.array([v*np.cos(theta), v*np.sin(theta), a,v*np.tan(delta)/L]).reshape(N,1)\n",
" C_lin = DT*(f_xu - np.dot(A,x_bar.reshape(N,1)) - np.dot(B,u_bar.reshape(M,1)))\n",
" \n",
" return np.round(A_lin,4), np.round(B_lin,4), np.round(C_lin,4)"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Motion Prediction: using scipy intergration"
]
},
{
"cell_type": "code",
"execution_count": 4,
"metadata": {},
"outputs": [],
"source": [
"# Define process model\n",
"# This uses the continuous model \n",
"def kinematics_model(x,t,u):\n",
" \"\"\"\n",
" Returns the set of ODE of the vehicle model.\n",
" \"\"\"\n",
" \n",
" L=0.3 #vehicle wheelbase\n",
" dxdt = x[2]*np.cos(x[3])\n",
" dydt = x[2]*np.sin(x[3])\n",
" dvdt = u[0]\n",
" dthetadt = x[2]*np.tan(u[1])/L\n",
"\n",
" dqdt = [dxdt,\n",
" dydt,\n",
" dvdt,\n",
" dthetadt]\n",
"\n",
" return dqdt\n",
"\n",
"def predict(x0,u):\n",
" \"\"\"\n",
" \"\"\"\n",
" \n",
" x_ = np.zeros((N,T+1))\n",
" \n",
" x_[:,0] = x0\n",
" \n",
" # solve ODE\n",
" for t in range(1,T+1):\n",
"\n",
" tspan = [0,DT]\n",
" x_next = odeint(kinematics_model,\n",
" x0,\n",
" tspan,\n",
" args=(u[:,t-1],))\n",
"\n",
" x0 = x_next[1]\n",
" x_[:,t]=x_next[1]\n",
" \n",
" return x_"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Validate the model, here the status w.r.t a straight line with constant heading 0"
]
},
{
"cell_type": "code",
"execution_count": 5,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CPU times: user 3.43 ms, sys: 0 ns, total: 3.43 ms\n",
"Wall time: 2.97 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": "iVBORw0KGgoAAAANSUhEUgAAAagAAAChCAYAAACSyiu8AAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjMuMSwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy/d3fzzAAAACXBIWXMAAAsTAAALEwEAmpwYAAAjGUlEQVR4nO3de1xVdb7/8dfaIAIisAXUxDQxrfRYqZBNaZigv1Iz6jiO9yEtJ0kpLUvPaUzHLKeJofDaFKkxNaNlUjZO46CJTuYjFG9BaTpqlhfkLje5rO/vjz1yJEAusvdae/N5Ph483Oy19trvvR7L/WF91/p+v5pSSiGEEEKYjMXoAEIIIURdpEAJIYQwJSlQQgghTEkKlBBCCFOSAiWEEMKUpEAJIYQwJXejAwghmq+4uJg1a9Zw5swZNE1j5syZdOnShfj4eC5evEhQUBBz5szBx8fH6KhCNJkm/aCEcF4rVqzgtttuIyIigsrKSi5fvszmzZvx8fEhKiqK5ORkioqKmDx5stFRhWgyaeITwkmVlJTw7bffMmzYMADc3d1p164daWlphIeHAxAeHk5aWpqRMYVoNmniE8JJZWVl4evry6pVqzh9+jQhISFER0dTUFCA1WoFwGq1UlhYaHBSIZrHVGdQuq7z/PPPs2zZMqOjCGF6VVVVnDx5khEjRvDaa6/Rtm1bkpOTG/36lJQU5s+fz/z58+0XUojrYKozqK1btxIcHExpaWmj1j979mydzwcGBpKdnd2S0a6b2TJJnoZdK1OXLl0cnKa2gIAAAgIC6NWrFwB33303ycnJ+Pn5kZeXh9VqJS8vD19f3zpfHxkZSWRkZPXvzvL/yWx5wHyZnC1Pff+fTHMGlZOTQ3p6OhEREUZHEcIp+Pv7ExAQUF1Yjhw5QteuXQkNDSU1NRWA1NRUwsLCjIwpRLOZ5gxq3bp1TJ48+ZpnTykpKaSkpACwbNkyAgMD61zP3d293mVGMVsmydMwM2b6uWnTppGQkEBlZSUdO3YkJiYGpRTx8fHs2LGDwMBA5s6da3RM0crpJcXNep0pCtT+/fvx8/MjJCSEjIyMetf7eZNEfaeMZju9BfNlkjwNM3sTH8BNN91U5zXbhQsXGpBGiJpURQVqy1/I2bMdfvsGmp+1Sa83RYE6evQo+/bt48CBA5SXl1NaWkpCQgKxsbFGRxNCCNEM6sxJ9Hfj4cdTtB02ivI2Hk3ehikK1MSJE5k4cSIAGRkZbNmyRYqTEEI4IVVVhfp8E2rLX6GdD5ZZL+IXMbJZLSSmKFBCCCGcnzr/I/q7b8DJY2ihg9EmPYnmU/ddpI1hugLVt29f+vbta3QMIYQQjaR0HbXjM9TH74FHW7QZ87CEDbnu7ZquQAkhhHAeKvsC+roEOHoE+oVimToLzb9Di2xbCpQQQogmU0qh/vVP1IZE0ED79Wy0eyPRNK3F3kMKlBBCiCZR+Tno762EI/vgln5YHnsaLaBji7+PFCghhBCNopRCpe1Gvb8GKsvRxs9Au38kmsU+gxJJgRJCCNEgdakQ9f5q1P4vIeQWLI89g9Y52K7vKQVKCAfSdb1R62ma1qJt+UJcD3Xoa/T3VkBxEdqjU9FGPILm5mb395UCJYQDTZgwoVHreXh4kJSUZOc0QlybKilGbXgHtWc7dO2BZc5itK49HPb+UqCEcCAPDw/++Mc/XnMdpRTPP/+8gxIJUTf17SH0dW9CXi7ayHFoD/0Kzb2NQzNIgRLCgR566CGCgoIaXG/06NEOSCNEbepyGWrTOtQXW6FzMJb5v0cLucWQLFKghHCgcePGNWq9sWPH2jmJELWp49+ir30Dss6hRY5Be2QKmkdbw/JIgRLCIBcuXKjz+TZt2uDv74/FTrfuCvFzqqIc9ckHqG3J0CEQy3NL0W7pZ3QsKVBCGOVaI/ZbLBYGDhzI448/jr+/v+NCiVZHnT5hmxbj7A9oQ0agjZuG5ultdCxACpQQhvnNb35DZmYmY8eOrZ4c8aOPPuKWW26hT58+vP/++yQmJvLss88aHVW4IFVZifr7R6i/bQAfPyyxC9H6hRodqwZpQxDCIBs3bmTGjBl07twZd3d3OnfuzBNPPMGmTZsIDg4mJiaGzMxMo2MKF6TO/oC+7HnUpx+gDRyMZfFy0xUnkDMoIQyjlOLixYsEB/9fb/zs7Ozqzryenp5UVVUZFU+4IKVXoVK2oDYngacnlidfQBt4r9Gx6iUFSgiDjBw5kt/97ncMHTqUgIAAcnNz+eKLLxg5ciQA6enp9O7d2+CUwlWoi+dtd+h9nwl33IVl6lNovlajY12TFCghDPLwww/TvXt3vvrqK06ePIm/vz8zZ87kzjvvBOCuu+7irrvuMjakcHpKKdSuf6A+fBcsFrTHnkb7xTCnGEpLCpQQBrrzzjurC5IQLU3lZqOvXw6ZB+C2O7BEx6J1aLijuFlIgRLCIBUVFXz00Ud8+eWXXLp0ifXr13Po0CHOnTvHAw88YHQ84cSUUuh7v0B98CeoqkSb9CRa+INOcdZ0NbmLTwiDrF+/njNnzhAbG1v9xXHjjTeybds2g5MJZ6YK8yl47X9RifEQ3A3LS29iGTrS6YoTmOQMKjs7m5UrV5Kfn4+maURGRlZfKBbCVX399dckJCTg6elZ/eXRoUMHcnNzDU4mnJVK/wr9z6u4XFqCNvYxtOFj0Cz2nxbDXkxRoNzc3JgyZQohISGUlpYyf/58br/9drp27Wp0NCHsxt3dvdb8UIWFhbRv396gRMJZqeIi1F//hNq7E7r1JODlxeR7+xod67qZokBZrVasVtvtjl5eXgQHB5ObmysFSri0u+++mxUrVhAdHQ1AXl4e69at45577mn0NnRdZ/78+XTo0IH58+dTVFREfHw8Fy9eJCgoiDlz5uDj42OnTyDMQH2TbrsRojAP7aHxaCPH4d65M2RnGx3tupnuGlRWVhYnT57k5ptvNjqKEHY1ceJEOnbsyLPPPktJSQmxsbFYrVZ++ctfNnobW7durdHRNzk5mX79+pGQkEC/fv1ITk62Q3JhBqqsFD1pFfqbi8DLG8uCP2AZMxHN3RTnHS3CVJ+krKyMuLg4oqOj8fauPVhhSkoKKSkpACxbtozAwMA6t+Pu7l7vMqOYLZPkaZi9M7m7uxMdHU10dHR1015TLmTn5OSQnp7Oo48+ymeffQZAWloaixYtAiA8PJxFixYxefJke8QXBlLHMmydbnOybNOvR01Ca+NhdKwWZ5oCVVlZSVxcHEOGDGHQoEF1rhMZGUlkZGT179n1nMJeGXjTTMyWSfI07FqZunTp0qxt1jfFBkBpaWn1406dOjW4rXXr1jF58uQarysoKKhuLrdarRQWFjYrpzAnVVGOSv4z6p+fQGAnLM+9gta7r9Gx7MYUBUopxZo1awgODpaZRIVLu9YUG1fbsGHDNZfv378fPz8/QkJCyMjIaFYWZ22RMFsecEymiuPfUvDmEvQfT+H1wCP4TH0Ki1fd02KYbR81N48pCtTRo0fZtWsX3bp1Y968eQBMmDCBAQMGGJxMiJZ1deH54osvOHLkCL/85S8JCgri4sWLfPTRR/Tr1/BEcUePHmXfvn0cOHCA8vJySktLSUhIwM/Pj7y8PKxWK3l5efj61n8nl7O2SJgtD9g3k6qsQP3tQ9TWjeBrxfLMYsr79ie3uASKSxyepzkaylNfi4QpCtStt97Kxo0bjY4hhENt2LCBhIQEPDxs1w5uuOEGZsyYwdNPP83QoUOv+dqJEycyceJEADIyMtiyZQuxsbEkJSWRmppKVFQUqamphIWF2ftjCDtSP522TSb4w7/RfnE/2vgn0Lxbz12ZpihQQrRGSimysrJqdKe4ePFirb5RTREVFUV8fDw7duwgMDCQuXPntkRU4WBKr0JtS0Z98j54tcMS8z9o/e82OpbDSYESwiCjRo2qnm7jShNIamoqo0aNatJ2+vbtS9++tgvl7du3Z+HChfaIKxxEXThru0PvxHcw4BdYJsegtfczOpYhpEAJYZAxY8bQrVs3vvrqK06dOlVrug3RuihdR6X+HfXROnB3R5s+F21QuFOOoddSpEAJYSCZbkMAqJyL6OsT4NtD8F8DsEydjWYNMDqW4Uw3koQQrmz79u2NWm/Hjh12TiLMQCmF/uV29MWz4d9H0abEYIl9SYrTf0iBEsKB3nvvPduXkq5f8ycpKcnoqMLOVEEe+sqlqHVvwo09sLyUgOW+B1p1k97PSROfEA5UVlbG+PHjG1yvTZs2DkgjjKL2/Qv9/dVQVoY2bjpaxENoFjlf+DkpUEI40IoVKxq1nvwV7ZpU8SXU+2tQabvhpl5Ypj2DdsONRscyLZcrUPpXX5CfsZ+q8nLQNDTNApYrP27g7m77aeMB7h7Qpg14eIBHW2jrhdbWEzy9bD9e3uDVzvbj4SFfGuK6BQUFGR1BGEQdTkN/bwUUFaI9PAntwbFobs47maAjuFyBoriQqvM/QWUlKIXSdVAK9CqoqoSqKqiogMoK27+qZqdIVd923dtAOx/w9oH2vuDji+bjC+39oL0/+Pqj+fmDfwfw62ArdEKIVk+VlqA2JqL+9U8I7m67CaJbiNGxnILLFShL5MMEjJ/e6HGoVGUlVJTD5TIoL4OyMigrhbISVGkJlJZAaTEUF0FJEar4EhRdgvM/oS5l2h7/p8jVKG5e3uAfANZANGsAleOngWfrGaJECAHqu8Po6xIgN9t2xvTQBDS5vthoLlegmkq70uRXx6jAjWnQU3qVrXgV5kNBLio/DwpyIT8XlZcNeTmos6dRlydJgRKilVCXL6M2v4favgU6dsHywjK0nrcaHcvptPoCdb00i9t/mvn8ILh7vUWtTWCgS0zBLIS4NnXiO/S1b8KFn2x35z0yFa1tW6NjOSUpUEI4WGFhIbt27SI9PZ3Tp09TUlKCt7c33bt3584772To0KHXnCZDmJOqqEB99lfU3zeBNQDL3CVot91hdCyn1ugCtX79esLDw7npppvsGEcI1/bBBx+we/du+vfvz7BhwwgODsbLy4vS0lJ++uknMjMzeeGFFxg8eDCTJk0yOq5opIqT36P/8SX48RTavZG2vk3e7YyO5fQaXaCqqqpYunQpvr6+DBkyhCFDhhAQIMNxCNEUVquVhISEOjvi9ujRg8GDB1NeXi5DHTkJVVWF+nwTuZ/9Fbx9sMx6Ee2Ou4yO5TIaXaCmTZtGdHQ0Bw4cYPfu3Xz88cf06tWL++67j0GDBuHpKbdVC9GQBx98sPpxfn4+/v7+tdYpKSnhgQcecGAq0Rzq/I/o774BJ4/R9t4IKsY+Zut6IlpMk8bWsFgsDBw4kGeeeYalS5dSWFjIqlWreOKJJ1izZg25ubn2yimEy3n66afrfH7OnDkOTiKaQuk6esqn6L97BrLOoc2Yh/9zS6Q42UGTbpIoKSlh79697N69m9OnTzNo0CCmT59OYGAgn332Ga+88gqvv/66vbIK4VKUqt0tvKSkBIuMyWZaKvuCrV/T0SPQLxTL1Flo/h2MjuWyGl2g4uLiOHToELfddhvDhw8nLCysRjv61KlTiY6OtkdGIVzKzJkzASgvL69+fEVRURH33nuvEbHENSilUP/6J2pDImig/Xq27WYIGf7MrhpdoHr16sX06dPrbDMHW/Pf22+/3ewgBw8eZO3atei6TkREBFFRUc3elhBmNnv2bJRSvPrqq8yePbvGMn9/f7p06WJQMlEXlZ9rG0PvyD64pR+Wx55GC+hodKxWodEFasyYMQ2u07aZndF0XScxMZEXX3yRgIAAFixYQGhoKF27dm3W9oQwsz59+gCQmJjY7P8zwv6UUqi03aj310BlOdr4GWj3j5RpMRzIFHv6+PHjdO7cmU6dOuHu7s4999xDWlqa0bGEaHFbt26loqICqP8PuoqKCrZu3erIWOJn1KVC1Fuvod5+HToHY/ntm1giRktxcjBTjCSRm5tbo09VQEAA33//fbO2tXChL99/705Fhbn6aLVpY65MkqdhAwe6sWBBy24zPz+f2NhY+vfvT58+fejSpQuenp6UlZVx9uxZMjMzOXDgAOHh4S37xqLR1KGvbU16xUVoj05FG/GITIthEFMUqLruZqrr4mNKSgopKSkALFu2jMDAwFrreHm5oWma6WYkNVsmydMwi0Wr8xi7HhMnTmT06NHs3LmTHTt28MMPP1BcXIyPjw/dunWjf//+TJgwgfbt27fo+4qGqZJi1IZ3UHu2Q9ceWOYsRuvaw+hYrZopClRAQAA5OTnVv+fk5GC1WmutFxkZSWRkZPXvdU2psWABBAYGNnq6DUcxWybJ07BrZbqeGxl8fX0ZM2ZMo67rCsdQ3x5CX/cm5OeijRqHNvpXaO7m+oOpNTJFg2rPnj05d+4cWVlZVFZWsmfPHkJDQ42OJYRwcepyGfoHa9D/+FvwaItl/mtYoiZLcTIJU5xBubm5MW3aNJYuXYqu69x///3ceOONRscSwq5KSkr48MMPyczM5NKlSzWaulevXt3g67Ozs1m5ciX5+flomkZkZCQjR46kqKiI+Ph4Ll68SFBQEHPmzMHHR+Yi+zl1/Fv0tW/YRoOIHIP2yBQ0D7mr0kxMUaAABgwYwIABA4yOIYTDvPPOO+Tm5jJ27FiWL1/O7Nmz+fTTTxk0aFCjXu/m5saUKVMICQmhtLSU+fPnc/vtt7Nz50769etHVFQUycnJJCcnM3nyZDt/GuehKspRn3yA2pYMHQKxPLcU7ZZ+RscSdTBFE58QrdHhw4d59tlnCQsLw2KxEBYWxpw5c9i9e3ejXm+1WgkJCQHAy8uL4OBgcnNzSUtLq74LMDw8XLpsXEWdPoH+8lzUPz5GGxyJZVGCFCcTM80ZlBCtjVIKb29vADw9PSkuLsbf35/z5883eVtZWVmcPHmSm2++mYKCguqbjKxWK4WFhS2a2xmpykrU3z9C/W0D+PhhiX0Jrd9Ao2OJBkiBEsIg3bt3JzMzk379+nHrrbeSmJiIp6cnN9xwQ5O2U1ZWRlxcHNHR0dUFrzEa020DwN3dvcVvt78eTc1TeeYkBQlLqDz+HZ5DhtP+iWextG/ZkcedfR/ZW3PzSIESwiC/+c1vqm+MmDZtGh988AHFxcXMmjWr0duorKwkLi6OIUOGVF+78vPzIy8vD6vVSl5eXr3Txzem2waYrwtAY/MovQqV8ilq85/B0xPLky9QMfBeci+Xw+WW/TzOuo8cpaE89XXbkAIlhEEKCwvp1asXYOsb9eSTTwK2ob8aQynFmjVrCA4OZvTo0dXPh4aGkpqaSlRUFKmpqYSFhbV8eJNTWeds/Zq+z4Q77sIy9Sk039p9K4W5yU0SQhjk5ZdfrvP5pUuXNur1R48eZdeuXXzzzTfMmzePefPmkZ6eTlRUFIcPHyY2NpbDhw+3qpkBlFLoO/+O/run4cdTaI89g+Wp/5Xi5KTkDEoIB9N1HfjPaNn/+bniwoULuDVy3Ldbb72VjRs31rls4cKF1x/UyajcbPT1yyHzANx2B5boWLQOQUbHEtdBCpQQDjZhwoTqx+PHj6+xzGKx8Mgjjzg6klNTSqH27kT95U9QVYk28Um0oQ/KZIIuQAqUEA62YsUKlFIsWrSIxYsXo5RC0zQ0TcPX1xcPDw+jIzoNVZiPnrQKDu6Fm2+zTSbYUSZ8dBVSoIRwsKAgW7PTqlWrAFuT39V9l0TjqPQ9tuJUVoI2Nhpt+MNoFpkWw5VIgRLCIMXFxbzzzjvs3bsXd3d3kpKS2LdvH8ePH6/V9Cf+j15UiJ74R9TendCtJ5Zpc9CCuxkdS9iB3MUnhEHefvttvL29WbVqFe7utr8Ve/fuzZ49ewxOZl7qm3RynpmC+noX2kPjsSz4gxQnFyZnUEIY5MiRI7z11lvVxQls/aEKCgoMTGVOqqwU9eFa1K7PcbuxB5aZC9C632x0LGFnUqCEMIi3tzeXLl2qce0pOztbrkX9jDr2DfraNyEnC23EIwRMjyWn8JLRsYQDSIESwiARERHExcUxfvx4lFIcO3aMv/zlLwwfPtzoaKagyi+jkv+MSvkUAjthee4VtN59/zNnkxSo1kAKlBAGefjhh2nTpg2JiYlUVVWxevXq6kkHWzt18nvbZILnzqANfRDtv6PRPL2MjiUcTAqUEAbRNI1Ro0YxatQoo6OYhqqsQP1tI2rrh+BrxfLMYrS+/Y2OJQwiBUoIA509e5ZTp05RVlZW4/lhw4YZlMg46qfT6O/Gww//Rrv7frQJT6B5y1T1rZkUKCEM8vHHH7Np0ya6d+9O27ZtayxrTQVK6VWobcmoT94Hr3ZYYv4Hrf/dRscSJiAFSgiDbN26lVdeeYXu3bsbHcUw6sJZ27WmE9/BgF9gmRyD1t7P6FjCJAwvUElJSezfvx93d3c6depETEwM7dq1MzqWEHbn4eFBcHCw0TEMoXQdtXMratM6cG+D9vizaHfdJwO8ihoMH0ni9ttvJy4ujtdff50bbriBzZs3Gx1JCLvRdb3651e/+hXvvvsueXl5NZ6/Mh2Hq1I5F9HfeMk2+njv/8KyaAWWQeFSnEQthp9B3XHHHdWPe/fuzd69ew1MI4R9XT3VxhXbt2+v9dyGDRscEcehlFKoPTtQG94GXaFNiUEb8v+kMIl6GV6grrZjxw7uueceo2MIYTcrVqwwOoIhVEEeetJKOPS17awpOhYtqLPRsYTJOaRALVmyhPz8/FrPjx8/nrCwMMB2R5ObmxtDhgypdzspKSmkpKQAsGzZMgIDA+tcz93dvd5lRjFbJsnTMHtkujLVBsCnn37KmDFjaq3z2WefMXr06BZ9XyOpff9Cf381lJWhjZuOFvEQmsXwqwvCCTikQP32t7+95vKdO3eyf/9+Fi5ceM3T/cjISCIjI6t/z87OrnO9wMDAepcZxWyZJE/DrpWpS5frnxRv06ZNdRaoTZs2uUSBUsWXUO+vQaXthu43Y5k+B+2GG42OJZyI4U18Bw8e5JNPPmHx4sW1+oII4Yq++eYbwHbDxJXHV1y4cAEvL+cf0kcd2Ye+fjkUFaI9PAntwbFobjKZoGgawwtUYmIilZWVLFmyBIBevXoxY8YMg1MJYT+rV68GoLy8vPox2IY+8vf3Z9q0aUZFu26qtAT14buo3dsguDuW2IVo3XoaHUs4KcML1PLly42OIIRDrVy5ErDdMDFr1iyD07Qc9d1h9HUJkJuN9uB/oz00Ea1NG6NjCSdmeIESorVyleKkLl9GbX4PtX0LdOyC5YVlaD1vNTqWcAFSoIQQzaZOfGebTPDCT2jDRqM9OhWtrafRsYSLkAIlhGgyVVmB2vJX1N83gbUDlrlL0G67o+EXCtEEUqCEEE2izpy0TYvx4ym0eyPQxj2O5i3jZ4qWJwVKCBd08OBB1q5di67rREREEBUVdd3bVFVVqM83obb8Fdr5YJn1Itodd11/WCHqIQVKCBej6zqJiYm8+OKLBAQEsGDBAkJDQ+natWuzt6nO/4j+7htw8hha6GC0SU+i+fi2XGgh6iAFSggXc/z4cTp37kynTp0AuOeee0hLS2tWgVK6TsmWDehJq8GjLdqMeVjC6h+OTIiWJAVKCBeTm5tLQEBA9e8BAQF8//33Td6O0qvQ31jEpW8PQb9QLFNnofl3aMmoQlyTFCghXIxSqtZzdY1x2ZjBl4sH/gL34Q/hMfRB00yL0VoGFr4erpJHCpQQLiYgIICcnJzq33NycrBarbXWa9Tgy+EjTTeQr9nygPkyOVue+gZfljHvhXAxPXv25Ny5c2RlZVFZWcmePXsIDQ01OpYQTSZnUEK4GDc3N6ZNm8bSpUvRdZ3777+fG2+UaS6E85ECJYQLGjBgAAMGDDA6hhDXRVN1XVEVQgghDOaS16Dmz59vdIRazJZJ8jTMjJmMYLb9YLY8YL5MrpLHJQuUEEII5ycFSgghhCm5ZIG6um+HWZgtk+RpmBkzGcFs+8FsecB8mVwlj9wkIYQQwpRc8gxKCCGE83PqflANzXmjlGLt2rUcOHCAtm3bEhMTQ0hIiF2yZGdns3LlSvLz89E0jcjISEaOHFljnYyMDF577TU6duwIwKBBgxg7dqxd8lzx1FNP4enpicViwc3NjWXLltVY7sh9dPbsWeLj46t/z8rKYty4cYwaNar6OUfso1WrVpGeno6fnx9xcXEAFBUVER8fz8WLFwkKCmLOnDn4+PjUeq095lkyKzN+1oaOZ3u7nmPHkZk2btzI9u3b8fW1TYkyYcIEh/WLq++7sFn7STmpqqoqNWvWLHX+/HlVUVGhnnvuOXXmzJka6+zfv18tXbpU6bqujh49qhYsWGC3PLm5uerEiRNKKaVKSkpUbGxsrTzffPONevXVV+2WoS4xMTGqoKCg3uWO3EdXq6qqUo8//rjKysqq8bwj9lFGRoY6ceKEmjt3bvVzSUlJavPmzUoppTZv3qySkpLqzNzQMecqzPpZGzqe7a25x46jM23YsEF98sknDs1xRX3fhc3ZT07bxHf1nDfu7u7Vc95cbd++fdx3331omkbv3r0pLi4mLy/PLnmsVmv1mYeXlxfBwcHk5uba5b1akiP30dWOHDlC586dCQoKsvt7/VyfPn1q/eWWlpZGeHg4AOHh4bWOJWjcMecqWtNnbYrmHjuOzmSk+r4Lm7OfnLaJrzFz3uTm5tYY4j0gIIDc3Nw6R3ZuSVlZWZw8eZKbb7651rJjx44xb948rFYrU6ZMccgYaUuXLgVg+PDhte6mMWofffnll9x77711LjNiHxUUFFR/ZqvVSmFhYa11WmqeJWdg5s96rePZCI05dozwj3/8g127dhESEsLUqVMNKWJXfxc2Zz85bYFSjZjzpjHrtLSysjLi4uKIjo7G29u7xrIePXqwatUqPD09SU9P5w9/+AMJCQl2zbNkyRI6dOhAQUEBL7/8Ml26dKFPnz7Vy43YR5WVlezfv5+JEyfWWmbEPmosI/aVUcz6WRs6noXNiBEjqq/dbtiwgffee4+YmBiHZrjWd2FjOW0TX2PmvAkICKgxB0l98+K0lMrKSuLi4hgyZAiDBg2qtdzb2xtPT0/ANphnVVWV3f/a6tDBNgOqn58fYWFhHD9+vMZyR+8jgAMHDtCjRw/8/f1rLTNiH4Ft/1xp2szLy6u+uHy1xs6z5ArM+lkbOp6N0Jhjx9H8/f2xWCxYLBYiIiI4ceKEQ9+/ru/C5uwnpy1QjZnzJjQ0lF27dqGU4tixY3h7e9vtP5lSijVr1hAcHMzo0aPrXCc/P7/6L9Pjx4+j6zrt27e3Sx6w/QVTWlpa/fjw4cN069atxjqO3EdXXKt5z9H76IrQ0FBSU1MBSE1NJSwsrNY6rWmeJTN+1sYcz0ZozLHjaFdfR/76668dOt1Kfd+FzdlPTt1RNz09nfXr11fPefPoo4+ybds2wHaKq5QiMTGRQ4cO4eHhQUxMDD179rRLlu+++46FCxfSrVu36qaQCRMmVJ+djBgxgs8//5xt27bh5uaGh4cHU6dO5ZZbbrFLHoALFy7w+uuvA1BVVcXgwYMN3UcAly9fZubMmaxYsaL6tP/qPI7YR2+88QaZmZlcunQJPz8/xo0bR1hYGPHx8WRnZxMYGMjcuXPx8fEhNzeXt956iwULFgB1H3Ouymyftb7j2ZGacuwYmSkjI4NTp06haRpBQUHMmDHDYWfA9X0X9urVq8n7yakLlBBCCNfltE18QgghXJsUKCGEEKYkBUoIIYQpSYESQghhSlKghBBCmJIUKCGEEKYkBUoIIYQpSYESQghhSlKgWpHz58/z2GOP8e9//xuwjVg9ffp0MjIyDE4mhBC1SYFqRTp37sykSZNYvnw5ly9fZvXq1YSHh9O3b1+jowkhRC0y1FEr9Pvf/56srCw0TePVV1+lTZs2RkcSQoha5AyqFYqIiODMmTM88MADUpyEEKYlBaqVKSsrY/369QwbNowPP/yQoqIioyMJIUSdpEC1MmvXrqVHjx48+eSTDBgwgD/96U9GRxJCiDpJgWpF0tLSOHjwIDNmzADg17/+NSdPnmT37t0GJxNCiNrkJgkhhBCmJGdQQgghTEkKlBBCCFOSAiWEEMKUpEAJIYQwJSlQQgghTEkKlBBCCFOSAiWEEMKUpEAJIYQwJSlQQgghTOn/A1S7vssAhdZUAAAAAElFTkSuQmCC\n",
"text/plain": [
"<Figure size 432x288 with 2 Axes>"
]
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"#plot trajectory\n",
"plt.subplot(2, 2, 1)\n",
"plt.plot(x_bar[0,:],x_bar[1,:])\n",
"plt.plot(np.linspace(0,10,T+1),np.zeros(T+1),\"b-\")\n",
"plt.axis('equal')\n",
"plt.ylabel('y')\n",
"plt.xlabel('x')\n",
"\n",
"plt.subplot(2, 2, 2)\n",
"plt.plot(np.degrees(x_bar[2,:]))\n",
"plt.ylabel('theta(t) [deg]')\n",
"#plt.xlabel('time')\n",
"\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"Motion Prediction: using the state space model"
]
},
{
"cell_type": "code",
"execution_count": 7,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CPU times: user 2.35 ms, sys: 0 ns, total: 2.35 ms\n",
"Wall time: 1.66 ms\n"
]
}
],
"source": [
"%%time\n",
"\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:] = 0.2 #m/s\n",
"u_bar[1,:] = np.radians(-np.pi/4) #rad\n",
"\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = 1\n",
"x0[2] = 0\n",
"x0[3] = np.radians(0)\n",
"\n",
"x_bar=np.zeros((N,T+1))\n",
"x_bar[:,0]=x0\n",
"\n",
"for t in range (1,T+1):\n",
" xt=x_bar[:,t-1].reshape(N,1)\n",
" ut=u_bar[:,t-1].reshape(M,1)\n",
" \n",
" A,B,C=get_linear_model(xt,ut)\n",
" \n",
" xt_plus_one = np.dot(A,xt)+np.dot(B,ut)+C\n",
" \n",
" x_bar[:,t]= np.squeeze(xt_plus_one)"
]
},
{
"cell_type": "code",
"execution_count": 8,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 432x288 with 2 Axes>"
]
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"#plot trajectory\n",
"plt.subplot(2, 2, 1)\n",
"plt.plot(x_bar[0,:],x_bar[1,:])\n",
"plt.plot(np.linspace(0,10,T+1),np.zeros(T+1),\"b-\")\n",
"plt.axis('equal')\n",
"plt.ylabel('y')\n",
"plt.xlabel('x')\n",
"\n",
"plt.subplot(2, 2, 2)\n",
"plt.plot(np.degrees(x_bar[2,:]))\n",
"plt.ylabel('theta(t)')\n",
"#plt.xlabel('time')\n",
"\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"The results are the same as expected, so the linearized model is equivalent as expected."
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## PRELIMINARIES"
]
},
{
"cell_type": "code",
"execution_count": 9,
"metadata": {},
"outputs": [],
"source": [
"def compute_path_from_wp(start_xp, start_yp, step = 0.1):\n",
" \"\"\"\n",
" Computes a reference path given a set of waypoints\n",
" \"\"\"\n",
" \n",
" final_xp=[]\n",
" final_yp=[]\n",
" delta = step #[m]\n",
"\n",
" for idx in range(len(start_xp)-1):\n",
" section_len = np.sum(np.sqrt(np.power(np.diff(start_xp[idx:idx+2]),2)+np.power(np.diff(start_yp[idx:idx+2]),2)))\n",
"\n",
" interp_range = np.linspace(0,1,np.floor(section_len/delta).astype(int))\n",
" \n",
" fx=interp1d(np.linspace(0,1,2),start_xp[idx:idx+2],kind=1)\n",
" fy=interp1d(np.linspace(0,1,2),start_yp[idx:idx+2],kind=1)\n",
" \n",
" final_xp=np.append(final_xp,fx(interp_range))\n",
" final_yp=np.append(final_yp,fy(interp_range))\n",
" \n",
" dx = np.append(0, np.diff(final_xp))\n",
" dy = np.append(0, np.diff(final_yp))\n",
" theta = np.arctan2(dy, dx)\n",
"\n",
" return np.vstack((final_xp,final_yp,theta))\n",
"\n",
"\n",
"def get_nn_idx(state,path):\n",
" \"\"\"\n",
" Computes the index of the waypoint closest to vehicle\n",
" \"\"\"\n",
"\n",
" dx = state[0]-path[0,:]\n",
" dy = state[1]-path[1,:]\n",
" dist = np.hypot(dx,dy)\n",
" nn_idx = np.argmin(dist)\n",
"\n",
" try:\n",
" v = [path[0,nn_idx+1] - path[0,nn_idx],\n",
" path[1,nn_idx+1] - path[1,nn_idx]] \n",
" v /= np.linalg.norm(v)\n",
"\n",
" d = [path[0,nn_idx] - state[0],\n",
" path[1,nn_idx] - state[1]]\n",
"\n",
" if np.dot(d,v) > 0:\n",
" target_idx = nn_idx\n",
" else:\n",
" target_idx = nn_idx+1\n",
"\n",
" except IndexError as e:\n",
" target_idx = nn_idx\n",
"\n",
" return target_idx\n",
"\n",
"def get_ref_trajectory(state, path, target_v):\n",
" \"\"\"\n",
" \"\"\"\n",
" xref = np.zeros((N, T + 1))\n",
" dref = np.zeros((1, T + 1))\n",
" \n",
" #sp = np.ones((1,T +1))*target_v #speed profile\n",
" \n",
" ncourse = path.shape[1]\n",
"\n",
" ind = get_nn_idx(state, path)\n",
"\n",
" xref[0, 0] = path[0,ind] #X\n",
" xref[1, 0] = path[1,ind] #Y\n",
" xref[2, 0] = target_v #sp[ind] #V\n",
" xref[3, 0] = path[2,ind] #Theta\n",
" dref[0, 0] = 0.0 # steer operational point should be 0\n",
" \n",
" dl = 0.05 # Waypoints spacing [m]\n",
" travel = 0.0\n",
"\n",
" for i in range(T + 1):\n",
" travel += abs(target_v) * DT #current V or target V?\n",
" dind = int(round(travel / dl))\n",
"\n",
" if (ind + dind) < ncourse:\n",
" xref[0, i] = path[0,ind + dind]\n",
" xref[1, i] = path[1,ind + dind]\n",
" xref[2, i] = target_v #sp[ind + dind]\n",
" xref[3, i] = path[2,ind + dind]\n",
" dref[0, i] = 0.0\n",
" else:\n",
" xref[0, i] = path[0,ncourse - 1]\n",
" xref[1, i] = path[1,ncourse - 1]\n",
" xref[2, i] = 0.0 #stop? #sp[ncourse - 1]\n",
" xref[3, i] = path[2,ncourse - 1]\n",
" dref[0, i] = 0.0\n",
"\n",
" return xref, dref"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"### MPC Problem formulation\n",
"\n",
"**Model Predictive Control** refers to the control approach of **numerically** solving a optimization problem at each time step. \n",
"\n",
"The controller generates a control signal over a fixed lenght T (Horizon) at each time step."
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"<!-- ![mpc](img/mpc_block_diagram.png) -->\n",
"\n",
"<!-- ![mpc](img/mpc_t.png) -->"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"#### Linear MPC Formulation\n",
"\n",
"Linear MPC makes use of the **LTI** (Linear time invariant) discrete state space model, wich represents a motion model used for Prediction.\n",
"\n",
"$x_{t+1} = Ax_t + Bu_t$\n",
"\n",
"The LTI formulation means that **future states** are linearly related to the current state and actuator signal. Hence, the MPC seeks to find a **control policy** U over a finite lenght horizon.\n",
"\n",
"$U={u_{t|t}, u_{t+1|t}, ...,u_{t+T|t}}$\n",
"\n",
"The objective function used minimize (drive the state to 0) is:\n",
"\n",
"$\n",
"\\begin{equation}\n",
"\\begin{aligned}\n",
"\\min_{} \\quad & \\sum^{t+T-1}_{j=t} x^T_{j|t}Qx_{j|t} + u^T_{j|t}Ru_{j|t}\\\\\n",
"\\textrm{s.t.} \\quad & x(0) = x0\\\\\n",
" & x_{j+1|t} = Ax_{j|t}+Bu_{j|t}) \\quad \\textrm{for} \\quad t<j<t+T-1 \\\\\n",
"\\end{aligned}\n",
"\\end{equation}\n",
"$\n",
"\n",
"Other linear constrains may be applied,for instance on the control variable:\n",
"\n",
"$ U_{MIN} < u_{j|t} < U_{MAX} \\quad \\textrm{for} \\quad t<j<t+T-1 $\n",
"\n",
"The objective fuction accounts for quadratic error on deviation from 0 of the state and the control inputs sequences. Q and R are the **weight matrices** and are used to tune the response.\n",
"\n",
"Because the goal is tracking a **reference signal** such as a trajectory, the objective function is rewritten as:\n",
"\n",
"$\n",
"\\begin{equation}\n",
"\\begin{aligned}\n",
"\\min_{} \\quad & \\sum^{t+T-1}_{j=t} \\delta x^T_{j|t}Q\\delta x_{j|t} + u^T_{j|t}Ru_{j|t}\n",
"\\end{aligned}\n",
"\\end{equation}\n",
"$\n",
"\n",
"where the error w.r.t desired state is accounted for:\n",
"\n",
"$ \\delta x = x_{j,t,ref} - x_{j,t} $"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"# Problem Formulation: Study case\n",
"\n",
"In this case, the objective function to minimize is given by:\n",
"\n",
"https://borrelli.me.berkeley.edu/pdfpub/IV_KinematicMPC_jason.pdf\n",
"\n",
"$\n",
"\\begin{equation}\n",
"\\begin{aligned}\n",
"\\min_{} \\quad & \\sum^{t+T-1}_{j=t} 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",
"\n",
"Where R,P,K,Q are the cost matrices used to tune the response.\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 = 322, constraints m = 404\n",
" nnz(P) + nnz(A) = 1051\n",
"settings: linear system solver = qdldl,\n",
" eps_abs = 1.0e-05, eps_rel = 1.0e-05,\n",
" eps_prim_inf = 1.0e-04, eps_dual_inf = 1.0e-04,\n",
" rho = 1.00e-01 (adaptive),\n",
" sigma = 1.00e-06, alpha = 1.60, max_iter = 10000\n",
" check_termination: on (interval 25),\n",
" scaling: on, scaled_termination: off\n",
" warm start: on, polish: on, time_limit: off\n",
"\n",
"iter objective pri res dua res rho time\n",
" 1 0.0000e+00 5.08e+00 5.08e+02 1.00e-01 3.71e-04s\n",
" 175 1.7545e+02 5.84e-05 5.89e-05 6.89e+00 1.86e-03s\n",
"\n",
"status: solved\n",
"solution polish: unsuccessful\n",
"number of iterations: 175\n",
"optimal objective: 175.4495\n",
"run time: 3.03e-03s\n",
"optimal rho estimate: 6.44e+00\n",
"\n",
"CPU times: user 118 ms, sys: 157 µs, total: 118 ms\n",
"Wall time: 115 ms\n"
]
}
],
"source": [
"%%time\n",
"\n",
"MAX_SPEED = 1.5 #m/s\n",
"MAX_STEER = np.radians(30) #rad\n",
"MAX_ACC = 1.0\n",
"REF_VEL=1.0\n",
"\n",
"track = compute_path_from_wp([0,3,6],\n",
" [0,0,0],0.05)\n",
"\n",
"# Starting Condition\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0 #x\n",
"x0[1] = -0.25 #y\n",
"x0[2] = 0.0 #v\n",
"x0[3] = np.radians(-0) #yaw\n",
" \n",
"#starting guess\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:] = MAX_ACC/2 #a\n",
"u_bar[1,:] = 0.1 #delta\n",
"\n",
"# dynamics starting state w.r.t world frame\n",
"x_bar = np.zeros((N,T+1))\n",
"x_bar[:,0] = x0\n",
"\n",
"#prediction for linearization of costrains\n",
"for t in range (1,T+1):\n",
" xt = x_bar[:,t-1].reshape(N,1)\n",
" ut = u_bar[:,t-1].reshape(M,1)\n",
" A, B, C = get_linear_model(xt,ut)\n",
" xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n",
" x_bar[:,t] = xt_plus_one\n",
"\n",
"#CVXPY Linear MPC problem statement\n",
"x = cp.Variable((N, T+1))\n",
"u = cp.Variable((M, T))\n",
"cost = 0\n",
"constr = []\n",
"\n",
"# Cost Matrices\n",
"Q = np.diag([10,10,10,10]) #state error cost\n",
"Qf = np.diag([10,10,10,10]) #state final error cost\n",
"R = np.diag([10,10]) #input cost\n",
"R_ = np.diag([10,10]) #input rate of change cost\n",
"\n",
"#Get Reference_traj\n",
"x_ref, d_ref = get_ref_trajectory(x_bar[:,0] ,track, REF_VEL)\n",
"\n",
"#Prediction Horizon\n",
"for t in range(T):\n",
" \n",
" # Tracking Error\n",
" cost += cp.quad_form(x[:,t]-x_ref[:,t], Q)\n",
"\n",
" # Actuation effort\n",
" cost += cp.quad_form( u[:, t], R)\n",
" \n",
" # Actuation rate of change\n",
" if t < (T - 1):\n",
" cost += cp.quad_form(u[:, t + 1] - u[:, t], R_)\n",
"\n",
" # Kinrmatics Constrains (Linearized model)\n",
" A,B,C=get_linear_model(x_bar[:,t],u_bar[:,t])\n",
" constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()]\n",
"\n",
"# sums problem objectives and concatenates constraints.\n",
"constr += [x[:,0] == x_bar[:,0]] #starting condition\n",
"constr += [x[2, :] <= MAX_SPEED] #max speed\n",
"constr += [x[2, :] >= 0.0] #min_speed (not really needed)\n",
"constr += [cp.abs(u[0, :]) <= MAX_ACC] #max acc\n",
"constr += [cp.abs(u[1, :]) <= MAX_STEER] #max steer\n",
"\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",
"v_mpc=np.array(x.value[2, :]).flatten()\n",
"theta_mpc=np.array(x.value[3, :]).flatten()\n",
"a_mpc=np.array(u.value[0, :]).flatten()\n",
"delta_mpc=np.array(u.value[1, :]).flatten()\n",
"\n",
"#simulate robot state trajectory for optimized U\n",
"x_traj=predict(x0, np.vstack((a_mpc,delta_mpc)))\n",
"\n",
"#plt.figure(figsize=(15,10))\n",
"#plot trajectory\n",
"plt.subplot(2, 2, 1)\n",
"plt.plot(track[0,:],track[1,:],\"b\")\n",
"plt.plot(x_ref[0,:],x_ref[1,:],\"g+\")\n",
"plt.plot(x_traj[0,:],x_traj[1,:])\n",
"plt.axis(\"equal\")\n",
"plt.ylabel('y')\n",
"plt.xlabel('x')\n",
"\n",
"#plot v(t)\n",
"plt.subplot(2, 2, 3)\n",
"plt.plot(a_mpc)\n",
"plt.ylabel('a_in(t)')\n",
"#plt.xlabel('time')\n",
"\n",
"\n",
"plt.subplot(2, 2, 2)\n",
"plt.plot(theta_mpc)\n",
"plt.ylabel('theta(t)')\n",
"\n",
"plt.subplot(2, 2, 4)\n",
"plt.plot(delta_mpc)\n",
"plt.ylabel('d_in(t)')\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"full track demo"
]
},
{
"cell_type": "code",
"execution_count": 13,
"metadata": {},
"outputs": [
{
"name": "stderr",
"output_type": "stream",
"text": [
"/home/marcello/.conda/envs/jupyter/lib/python3.8/site-packages/cvxpy/problems/problem.py:1054: UserWarning: Solution may be inaccurate. Try another solver, adjusting the solver settings, or solve with verbose=True for more information.\n",
" warnings.warn(\n"
]
},
{
"name": "stdout",
"output_type": "stream",
"text": [
"CVXPY Optimization Time: Avrg: 0.1170s Max: 0.1765s Min: 0.1054s\n"
]
}
],
"source": [
"track = compute_path_from_wp([0,3,4,6,10,12,14,6,1,0],\n",
" [0,0,2,4,3,3,-2,-6,-2,-2],0.05)\n",
"\n",
"# track = compute_path_from_wp([0,5,7.5,10,12,13,13,10],\n",
"# [0,0,2.5,2.5,0,0,5,10],0.5)\n",
"\n",
"sim_duration = 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.5 #m/s\n",
"MAX_STEER = np.radians(30) #rad\n",
"MAX_ACC = 1.0\n",
"REF_VEL=1.0\n",
"\n",
"# Starting Condition\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0 #x\n",
"x0[1] = -0.25 #y\n",
"x0[2] = 0.0 #v\n",
"x0[3] = np.radians(-0) #yaw\n",
" \n",
"#starting guess\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:] = MAX_ACC/2 #a\n",
"u_bar[1,:] = 0.1 #delta\n",
"\n",
"for sim_time in range(sim_duration-1):\n",
" \n",
" iter_start=time.time()\n",
" \n",
" # dynamics starting state\n",
" x_bar = np.zeros((N,T+1))\n",
" x_bar[:,0] = x_sim[:,sim_time]\n",
" \n",
" #prediction for linearization of costrains\n",
" for t in range (1,T+1):\n",
" xt=x_bar[:,t-1].reshape(N,1)\n",
" ut=u_bar[:,t-1].reshape(M,1)\n",
" A,B,C=get_linear_model(xt,ut)\n",
" xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n",
" x_bar[:,t]= xt_plus_one\n",
" \n",
" #CVXPY Linear MPC problem statement\n",
" x = cp.Variable((N, T+1))\n",
" u = cp.Variable((M, T))\n",
" cost = 0\n",
" constr = []\n",
"\n",
" # Cost Matrices\n",
" Q = np.diag([20,20,10,0]) #state error cost\n",
" Qf = np.diag([10,10,10,10]) #state final error cost\n",
" R = np.diag([10,10]) #input cost\n",
" R_ = np.diag([10,10]) #input rate of change cost\n",
"\n",
" #Get Reference_traj\n",
" x_ref, d_ref = get_ref_trajectory(x_bar[:,0] ,track, REF_VEL)\n",
" \n",
" #Prediction Horizon\n",
" for t in range(T):\n",
"\n",
" # Tracking Error\n",
" cost += cp.quad_form(x[:,t]-x_ref[:,t], Q)\n",
"\n",
" # Actuation effort\n",
" cost += cp.quad_form( u[:, t], R)\n",
"\n",
" # Actuation rate of change\n",
" if t < (T - 1):\n",
" cost += cp.quad_form(u[:, t + 1] - u[:, t], R_)\n",
"\n",
" # Kinrmatics Constrains (Linearized model)\n",
" A,B,C=get_linear_model(x_bar[:,t],u_bar[:,t])\n",
" constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()]\n",
"\n",
" # sums problem objectives and concatenates constraints.\n",
" constr += [x[:,0] == x_bar[:,0]] #starting condition\n",
" constr += [x[2, :] <= MAX_SPEED] #max speed\n",
" constr += [x[2, :] >= 0.0] #min_speed (not really needed)\n",
" constr += [cp.abs(u[0, :]) <= MAX_ACC] #max acc\n",
" constr += [cp.abs(u[1, :]) <= MAX_STEER] #max steer\n",
" \n",
" # Solve\n",
" prob = cp.Problem(cp.Minimize(cost), constr)\n",
" solution = prob.solve(solver=cp.OSQP, verbose=False)\n",
" \n",
" #retrieved optimized U and assign to u_bar to linearize in next step\n",
" u_bar=np.vstack((np.array(u.value[0, :]).flatten(),\n",
" (np.array(u.value[1, :]).flatten())))\n",
" \n",
" u_sim[:,sim_time] = u_bar[:,0]\n",
" \n",
" # Measure elpased time to get results from cvxpy\n",
" opt_time.append(time.time()-iter_start)\n",
" \n",
" # move simulation to t+1\n",
" tspan = [0,DT]\n",
" x_sim[:,sim_time+1] = odeint(kinematics_model,\n",
" x_sim[:,sim_time],\n",
" tspan,\n",
" args=(u_bar[:,0],))[1]\n",
" \n",
"print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n",
" np.max(opt_time),\n",
" np.min(opt_time))) "
]
},
{
"cell_type": "code",
"execution_count": 15,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 1080x720 with 5 Axes>"
]
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"#plot trajectory\n",
"grid = plt.GridSpec(4, 5)\n",
"\n",
"plt.figure(figsize=(15,10))\n",
"\n",
"plt.subplot(grid[0:4, 0:4])\n",
"plt.plot(track[0,:],track[1,:],\"b+\")\n",
"plt.plot(x_sim[0,:],x_sim[1,:])\n",
"plt.axis(\"equal\")\n",
"plt.ylabel('y')\n",
"plt.xlabel('x')\n",
"\n",
"plt.subplot(grid[0, 4])\n",
"plt.plot(u_sim[0,:])\n",
"plt.ylabel('a(t) [m/ss]')\n",
"\n",
"plt.subplot(grid[1, 4])\n",
"plt.plot(x_sim[2,:])\n",
"plt.ylabel('v(t) [m/s]')\n",
"\n",
"plt.subplot(grid[2, 4])\n",
"plt.plot(np.degrees(u_sim[1,:]))\n",
"plt.ylabel('delta(t) [rad]')\n",
"\n",
"plt.subplot(grid[3, 4])\n",
"plt.plot(x_sim[3,:])\n",
"plt.ylabel('theta(t) [rad]')\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## OBSTACLE AVOIDANCE\n",
"see dccp paper for reference"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"import dccp\n",
"track = compute_path_from_wp([0,3,4,6,10,13],\n",
" [0,0,2,4,3,3],0.25)\n",
"\n",
"obstacles=np.array([[4,6],[2,4]])\n",
"obstacle_radius=0.5\n",
"\n",
"def to_vehic_frame(pt,pos_x,pos_y,theta):\n",
" dx = pt[0] - pos_x\n",
" dy = pt[1] - pos_y\n",
"\n",
" return [dx * np.cos(-theta) - dy * np.sin(-theta),\n",
" dy * np.cos(-theta) + dx * np.sin(-theta)]\n",
" \n",
"# track = compute_path_from_wp([0,5,7.5,10,12,13,13,10],\n",
"# [0,0,2.5,2.5,0,0,5,10],0.5)\n",
"\n",
"sim_duration = 80 #time steps\n",
"opt_time=[]\n",
"\n",
"x_sim = np.zeros((N,sim_duration))\n",
"u_sim = np.zeros((M,sim_duration-1))\n",
"\n",
"MAX_SPEED = 1.25\n",
"MIN_SPEED = 0.75\n",
"MAX_STEER_SPEED = 1.57\n",
"\n",
"# Starting Condition\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0\n",
"x0[1] = -0.25\n",
"x0[2] = np.radians(-0)\n",
"x_sim[:,0]=x0\n",
" \n",
"#starting guess\n",
"u_bar = np.zeros((M,T))\n",
"u_bar[0,:]=0.5*(MAX_SPEED+MIN_SPEED)\n",
"u_bar[1,:]=0.00\n",
"\n",
"for sim_time in range(sim_duration-1):\n",
" \n",
" iter_start=time.time()\n",
" \n",
" #compute coefficients\n",
" K=road_curve(x_sim[:,sim_time],track)\n",
" \n",
" #compute opstacles in ref frame\n",
" o_=[]\n",
" for j in range(2):\n",
" o_.append(to_vehic_frame(obstacles[:,j],x_sim[0,sim_time],x_sim[1,sim_time],x_sim[2,sim_time]) )\n",
" \n",
" # dynamics starting state w.r.t vehicle frame\n",
" x_bar=np.zeros((N,T+1))\n",
" \n",
" #prediction for linearization of costrains\n",
" for t in range (1,T+1):\n",
" xt=x_bar[:,t-1].reshape(N,1)\n",
" ut=u_bar[:,t-1].reshape(M,1)\n",
" A,B,C=get_linear_model(xt,ut)\n",
" xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n",
" x_bar[:,t]= xt_plus_one\n",
" \n",
" #CVXPY Linear MPC problem statement\n",
" cost = 0\n",
" constr = []\n",
" x = cp.Variable((N, T+1))\n",
" u = cp.Variable((M, T))\n",
" \n",
" #Prediction Horizon\n",
" for t in range(T):\n",
"\n",
" #cost += 30*cp.sum_squares(x[2,t]-np.arctan(df(x_bar[0,t],K))) # psi\n",
" cost += 50*cp.sum_squares(x[2,t]-np.arctan2(df(x_bar[0,t],K),x_bar[0,t])) # psi\n",
" cost += 20*cp.sum_squares(f(x_bar[0,t],K)-x[1,t]) # cte\n",
"\n",
" # Actuation rate of change\n",
" if t < (T - 1):\n",
" cost += cp.quad_form(u[:, t + 1] - u[:, t], 100*np.eye(M))\n",
" \n",
" # Actuation effort\n",
" cost += cp.quad_form( u[:, t],1*np.eye(M))\n",
" \n",
" # Kinrmatics Constrains (Linearized model)\n",
" A,B,C=get_linear_model(x_bar[:,t],u_bar[:,t])\n",
" constr += [x[:,t+1] == A@x[:,t] + B@u[:,t] + C.flatten()]\n",
" \n",
" # Obstacle Avoidance Contrains\n",
" for j in range(2):\n",
" constr += [ cp.norm(x[0:2,t]-o_[j],2) >= obstacle_radius ]\n",
"\n",
" # sums problem objectives and concatenates constraints.\n",
" constr += [x[:,0] == x_bar[:,0]] #<--watch out the start condition\n",
" constr += [u[0, :] <= MAX_SPEED]\n",
" constr += [u[0, :] >= MIN_SPEED]\n",
" constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED]\n",
" \n",
" # Solve\n",
" prob = cp.Problem(cp.Minimize(cost), constr)\n",
" solution = prob.solve(method=\"dccp\", verbose=False)\n",
" \n",
" #retrieved optimized U and assign to u_bar to linearize in next step\n",
" u_bar=np.vstack((np.array(u.value[0, :]).flatten(),\n",
" (np.array(u.value[1, :]).flatten())))\n",
" \n",
" u_sim[:,sim_time] = u_bar[:,0]\n",
" \n",
" # Measure elpased time to get results from cvxpy\n",
" opt_time.append(time.time()-iter_start)\n",
" \n",
" # move simulation to t+1\n",
" tspan = [0,dt]\n",
" x_sim[:,sim_time+1] = odeint(kinematics_model,\n",
" x_sim[:,sim_time],\n",
" tspan,\n",
" args=(u_bar[:,0],))[1]\n",
" \n",
"print(\"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(np.mean(opt_time),\n",
" np.max(opt_time),\n",
" np.min(opt_time))) "
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"#plot trajectory\n",
"grid = plt.GridSpec(2, 3)\n",
"\n",
"plt.figure(figsize=(15,10))\n",
"\n",
"ax=plt.subplot(grid[0:2, 0:2])\n",
"plt.plot(track[0,:],track[1,:],\"b+\")\n",
"plt.plot(x_sim[0,:],x_sim[1,:])\n",
"#obstacles\n",
"circle1=plt.Circle((obstacles[0,0], obstacles[1,0]), obstacle_radius, color='r')\n",
"circle2=plt.Circle((obstacles[0,1], obstacles[1,1]), obstacle_radius, color='r')\n",
"plt.axis(\"equal\")\n",
"plt.ylabel('y')\n",
"plt.xlabel('x')\n",
"\n",
"ax.add_artist(circle1)\n",
"ax.add_artist(circle2)\n",
"\n",
"plt.subplot(grid[0, 2])\n",
"plt.plot(u_sim[0,:])\n",
"plt.ylabel('v(t) [m/s]')\n",
"\n",
"plt.subplot(grid[1, 2])\n",
"plt.plot(np.degrees(u_sim[1,:]))\n",
"plt.ylabel('w(t) [deg/s]')\n",
"\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "code",
"execution_count": null,
"metadata": {},
"outputs": [],
"source": []
}
],
"metadata": {
"kernelspec": {
"display_name": "Python 3",
"language": "python",
"name": "python3"
},
"language_info": {
"codemirror_mode": {
"name": "ipython",
"version": 3
},
"file_extension": ".py",
"mimetype": "text/x-python",
"name": "python",
"nbconvert_exporter": "python",
"pygments_lexer": "ipython3",
"version": "3.8.5"
}
},
"nbformat": 4,
"nbformat_minor": 4
}