1084 lines
153 KiB
Plaintext
1084 lines
153 KiB
Plaintext
|
{
|
||
|
"cells": [
|
||
|
{
|
||
|
"cell_type": "code",
|
||
|
"execution_count": 77,
|
||
|
"metadata": {},
|
||
|
"outputs": [],
|
||
|
"source": [
|
||
|
"import numpy as np\n",
|
||
|
"from scipy.integrate import odeint\n",
|
||
|
"from scipy.interpolate import interp1d\n",
|
||
|
"import cvxpy as cp\n",
|
||
|
"\n",
|
||
|
"import matplotlib.pyplot as plt\n",
|
||
|
"plt.style.use(\"ggplot\")\n",
|
||
|
"\n",
|
||
|
"import time"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "markdown",
|
||
|
"metadata": {},
|
||
|
"source": [
|
||
|
"### kinematics model equations\n",
|
||
|
"\n",
|
||
|
"The variables of the model are:\n",
|
||
|
"\n",
|
||
|
"* $x$ coordinate of the robot\n",
|
||
|
"* $y$ coordinate of the robot\n",
|
||
|
"* $\\theta$ heading of the robot\n",
|
||
|
"* $\\psi$ heading error = $\\psi = \\theta_{ref} - \\theta$\n",
|
||
|
"* $cte$ crosstrack error = lateral distance of the robot from the track w.r.t robot frame, cte is a function of the track and x\n",
|
||
|
"\n",
|
||
|
"The inputs of the model are:\n",
|
||
|
"\n",
|
||
|
"* $v$ linear velocity of the robot\n",
|
||
|
"* $w$ angular velocity of the robot\n",
|
||
|
"\n",
|
||
|
"These are the differential equations f(x,u) of the model:\n",
|
||
|
"\n",
|
||
|
"* $\\dot{x} = v\\cos{\\theta}$ \n",
|
||
|
"* $\\dot{y} = v\\sin{\\theta}$\n",
|
||
|
"* $\\dot{\\theta} = w$\n",
|
||
|
"* $\\dot{\\psi} = -w$\n",
|
||
|
"* $\\dot{cte} = v\\sin{\\psi}$\n",
|
||
|
"\n",
|
||
|
"The **Continuous** State Space Model is\n",
|
||
|
"\n",
|
||
|
"$ {\\dot{x}} = Ax + Bu $\n",
|
||
|
"\n",
|
||
|
"with:\n",
|
||
|
"\n",
|
||
|
"$ A =\n",
|
||
|
"\\quad\n",
|
||
|
"\\begin{bmatrix}\n",
|
||
|
"\\frac{\\partial f(x,u)}{\\partial x} & \\frac{\\partial f(x,u)}{\\partial y} & \\frac{\\partial f(x,u)}{\\partial \\theta} & \\frac{\\partial f(x,u)}{\\partial \\psi} & \\frac{\\partial f(x,u)}{\\partial cte} \\\\\n",
|
||
|
"\\end{bmatrix}\n",
|
||
|
"\\quad\n",
|
||
|
"=\n",
|
||
|
"\\quad\n",
|
||
|
"\\begin{bmatrix}\n",
|
||
|
"0 & 0 & -vsin(\\theta) & 0 & 0 \\\\\n",
|
||
|
"0 & 0 & vcos(\\theta) & 0 & 0 \\\\\n",
|
||
|
"0 & 0 & 0 & 0 & 0 \\\\\n",
|
||
|
"0 & 0 & 0 & 0 & 0 \\\\\n",
|
||
|
"0 & 0 & 0 & vcos(\\psi) & 0 \n",
|
||
|
"\\end{bmatrix}\n",
|
||
|
"\\quad $\n",
|
||
|
"\n",
|
||
|
"\n",
|
||
|
"$ B = \\quad\n",
|
||
|
"\\begin{bmatrix}\n",
|
||
|
"\\frac{\\partial f(x,u)}{\\partial v} & \\frac{\\partial f(x,u)}{\\partial w} \\\\\n",
|
||
|
"\\end{bmatrix}\n",
|
||
|
"\\quad\n",
|
||
|
"=\n",
|
||
|
"\\quad\n",
|
||
|
"\\begin{bmatrix}\n",
|
||
|
"\\cos{\\theta_t} & 0 \\\\\n",
|
||
|
"\\sin{\\theta_t} & 0 \\\\\n",
|
||
|
"0 & 1 \\\\\n",
|
||
|
"0 & -1 \\\\\n",
|
||
|
"\\sin{(\\psi_t)} & 0 \n",
|
||
|
"\\end{bmatrix}\n",
|
||
|
"\\quad $\n",
|
||
|
"\n",
|
||
|
"discretize with forward Euler Integration for time step dt:\n",
|
||
|
"\n",
|
||
|
"* ${x_{t+1}} = x_{t} + v_t\\cos{\\theta}*dt$\n",
|
||
|
"* ${y_{t+1}} = y_{t} + v_t\\sin{\\theta}*dt$\n",
|
||
|
"* ${\\theta_{t+1}} = \\theta_{t} + w_t*dt$\n",
|
||
|
"* ${\\psi_{t+1}} = \\psi_{t} - w_t*dt$\n",
|
||
|
"* ${cte_{t+1}} = cte_{t} + v_t\\sin{\\psi}*dt$\n",
|
||
|
"\n",
|
||
|
"The **Discrete** State Space Model is then:\n",
|
||
|
"\n",
|
||
|
"${x_{t+1}} = Ax_t + Bu_t $\n",
|
||
|
"\n",
|
||
|
"with:\n",
|
||
|
"\n",
|
||
|
"$\n",
|
||
|
"A = \\quad\n",
|
||
|
"\\begin{bmatrix}\n",
|
||
|
"1 & 0 & -v\\sin{\\theta}dt & 0 & 0 \\\\\n",
|
||
|
"0 & 1 & v\\cos{\\theta}dt & 0 & 0 \\\\\n",
|
||
|
"0 & 0 & 1 & 0 & 0 \\\\\n",
|
||
|
"0 & 0 & 0 & 1 & 0 \\\\\n",
|
||
|
"0 & 0 & 0 & vcos{(\\psi)}dt & 1 \n",
|
||
|
"\\end{bmatrix}\n",
|
||
|
"\\quad\n",
|
||
|
"$\n",
|
||
|
"\n",
|
||
|
"$\n",
|
||
|
"B = \\quad\n",
|
||
|
"\\begin{bmatrix}\n",
|
||
|
"\\cos{\\theta_t}dt & 0 \\\\\n",
|
||
|
"\\sin{\\theta_t}dt & 0 \\\\\n",
|
||
|
"0 & dt \\\\\n",
|
||
|
"0 & -dt \\\\\n",
|
||
|
"\\sin{\\psi_t}dt & 0 \n",
|
||
|
"\\end{bmatrix}\n",
|
||
|
"\\quad\n",
|
||
|
"$\n",
|
||
|
"\n",
|
||
|
"This State Space Model is **non-linear** (A,B are time changing), to linearize it the **Taylor's series expansion** is used around $\\bar{x}$ and $\\bar{u}$:\n",
|
||
|
"\n",
|
||
|
"$ \\dot{x} = f(x,u) \\approx f(\\bar{x},\\bar{u}) + A(x-\\bar{x}) + B(u-\\bar{u})$\n",
|
||
|
"\n",
|
||
|
"So:\n",
|
||
|
"\n",
|
||
|
"$ x_{t+1} = x_t + (f(\\bar{x},\\bar{u}) + A(x_t-\\bar{x}) + B(u_t-\\bar{u}) )dt $\n",
|
||
|
"\n",
|
||
|
"$ x_{t+1} = (I+dtA)x_t + dtBu_t +dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\bar{u}))$\n",
|
||
|
"\n",
|
||
|
"The Discrete linearized kinematics model is\n",
|
||
|
"\n",
|
||
|
"$ x_{t+1} = A'x_t + B' u_t + C' $\n",
|
||
|
"\n",
|
||
|
"with:\n",
|
||
|
"\n",
|
||
|
"$ A' = I+dtA $\n",
|
||
|
"\n",
|
||
|
"$ B' = dtB $\n",
|
||
|
"\n",
|
||
|
"$ C' = dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\bar{u}) $"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "markdown",
|
||
|
"metadata": {},
|
||
|
"source": [
|
||
|
"-----------------\n",
|
||
|
"[About Taylor Series Expansion](https://courses.engr.illinois.edu/ece486/fa2017/documents/lecture_notes/state_space_p2.pdf):\n",
|
||
|
"\n",
|
||
|
"In order to linearize general nonlinear systems, we will use the Taylor Series expansion of functions.\n",
|
||
|
"\n",
|
||
|
"Typically it is possible to assume that the system is operating about some nominal\n",
|
||
|
"state solution $\\bar{x}$ (possibly requires a nominal input $\\bar{u}$) called **equilibrium point**.\n",
|
||
|
"\n",
|
||
|
"Recall that the Taylor Series expansion of f(x) around the\n",
|
||
|
"point $\\bar{x}$ is given by:\n",
|
||
|
"\n",
|
||
|
"$f(x)=f(\\bar{x}) + \\frac{df(x)}{dx}|_{x=\\bar{x}}(x-\\bar{x})$ + higher order terms...\n",
|
||
|
"\n",
|
||
|
"For x sufficiently close to $\\bar{x}$, these higher order terms will be very close to zero, and so we can drop them.\n",
|
||
|
"\n",
|
||
|
"The extension to functions of multiple states and inputs is very similar to the above procedure.Suppose the evolution of state x\n",
|
||
|
"is given by:\n",
|
||
|
"\n",
|
||
|
"$\\dot{x} = f(x1, x2, . . . , xn, u1, u2, . . . , um) = Ax+Bu$\n",
|
||
|
"\n",
|
||
|
"Where:\n",
|
||
|
"\n",
|
||
|
"$ A =\n",
|
||
|
"\\quad\n",
|
||
|
"\\begin{bmatrix}\n",
|
||
|
"\\frac{\\partial f(x,u)}{\\partial x1} & ... & \\frac{\\partial f(x,u)}{\\partial xn} \\\\\n",
|
||
|
"\\end{bmatrix}\n",
|
||
|
"\\quad\n",
|
||
|
"$ and $ B = \\quad\n",
|
||
|
"\\begin{bmatrix}\n",
|
||
|
"\\frac{\\partial f(x,u)}{\\partial u1} & ... & \\frac{\\partial f(x,u)}{\\partial um} \\\\\n",
|
||
|
"\\end{bmatrix}\n",
|
||
|
"\\quad $\n",
|
||
|
"\n",
|
||
|
"Then:\n",
|
||
|
"\n",
|
||
|
"$f(x,u)=f(\\bar{x},\\bar{u}) + \\frac{df(x,u)}{dx}|_{x=\\bar{x}}(x-\\bar{x}) + \\frac{df(x,u)}{du}|_{u=\\bar{u}}(u-\\bar{u}) = f(\\bar{x},\\bar{u}) + A_{x=\\bar{x}}(x-\\bar{x}) + B_{u=\\bar{u}}(u-\\bar{u})$\n",
|
||
|
"\n",
|
||
|
"-----------------"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "markdown",
|
||
|
"metadata": {},
|
||
|
"source": [
|
||
|
"### Kinematics Model"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "code",
|
||
|
"execution_count": 78,
|
||
|
"metadata": {},
|
||
|
"outputs": [],
|
||
|
"source": [
|
||
|
"# Control problem statement.\n",
|
||
|
"\n",
|
||
|
"N = 5 #number of state variables\n",
|
||
|
"M = 2 #number of control variables\n",
|
||
|
"T = 20 #Prediction Horizon\n",
|
||
|
"dt = 0.25 #discretization step"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "code",
|
||
|
"execution_count": 79,
|
||
|
"metadata": {},
|
||
|
"outputs": [],
|
||
|
"source": [
|
||
|
"def get_linear_model(x_bar,u_bar):\n",
|
||
|
" \"\"\"\n",
|
||
|
" \"\"\"\n",
|
||
|
" \n",
|
||
|
" x = x_bar[0]\n",
|
||
|
" y = x_bar[1]\n",
|
||
|
" theta = x_bar[2]\n",
|
||
|
" psi = x_bar[3]\n",
|
||
|
" cte = x_bar[4]\n",
|
||
|
" \n",
|
||
|
" v = u_bar[0]\n",
|
||
|
" w = u_bar[1]\n",
|
||
|
" \n",
|
||
|
" A = np.zeros((N,N))\n",
|
||
|
" A[0,2]=-v*np.sin(theta)\n",
|
||
|
" A[1,2]=v*np.cos(theta)\n",
|
||
|
" A[4,3]=v*np.cos(psi)\n",
|
||
|
" A_lin=np.eye(N)+dt*A\n",
|
||
|
" \n",
|
||
|
" B = np.zeros((N,M))\n",
|
||
|
" B[0,0]=np.cos(theta)\n",
|
||
|
" B[1,0]=np.sin(theta)\n",
|
||
|
" B[2,1]=1\n",
|
||
|
" B[3,1]=-1\n",
|
||
|
" B[4,0]=np.sin(psi)\n",
|
||
|
" B_lin=dt*B\n",
|
||
|
" \n",
|
||
|
" f_xu=np.array([v*np.cos(theta),v*np.sin(theta),w,-w,v*np.sin(-psi)]).reshape(N,1)\n",
|
||
|
" C_lin = dt*(f_xu - np.dot(A,x_bar.reshape(N,1)) - np.dot(B,u_bar.reshape(M,1)))\n",
|
||
|
" \n",
|
||
|
" return A_lin,B_lin,C_lin"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "markdown",
|
||
|
"metadata": {},
|
||
|
"source": [
|
||
|
"Motion Prediction: using scipy intergration"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "code",
|
||
|
"execution_count": 80,
|
||
|
"metadata": {},
|
||
|
"outputs": [],
|
||
|
"source": [
|
||
|
"# Define process model\n",
|
||
|
"def kinematics_model(x,t,u):\n",
|
||
|
" \"\"\"\n",
|
||
|
" \"\"\"\n",
|
||
|
"\n",
|
||
|
" dxdt = u[0]*np.cos(x[2])\n",
|
||
|
" dydt = u[0]*np.sin(x[2])\n",
|
||
|
" dthetadt = u[1]\n",
|
||
|
" dpsidt = -u[1]\n",
|
||
|
" dctedt = u[0]*np.sin(-x[3])\n",
|
||
|
"\n",
|
||
|
" dqdt = [dxdt,\n",
|
||
|
" dydt,\n",
|
||
|
" dthetadt,\n",
|
||
|
" dpsidt,\n",
|
||
|
" dctedt]\n",
|
||
|
"\n",
|
||
|
" return dqdt\n",
|
||
|
"\n",
|
||
|
"def predict(x0,u):\n",
|
||
|
" \"\"\"\n",
|
||
|
" \"\"\"\n",
|
||
|
" \n",
|
||
|
" x_bar = np.zeros((N,T+1))\n",
|
||
|
" \n",
|
||
|
" x_bar[:,0] = x0\n",
|
||
|
" \n",
|
||
|
" # solve ODE\n",
|
||
|
" for t in range(1,T+1):\n",
|
||
|
"\n",
|
||
|
" tspan = [0,dt]\n",
|
||
|
" x_next = odeint(kinematics_model,\n",
|
||
|
" x0,\n",
|
||
|
" tspan,\n",
|
||
|
" args=(u[:,t-1],))\n",
|
||
|
"\n",
|
||
|
" x0 = x_next[1]\n",
|
||
|
" x_bar[:,t]=x_next[1]\n",
|
||
|
" \n",
|
||
|
" return x_bar"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "markdown",
|
||
|
"metadata": {},
|
||
|
"source": [
|
||
|
"Validate the model, here the status w.r.t a straight line with constant heading 0"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "code",
|
||
|
"execution_count": 81,
|
||
|
"metadata": {},
|
||
|
"outputs": [
|
||
|
{
|
||
|
"name": "stdout",
|
||
|
"output_type": "stream",
|
||
|
"text": [
|
||
|
"CPU times: user 7.22 ms, sys: 0 ns, total: 7.22 ms\n",
|
||
|
"Wall time: 5.83 ms\n"
|
||
|
]
|
||
|
}
|
||
|
],
|
||
|
"source": [
|
||
|
"%%time\n",
|
||
|
"\n",
|
||
|
"u_bar = np.zeros((M,T))\n",
|
||
|
"u_bar[0,:] = 1 #m/s\n",
|
||
|
"u_bar[1,:] = np.radians(-10) #rad/s\n",
|
||
|
"\n",
|
||
|
"x0 = np.zeros(N)\n",
|
||
|
"x0[0] = 0\n",
|
||
|
"x0[1] = 1\n",
|
||
|
"x0[2] = np.radians(0)\n",
|
||
|
"x0[3] = 0\n",
|
||
|
"x0[4] = 1\n",
|
||
|
"\n",
|
||
|
"x_bar=predict(x0,u_bar)"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "markdown",
|
||
|
"metadata": {},
|
||
|
"source": [
|
||
|
"Check the model prediction"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "code",
|
||
|
"execution_count": 82,
|
||
|
"metadata": {},
|
||
|
"outputs": [
|
||
|
{
|
||
|
"data": {
|
||
|
"image/png": "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
|
||
|
"text/plain": [
|
||
|
"<Figure size 432x288 with 4 Axes>"
|
||
|
]
|
||
|
},
|
||
|
"metadata": {},
|
||
|
"output_type": "display_data"
|
||
|
}
|
||
|
],
|
||
|
"source": [
|
||
|
"#plot trajectory\n",
|
||
|
"plt.subplot(2, 2, 1)\n",
|
||
|
"plt.plot(x_bar[0,:],x_bar[1,:])\n",
|
||
|
"plt.plot(np.linspace(0,10,T+1),np.zeros(T+1),\"b-\")\n",
|
||
|
"plt.axis('equal')\n",
|
||
|
"plt.ylabel('y')\n",
|
||
|
"plt.xlabel('x')\n",
|
||
|
"\n",
|
||
|
"plt.subplot(2, 2, 2)\n",
|
||
|
"plt.plot(np.degrees(x_bar[2,:]))\n",
|
||
|
"plt.ylabel('theta(t) [deg]')\n",
|
||
|
"#plt.xlabel('time')\n",
|
||
|
"\n",
|
||
|
"plt.subplot(2, 2, 3)\n",
|
||
|
"plt.plot(np.degrees(x_bar[3,:]))\n",
|
||
|
"plt.ylabel('psi(t) [deg]')\n",
|
||
|
"#plt.xlabel('time')\n",
|
||
|
"\n",
|
||
|
"plt.subplot(2, 2, 4)\n",
|
||
|
"plt.plot(x_bar[4,:])\n",
|
||
|
"plt.ylabel('cte(t)')\n",
|
||
|
"\n",
|
||
|
"plt.tight_layout()\n",
|
||
|
"plt.show()"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "markdown",
|
||
|
"metadata": {},
|
||
|
"source": [
|
||
|
"the results seems valid:\n",
|
||
|
"* the cte is correct\n",
|
||
|
"* theta error is correct"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "markdown",
|
||
|
"metadata": {},
|
||
|
"source": [
|
||
|
"Motion Prediction: using the state space model"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "code",
|
||
|
"execution_count": 83,
|
||
|
"metadata": {},
|
||
|
"outputs": [
|
||
|
{
|
||
|
"name": "stdout",
|
||
|
"output_type": "stream",
|
||
|
"text": [
|
||
|
"CPU times: user 2.58 ms, sys: 0 ns, total: 2.58 ms\n",
|
||
|
"Wall time: 1.89 ms\n"
|
||
|
]
|
||
|
}
|
||
|
],
|
||
|
"source": [
|
||
|
"%%time\n",
|
||
|
"\n",
|
||
|
"u_bar = np.zeros((M,T))\n",
|
||
|
"u_bar[0,:] = 1 #m/s\n",
|
||
|
"u_bar[1,:] = np.radians(-10) #rad/s\n",
|
||
|
"\n",
|
||
|
"x0 = np.zeros(N)\n",
|
||
|
"x0[0] = 0\n",
|
||
|
"x0[1] = 1\n",
|
||
|
"x0[2] = np.radians(0)\n",
|
||
|
"x0[3] = 0\n",
|
||
|
"x0[4] = 1\n",
|
||
|
"\n",
|
||
|
"x_bar=np.zeros((N,T+1))\n",
|
||
|
"x_bar[:,0]=x0\n",
|
||
|
"\n",
|
||
|
"for t in range (1,T+1):\n",
|
||
|
" xt=x_bar[:,t-1].reshape(5,1)\n",
|
||
|
" ut=u_bar[:,t-1].reshape(2,1)\n",
|
||
|
" \n",
|
||
|
" A,B,C=get_linear_model(xt,ut)\n",
|
||
|
" \n",
|
||
|
" xt_plus_one = np.dot(A,xt)+np.dot(B,ut)+C\n",
|
||
|
" \n",
|
||
|
" x_bar[:,t]= np.squeeze(xt_plus_one)"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "code",
|
||
|
"execution_count": 84,
|
||
|
"metadata": {},
|
||
|
"outputs": [
|
||
|
{
|
||
|
"data": {
|
||
|
"image/png": "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
|
||
|
"text/plain": [
|
||
|
"<Figure size 432x288 with 4 Axes>"
|
||
|
]
|
||
|
},
|
||
|
"metadata": {},
|
||
|
"output_type": "display_data"
|
||
|
}
|
||
|
],
|
||
|
"source": [
|
||
|
"#plot trajectory\n",
|
||
|
"plt.subplot(2, 2, 1)\n",
|
||
|
"plt.plot(x_bar[0,:],x_bar[1,:])\n",
|
||
|
"plt.plot(np.linspace(0,10,T+1),np.zeros(T+1),\"b-\")\n",
|
||
|
"plt.axis('equal')\n",
|
||
|
"plt.ylabel('y')\n",
|
||
|
"plt.xlabel('x')\n",
|
||
|
"\n",
|
||
|
"plt.subplot(2, 2, 2)\n",
|
||
|
"plt.plot(x_bar[2,:])\n",
|
||
|
"plt.ylabel('theta(t)')\n",
|
||
|
"#plt.xlabel('time')\n",
|
||
|
"\n",
|
||
|
"plt.subplot(2, 2, 3)\n",
|
||
|
"plt.plot(x_bar[3,:])\n",
|
||
|
"plt.ylabel('psi(t)')\n",
|
||
|
"#plt.xlabel('time')\n",
|
||
|
"\n",
|
||
|
"plt.subplot(2, 2, 4)\n",
|
||
|
"plt.plot(x_bar[4,:])\n",
|
||
|
"plt.ylabel('cte(t)')\n",
|
||
|
"\n",
|
||
|
"plt.tight_layout()\n",
|
||
|
"plt.show()"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "markdown",
|
||
|
"metadata": {},
|
||
|
"source": [
|
||
|
"The results are the same as expected"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "markdown",
|
||
|
"metadata": {},
|
||
|
"source": [
|
||
|
"------------------\n",
|
||
|
"\n",
|
||
|
"the kinematics model predictits psi and cte for constant heading references. So, for non-constant paths appropriate functions have to be developed.\n",
|
||
|
"\n",
|
||
|
"-----------------"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "markdown",
|
||
|
"metadata": {},
|
||
|
"source": [
|
||
|
"## PRELIMINARIES"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "code",
|
||
|
"execution_count": 85,
|
||
|
"metadata": {},
|
||
|
"outputs": [],
|
||
|
"source": [
|
||
|
"def compute_path_from_wp(start_xp, start_yp, step = 0.1):\n",
|
||
|
" final_xp=[]\n",
|
||
|
" final_yp=[]\n",
|
||
|
" delta = step #[m]\n",
|
||
|
"\n",
|
||
|
" for idx in range(len(start_xp)-1):\n",
|
||
|
" section_len = np.sum(np.sqrt(np.power(np.diff(start_xp[idx:idx+2]),2)+np.power(np.diff(start_yp[idx:idx+2]),2)))\n",
|
||
|
"\n",
|
||
|
" interp_range = np.linspace(0,1,np.floor(section_len/delta).astype(int))\n",
|
||
|
" \n",
|
||
|
" fx=interp1d(np.linspace(0,1,2),start_xp[idx:idx+2],kind=1)\n",
|
||
|
" fy=interp1d(np.linspace(0,1,2),start_yp[idx:idx+2],kind=1)\n",
|
||
|
" \n",
|
||
|
" final_xp=np.append(final_xp,fx(interp_range))\n",
|
||
|
" final_yp=np.append(final_yp,fy(interp_range))\n",
|
||
|
"\n",
|
||
|
" return np.vstack((final_xp,final_yp))\n",
|
||
|
"\n",
|
||
|
"def get_nn_idx(state,path):\n",
|
||
|
"\n",
|
||
|
" dx = state[0]-path[0,:]\n",
|
||
|
" dy = state[1]-path[1,:]\n",
|
||
|
" dist = np.sqrt(dx**2 + dy**2)\n",
|
||
|
" nn_idx = np.argmin(dist)\n",
|
||
|
"\n",
|
||
|
" try:\n",
|
||
|
" v = [path[0,nn_idx+1] - path[0,nn_idx],\n",
|
||
|
" path[1,nn_idx+1] - path[1,nn_idx]] \n",
|
||
|
" v /= np.linalg.norm(v)\n",
|
||
|
"\n",
|
||
|
" d = [path[0,nn_idx] - state[0],\n",
|
||
|
" path[1,nn_idx] - state[1]]\n",
|
||
|
"\n",
|
||
|
" if np.dot(d,v) > 0:\n",
|
||
|
" target_idx = nn_idx\n",
|
||
|
" else:\n",
|
||
|
" target_idx = nn_idx+1\n",
|
||
|
"\n",
|
||
|
" except IndexError as e:\n",
|
||
|
" target_idx = nn_idx\n",
|
||
|
"\n",
|
||
|
" return target_idx\n",
|
||
|
"\n",
|
||
|
"def road_curve(state,track):\n",
|
||
|
" \n",
|
||
|
" #given vehicle pos find lookahead waypoints\n",
|
||
|
" nn_idx=get_nn_idx(state,track)\n",
|
||
|
" LOOKAHED=6\n",
|
||
|
" lk_wp=track[:,nn_idx:nn_idx+LOOKAHED]\n",
|
||
|
"\n",
|
||
|
" #trasform lookahead waypoints to vehicle ref frame\n",
|
||
|
" dx = lk_wp[0,:] - state[0]\n",
|
||
|
" dy = lk_wp[1,:] - state[1]\n",
|
||
|
"\n",
|
||
|
" wp_vehicle_frame = np.vstack(( dx * np.cos(-state[2]) - dy * np.sin(-state[2]),\n",
|
||
|
" dy * np.cos(-state[2]) + dx * np.sin(-state[2]) ))\n",
|
||
|
"\n",
|
||
|
" #fit poly\n",
|
||
|
" return np.polyfit(wp_vehicle_frame[0,:], wp_vehicle_frame[1,:], 3, rcond=None, full=False, w=None, cov=False)\n",
|
||
|
"\n",
|
||
|
"def f(x,coeff):\n",
|
||
|
" return coeff[0]*x**3+coeff[1]*x**2+coeff[2]*x**1+coeff[3]*x**0\n",
|
||
|
"\n",
|
||
|
"def df(x,coeff):\n",
|
||
|
" return 3*coeff[0]*x**2+2*coeff[1]*x+coeff[2]"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "markdown",
|
||
|
"metadata": {},
|
||
|
"source": [
|
||
|
"test it"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "markdown",
|
||
|
"metadata": {},
|
||
|
"source": [
|
||
|
"### MPC Problem formulation\n",
|
||
|
"\n",
|
||
|
"**Model Predictive Control** refers to the control approach of **numerically** solving a optimization problem at each time step. \n",
|
||
|
"\n",
|
||
|
"The controller generates a control signal over a fixed lenght T (Horizon) at each time step."
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "markdown",
|
||
|
"metadata": {},
|
||
|
"source": [
|
||
|
"\n",
|
||
|
"\n",
|
||
|
""
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"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": 110,
|
||
|
"metadata": {},
|
||
|
"outputs": [],
|
||
|
"source": [
|
||
|
"track = compute_path_from_wp([0,10],[0,0])\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",
|
||
|
"K=road_curve(x0,track)\n",
|
||
|
"\n",
|
||
|
"x0[3]=-np.arctan(K[2])\n",
|
||
|
"x0[4]=K[3]\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",
|
||
|
"x_bar[:,0]=x0\n",
|
||
|
"\n",
|
||
|
"for t in range (1,T+1):\n",
|
||
|
" xt=x_bar[:,t].reshape(5,1)\n",
|
||
|
" ut=u_bar[:,t-1].reshape(2,1)\n",
|
||
|
" \n",
|
||
|
" A,B,C=get_linear_model(xt,ut)\n",
|
||
|
" \n",
|
||
|
" xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n",
|
||
|
" \n",
|
||
|
" xt_plus_one[3]=-np.arctan(df(x_bar[0,t],K))\n",
|
||
|
" xt_plus_one[4]=f(x_bar[0,t],K)\n",
|
||
|
" x_bar[:,t]= xt_plus_one\n",
|
||
|
"#################################################\n"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "code",
|
||
|
"execution_count": 111,
|
||
|
"metadata": {},
|
||
|
"outputs": [
|
||
|
{
|
||
|
"name": "stdout",
|
||
|
"output_type": "stream",
|
||
|
"text": [
|
||
|
"-----------------------------------------------------------------\n",
|
||
|
" OSQP v0.6.0 - Operator Splitting QP Solver\n",
|
||
|
" (c) Bartolomeo Stellato, Goran Banjac\n",
|
||
|
" University of Oxford - Stanford University 2019\n",
|
||
|
"-----------------------------------------------------------------\n",
|
||
|
"problem: variables n = 283, constraints m = 323\n",
|
||
|
" nnz(P) + nnz(A) = 859\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.06e+02 1.00e-01 3.10e-04s\n",
|
||
|
" 200 2.6661e+03 1.40e-02 3.46e-02 1.86e+01 1.82e-03s\n",
|
||
|
" 400 2.6955e+03 5.00e-04 1.18e-03 1.86e+01 3.67e-03s\n",
|
||
|
" 575 2.6965e+03 3.06e-05 7.23e-05 1.86e+01 4.96e-03s\n",
|
||
|
"\n",
|
||
|
"status: solved\n",
|
||
|
"solution polish: unsuccessful\n",
|
||
|
"number of iterations: 575\n",
|
||
|
"optimal objective: 2696.5396\n",
|
||
|
"run time: 5.74e-03s\n",
|
||
|
"optimal rho estimate: 4.38e+01\n",
|
||
|
"\n",
|
||
|
"CPU times: user 228 ms, sys: 204 µs, total: 228 ms\n",
|
||
|
"Wall time: 221 ms\n"
|
||
|
]
|
||
|
}
|
||
|
],
|
||
|
"source": [
|
||
|
"%%time\n",
|
||
|
"\n",
|
||
|
"x = cp.Variable((N, T+1))\n",
|
||
|
"u = cp.Variable((M, T))\n",
|
||
|
"\n",
|
||
|
"#CVXPY Linear MPC problem statement\n",
|
||
|
"cost = 0\n",
|
||
|
"constr = []\n",
|
||
|
"\n",
|
||
|
"for t in range(T):\n",
|
||
|
" \n",
|
||
|
" # Cost function\n",
|
||
|
" cost += 10*cp.sum_squares( x[3, t]) # psi\n",
|
||
|
" cost += 500*cp.sum_squares( x[4, t]) # cte\n",
|
||
|
" \n",
|
||
|
" # Actuation effort\n",
|
||
|
" cost += cp.quad_form( u[:, t],10*np.eye(M))\n",
|
||
|
" \n",
|
||
|
" # Actuation rate of change\n",
|
||
|
" if t < (T - 1):\n",
|
||
|
" cost += cp.quad_form(u[:, t + 1] - u[:, t], 5*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] == x0]\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": "markdown",
|
||
|
"metadata": {},
|
||
|
"source": [
|
||
|
"Print Results:"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "code",
|
||
|
"execution_count": 112,
|
||
|
"metadata": {},
|
||
|
"outputs": [
|
||
|
{
|
||
|
"name": "stderr",
|
||
|
"output_type": "stream",
|
||
|
"text": [
|
||
|
"No handles with labels found to put in legend.\n"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"data": {
|
||
|
"image/png": "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
|
||
|
"text/plain": [
|
||
|
"<Figure size 432x288 with 4 Axes>"
|
||
|
]
|
||
|
},
|
||
|
"metadata": {},
|
||
|
"output_type": "display_data"
|
||
|
}
|
||
|
],
|
||
|
"source": [
|
||
|
"x_mpc=np.array(x.value[0, :]).flatten()\n",
|
||
|
"y_mpc=np.array(x.value[1, :]).flatten()\n",
|
||
|
"theta_mpc=np.array(x.value[2, :]).flatten()\n",
|
||
|
"psi_mpc=np.array(x.value[3, :]).flatten()\n",
|
||
|
"cte_mpc=np.array(x.value[4, :]).flatten()\n",
|
||
|
"v_mpc=np.array(u.value[0, :]).flatten()\n",
|
||
|
"w_mpc=np.array(u.value[1, :]).flatten()\n",
|
||
|
"\n",
|
||
|
"#simulate robot state trajectory for optimized U\n",
|
||
|
"x_traj=predict(x0, np.vstack((v_mpc,w_mpc)))\n",
|
||
|
"\n",
|
||
|
"#plt.figure(figsize=(15,10))\n",
|
||
|
"#plot trajectory\n",
|
||
|
"plt.subplot(2, 2, 1)\n",
|
||
|
"plt.plot(track[0,:],track[1,:],\"b*\")\n",
|
||
|
"plt.plot(x_traj[0,:],x_traj[1,:])\n",
|
||
|
"plt.axis(\"equal\")\n",
|
||
|
"plt.ylabel('y')\n",
|
||
|
"plt.xlabel('x')\n",
|
||
|
"\n",
|
||
|
"#plot v(t)\n",
|
||
|
"plt.subplot(2, 2, 2)\n",
|
||
|
"plt.plot(v_mpc)\n",
|
||
|
"plt.ylabel('v(t)')\n",
|
||
|
"#plt.xlabel('time')\n",
|
||
|
"\n",
|
||
|
"#plot w(t)\n",
|
||
|
"plt.subplot(2, 2, 3)\n",
|
||
|
"plt.plot(w_mpc)\n",
|
||
|
"plt.ylabel('w(t)')\n",
|
||
|
"#plt.xlabel('time')\n",
|
||
|
"\n",
|
||
|
"plt.subplot(2, 2, 4)\n",
|
||
|
"plt.plot(cte_mpc)\n",
|
||
|
"plt.ylabel('cte(t)')\n",
|
||
|
"plt.legend(loc='best')\n",
|
||
|
"\n",
|
||
|
"plt.tight_layout()\n",
|
||
|
"plt.show()"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "markdown",
|
||
|
"metadata": {},
|
||
|
"source": [
|
||
|
"full track demo"
|
||
|
]
|
||
|
},
|
||
|
{
|
||
|
"cell_type": "code",
|
||
|
"execution_count": 93,
|
||
|
"metadata": {},
|
||
|
"outputs": [
|
||
|
{
|
||
|
"name": "stdout",
|
||
|
"output_type": "stream",
|
||
|
"text": [
|
||
|
"CVXPY Optimization Time: Avrg: 0.1988s Max: 0.2729s Min: 0.1579s\n"
|
||
|
]
|
||
|
}
|
||
|
],
|
||
|
"source": [
|
||
|
"track = compute_path_from_wp([0,3,4,6],\n",
|
||
|
" [0,0,2,1])\n",
|
||
|
"\n",
|
||
|
"sim_duration = 20\n",
|
||
|
"opt_time=[]\n",
|
||
|
"\n",
|
||
|
"x_sim = np.zeros((N,sim_duration))\n",
|
||
|
"u_sim = np.zeros((M,sim_duration-1))\n",
|
||
|
"\n",
|
||
|
"MAX_SPEED = 1.25\n",
|
||
|
"MIN_SPEED = 0.75\n",
|
||
|
"MAX_STEER_SPEED = 1.57/2\n",
|
||
|
"\n",
|
||
|
"# Starting Condition\n",
|
||
|
"x0 = np.zeros(N)\n",
|
||
|
"x0[0] = 0\n",
|
||
|
"x0[1] = -0.25\n",
|
||
|
"x0[2] = np.radians(-0)\n",
|
||
|
"\n",
|
||
|
"K=road_curve(x0,track)\n",
|
||
|
"\n",
|
||
|
"x0[3]=-np.arctan(K[2])\n",
|
||
|
"x0[4]=K[3]\n",
|
||
|
"\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\n",
|
||
|
" x_bar=np.zeros((N,T+1))\n",
|
||
|
" x_bar[:,0]=x_sim[:,sim_time]\n",
|
||
|
" for t in range (1,T+1):\n",
|
||
|
" xt=x_bar[:,t].reshape(5,1)\n",
|
||
|
" ut=u_bar[:,t-1].reshape(2,1)\n",
|
||
|
"\n",
|
||
|
" A,B,C=get_linear_model(xt,ut)\n",
|
||
|
"\n",
|
||
|
" xt_plus_one = np.squeeze(np.dot(A,xt)+np.dot(B,ut)+C)\n",
|
||
|
"\n",
|
||
|
" xt_plus_one[3]=-np.arctan(df(x_bar[0,t],K))\n",
|
||
|
" xt_plus_one[4]=f(x_bar[0,t],K)\n",
|
||
|
" x_bar[:,t]= xt_plus_one\n",
|
||
|
" \n",
|
||
|
" #CVXPY Linear MPC problem statement\n",
|
||
|
" cost = 0\n",
|
||
|
" constr = []\n",
|
||
|
" x = cp.Variable((N, T+1))\n",
|
||
|
" u = cp.Variable((M, T))\n",
|
||
|
" \n",
|
||
|
" for t in range(T):\n",
|
||
|
"\n",
|
||
|
" # Tracking\n",
|
||
|
" cost += 50*cp.sum_squares( x[3, t]) # psi\n",
|
||
|
" cost += 1000*cp.sum_squares( x[4, t]) # cte\n",
|
||
|
"\n",
|
||
|
" # Actuation rate of change\n",
|
||
|
" if t < (T - 1):\n",
|
||
|
" cost += cp.quad_form(u[:, t + 1] - u[:, t], 10*np.eye(M))\n",
|
||
|
" \n",
|
||
|
" # Actuation effort\n",
|
||
|
" cost += cp.quad_form( u[:, t],10*np.eye(M))\n",
|
||
|
" \n",
|
||
|
" # Constrains\n",
|
||
|
" A,B,C=get_linear_model(x_bar[:,t],u_bar[:,t])\n",
|
||
|
" constr += [x[:,t+1] == A*x[:,t] + B*u[:,t] + C.flatten()]\n",
|
||
|
"\n",
|
||
|
" # sums problem objectives and concatenates constraints.\n",
|
||
|
" constr += [x[:,0] == x_sim[:,sim_time]] # starting 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[:,1],))[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": 92,
|
||
|
"metadata": {},
|
||
|
"outputs": [
|
||
|
{
|
||
|
"data": {
|
||
|
"image/png": "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
|
||
|
"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
|
||
|
}
|