1262 lines
218 KiB
Plaintext
1262 lines
218 KiB
Plaintext
{
|
|
"cells": [
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": 17,
|
|
"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",
|
|
"\n",
|
|
"plt.style.use(\"ggplot\")\n",
|
|
"\n",
|
|
"import time"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "markdown",
|
|
"metadata": {},
|
|
"source": [
|
|
"### kinematics model equations\n",
|
|
"\n",
|
|
"The variables of the model are:\n",
|
|
"\n",
|
|
"* $x$ coordinate of the robot\n",
|
|
"* $y$ coordinate of the robot\n",
|
|
"* $\\theta$ heading of the robot\n",
|
|
"\n",
|
|
"The inputs of the model are:\n",
|
|
"\n",
|
|
"* $v$ linear velocity of the robot\n",
|
|
"* $w$ angular velocity of the robot\n",
|
|
"\n",
|
|
"These are the differential equations f(x,u) of the model:\n",
|
|
"\n",
|
|
"$\\dot{x} = f(x,u)$\n",
|
|
"\n",
|
|
"* $\\dot{x} = v\\cos{\\theta}$ \n",
|
|
"* $\\dot{y} = v\\sin{\\theta}$\n",
|
|
"* $\\dot{\\theta} = w$\n",
|
|
"\n",
|
|
"Discretize with forward Euler Integration for time step dt:\n",
|
|
"\n",
|
|
"${x_{t+1}} = x_{t} + f(x,u)dt$\n",
|
|
"\n",
|
|
"* ${x_{t+1}} = x_{t} + v_t\\cos{\\theta}dt$\n",
|
|
"* ${y_{t+1}} = y_{t} + v_t\\sin{\\theta}dt$\n",
|
|
"* ${\\theta_{t+1}} = \\theta_{t} + w_t dt$\n",
|
|
"\n",
|
|
"----------------------\n",
|
|
"\n",
|
|
"The Model is **non-linear** and **time variant**, but the Numerical Optimizer requires a Linear sets of equations. To approximate the equivalent **LTI** State space model, the **Taylor's series expansion** is used around $\\bar{x}$ and $\\bar{u}$ (at each time step):\n",
|
|
"\n",
|
|
"$ f(x,u) \\approx f(\\bar{x},\\bar{u}) + \\frac{\\partial f(x,u)}{\\partial x}|_{x=\\bar{x},u=\\bar{u}}(x-\\bar{x}) + \\frac{\\partial f(x,u)}{\\partial u}|_{x=\\bar{x},u=\\bar{u}}(u-\\bar{u})$\n",
|
|
"\n",
|
|
"This can be rewritten usibg the State Space model form Ax+Bu :\n",
|
|
"\n",
|
|
"$ f(\\bar{x},\\bar{u}) + A|_{x=\\bar{x},u=\\bar{u}}(x-\\bar{x}) + B|_{x=\\bar{x},u=\\bar{u}}(u-\\bar{u})$\n",
|
|
"\n",
|
|
"Where:\n",
|
|
"\n",
|
|
"$\n",
|
|
"A =\n",
|
|
"\\quad\n",
|
|
"\\begin{bmatrix}\n",
|
|
"\\frac{\\partial f(x,u)}{\\partial x} & \\frac{\\partial f(x,u)}{\\partial y} & \\frac{\\partial f(x,u)}{\\partial \\theta} \\\\\n",
|
|
"\\end{bmatrix}\n",
|
|
"\\quad\n",
|
|
"=\n",
|
|
"\\quad\n",
|
|
"\\begin{bmatrix}\n",
|
|
"0 & 0 & -v\\sin{\\theta} \\\\\n",
|
|
"0 & 0 & v\\cos{\\theta} \\\\\n",
|
|
"0 & 0 & 0\\\\\n",
|
|
"\\end{bmatrix}\n",
|
|
"\\quad\n",
|
|
"$\n",
|
|
"\n",
|
|
"and\n",
|
|
"\n",
|
|
"$\n",
|
|
"B = \n",
|
|
"\\quad\n",
|
|
"\\begin{bmatrix}\n",
|
|
"\\frac{\\partial f(x,u)}{\\partial v} & \\frac{\\partial f(x,u)}{\\partial w} \\\\\n",
|
|
"\\end{bmatrix}\n",
|
|
"\\quad\n",
|
|
"= \n",
|
|
"\\quad\n",
|
|
"\\begin{bmatrix}\n",
|
|
"\\cos{\\theta} & 0 \\\\\n",
|
|
"\\sin{\\theta} & 0 \\\\\n",
|
|
"0 & 1\n",
|
|
"\\end{bmatrix}\n",
|
|
"\\quad\n",
|
|
"$\n",
|
|
"\n",
|
|
"are the *Jacobians*.\n",
|
|
"\n",
|
|
"\n",
|
|
"\n",
|
|
"So the discretized model is given by:\n",
|
|
"\n",
|
|
"$ x_{t+1} = x_t + (f(\\bar{x},\\bar{u}) + A|_{x=\\bar{x}}(x_t-\\bar{x}) + B|_{u=\\bar{u}}(u_t-\\bar{u}) )dt $\n",
|
|
"\n",
|
|
"$ x_{t+1} = (I+dtA)x_t + dtBu_t +dt(f(\\bar{x},\\bar{u}) - A\\bar{x} - B\\bar{u}))$\n",
|
|
"\n",
|
|
"The LTI-equivalent kinematics model is:\n",
|
|
"\n",
|
|
"$ x_{t+1} = A'x_t + B' u_t + C' $\n",
|
|
"\n",
|
|
"with:\n",
|
|
"\n",
|
|
"$ A' = I+dtA|_{x=\\bar{x},u=\\bar{u}} $\n",
|
|
"\n",
|
|
"$ B' = dtB|_{x=\\bar{x},u=\\bar{u}} $\n",
|
|
"\n",
|
|
"$ C' = dt(f(\\bar{x},\\bar{u}) - A|_{x=\\bar{x},u=\\bar{u}}\\bar{x} - B|_{x=\\bar{x},u=\\bar{u}}\\bar{u}) $"
|
|
]
|
|
},
|
|
{
|
|
"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": 18,
|
|
"metadata": {},
|
|
"outputs": [],
|
|
"source": [
|
|
"# Control problem statement.\n",
|
|
"\n",
|
|
"N = 3 # number of state variables\n",
|
|
"M = 2 # number of control variables\n",
|
|
"T = 20 # Prediction Horizon\n",
|
|
"dt = 0.25 # discretization step"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": 19,
|
|
"metadata": {},
|
|
"outputs": [],
|
|
"source": [
|
|
"def get_linear_model(x_bar, u_bar):\n",
|
|
" \"\"\" \"\"\"\n",
|
|
"\n",
|
|
" x = x_bar[0]\n",
|
|
" y = x_bar[1]\n",
|
|
" theta = x_bar[2]\n",
|
|
"\n",
|
|
" v = u_bar[0]\n",
|
|
" w = u_bar[1]\n",
|
|
"\n",
|
|
" A = np.zeros((N, N))\n",
|
|
" A[0, 2] = -v * np.sin(theta)\n",
|
|
" A[1, 2] = v * np.cos(theta)\n",
|
|
" A_lin = np.eye(N) + dt * A\n",
|
|
"\n",
|
|
" B = np.zeros((N, M))\n",
|
|
" B[0, 0] = np.cos(theta)\n",
|
|
" B[1, 0] = np.sin(theta)\n",
|
|
" B[2, 1] = 1\n",
|
|
" B_lin = dt * B\n",
|
|
"\n",
|
|
" f_xu = np.array([v * np.cos(theta), v * np.sin(theta), w]).reshape(N, 1)\n",
|
|
" C_lin = dt * (\n",
|
|
" f_xu - np.dot(A, x_bar.reshape(N, 1)) - np.dot(B, u_bar.reshape(M, 1))\n",
|
|
" )\n",
|
|
"\n",
|
|
" return A_lin, B_lin, C_lin"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "markdown",
|
|
"metadata": {},
|
|
"source": [
|
|
"Motion Prediction: using scipy intergration"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": 20,
|
|
"metadata": {},
|
|
"outputs": [],
|
|
"source": [
|
|
"# Define process model\n",
|
|
"# This uses the continuous model\n",
|
|
"def kinematics_model(x, t, u):\n",
|
|
" \"\"\" \"\"\"\n",
|
|
"\n",
|
|
" dxdt = u[0] * np.cos(x[2])\n",
|
|
" dydt = u[0] * np.sin(x[2])\n",
|
|
" dthetadt = u[1]\n",
|
|
"\n",
|
|
" dqdt = [dxdt, dydt, dthetadt]\n",
|
|
"\n",
|
|
" return dqdt\n",
|
|
"\n",
|
|
"\n",
|
|
"def predict(x0, u):\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, x0, tspan, 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": 21,
|
|
"metadata": {},
|
|
"outputs": [
|
|
{
|
|
"name": "stdout",
|
|
"output_type": "stream",
|
|
"text": [
|
|
"CPU times: user 8.17 ms, sys: 10 µs, total: 8.18 ms\n",
|
|
"Wall time: 7.26 ms\n"
|
|
]
|
|
}
|
|
],
|
|
"source": [
|
|
"%%time\n",
|
|
"\n",
|
|
"u_bar = np.zeros((M, T))\n",
|
|
"u_bar[0, :] = 1 # m/s\n",
|
|
"u_bar[1, :] = np.radians(-10) # rad/s\n",
|
|
"\n",
|
|
"x0 = np.zeros(N)\n",
|
|
"x0[0] = 0\n",
|
|
"x0[1] = 1\n",
|
|
"x0[2] = np.radians(0)\n",
|
|
"\n",
|
|
"x_bar = predict(x0, u_bar)"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "markdown",
|
|
"metadata": {},
|
|
"source": [
|
|
"Check the model prediction"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": 22,
|
|
"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": 23,
|
|
"metadata": {},
|
|
"outputs": [
|
|
{
|
|
"name": "stdout",
|
|
"output_type": "stream",
|
|
"text": [
|
|
"CPU times: user 1.72 ms, sys: 0 ns, total: 1.72 ms\n",
|
|
"Wall time: 1.2 ms\n"
|
|
]
|
|
}
|
|
],
|
|
"source": [
|
|
"%%time\n",
|
|
"\n",
|
|
"u_bar = np.zeros((M, T))\n",
|
|
"u_bar[0, :] = 1 # m/s\n",
|
|
"u_bar[1, :] = np.radians(-10) # rad/s\n",
|
|
"\n",
|
|
"x0 = np.zeros(N)\n",
|
|
"x0[0] = 0\n",
|
|
"x0[1] = 1\n",
|
|
"x0[2] = np.radians(0)\n",
|
|
"\n",
|
|
"x_bar = np.zeros((N, T + 1))\n",
|
|
"x_bar[:, 0] = x0\n",
|
|
"\n",
|
|
"for t in range(1, T + 1):\n",
|
|
" xt = x_bar[:, t - 1].reshape(N, 1)\n",
|
|
" ut = u_bar[:, t - 1].reshape(M, 1)\n",
|
|
"\n",
|
|
" A, B, C = get_linear_model(xt, ut)\n",
|
|
"\n",
|
|
" xt_plus_one = np.dot(A, xt) + np.dot(B, ut) + C\n",
|
|
"\n",
|
|
" x_bar[:, t] = np.squeeze(xt_plus_one)"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": 24,
|
|
"metadata": {},
|
|
"outputs": [
|
|
{
|
|
"data": {
|
|
"image/png": "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\n",
|
|
"text/plain": [
|
|
"<Figure size 432x288 with 2 Axes>"
|
|
]
|
|
},
|
|
"metadata": {},
|
|
"output_type": "display_data"
|
|
}
|
|
],
|
|
"source": [
|
|
"# plot trajectory\n",
|
|
"plt.subplot(2, 2, 1)\n",
|
|
"plt.plot(x_bar[0, :], x_bar[1, :])\n",
|
|
"plt.plot(np.linspace(0, 10, T + 1), np.zeros(T + 1), \"b-\")\n",
|
|
"plt.axis(\"equal\")\n",
|
|
"plt.ylabel(\"y\")\n",
|
|
"plt.xlabel(\"x\")\n",
|
|
"\n",
|
|
"plt.subplot(2, 2, 2)\n",
|
|
"plt.plot(np.degrees(x_bar[2, :]))\n",
|
|
"plt.ylabel(\"theta(t)\")\n",
|
|
"# plt.xlabel('time')\n",
|
|
"\n",
|
|
"\n",
|
|
"plt.tight_layout()\n",
|
|
"plt.show()"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "markdown",
|
|
"metadata": {},
|
|
"source": [
|
|
"The results are the same as expected, so the linearized model is equivalent as expected."
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "markdown",
|
|
"metadata": {},
|
|
"source": [
|
|
"------------------\n",
|
|
"\n",
|
|
"the kinematics model predictits psi and cte for constant heading references. So, for non-constant paths appropriate functions have to be developed.\n",
|
|
"\n",
|
|
"-----------------"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "markdown",
|
|
"metadata": {},
|
|
"source": [
|
|
"## PRELIMINARIES"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": 25,
|
|
"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(\n",
|
|
" np.sqrt(\n",
|
|
" np.power(np.diff(start_xp[idx : idx + 2]), 2)\n",
|
|
" + np.power(np.diff(start_yp[idx : idx + 2]), 2)\n",
|
|
" )\n",
|
|
" )\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",
|
|
"\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 = [\n",
|
|
" path[0, nn_idx + 1] - path[0, nn_idx],\n",
|
|
" path[1, nn_idx + 1] - path[1, nn_idx],\n",
|
|
" ]\n",
|
|
" v /= np.linalg.norm(v)\n",
|
|
"\n",
|
|
" d = [path[0, nn_idx] - state[0], 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",
|
|
"\n",
|
|
"def road_curve(state, track):\n",
|
|
"\n",
|
|
" # given vehicle pos find lookahead waypoints\n",
|
|
" nn_idx = get_nn_idx(state, track) - 1\n",
|
|
" LOOKAHED = 6\n",
|
|
" lk_wp = track[:, nn_idx : nn_idx + LOOKAHED]\n",
|
|
"\n",
|
|
" # trasform lookahead waypoints to vehicle ref frame\n",
|
|
" dx = lk_wp[0, :] - state[0]\n",
|
|
" dy = lk_wp[1, :] - state[1]\n",
|
|
"\n",
|
|
" wp_vehicle_frame = np.vstack(\n",
|
|
" (\n",
|
|
" dx * np.cos(-state[2]) - dy * np.sin(-state[2]),\n",
|
|
" dy * np.cos(-state[2]) + dx * np.sin(-state[2]),\n",
|
|
" )\n",
|
|
" )\n",
|
|
"\n",
|
|
" # fit poly\n",
|
|
" return np.polyfit(\n",
|
|
" wp_vehicle_frame[0, :],\n",
|
|
" wp_vehicle_frame[1, :],\n",
|
|
" 3,\n",
|
|
" rcond=None,\n",
|
|
" full=False,\n",
|
|
" w=None,\n",
|
|
" cov=False,\n",
|
|
" )\n",
|
|
"\n",
|
|
"\n",
|
|
"def f(x, coeff):\n",
|
|
" return round(\n",
|
|
" coeff[0] * x**3 + coeff[1] * x**2 + coeff[2] * x**1 + coeff[3] * x**0, 6\n",
|
|
" )\n",
|
|
"\n",
|
|
"\n",
|
|
"# def f(x,coeff):\n",
|
|
"# return round(coeff[0]*x**5+coeff[1]*x**4+coeff[2]*x**3+coeff[3]*x**2+coeff[4]*x**1+coeff[5]*x**0,6)\n",
|
|
"\n",
|
|
"\n",
|
|
"def df(x, coeff):\n",
|
|
" return round(3 * coeff[0] * x**2 + 2 * coeff[1] * x**1 + coeff[2] * x**0, 6)\n",
|
|
"\n",
|
|
"\n",
|
|
"# def df(x,coeff):\n",
|
|
"# return round(5*coeff[0]*x**4 + 4*coeff[1]*x**3 +3*coeff[2]*x**2 + 2*coeff[3]*x**1 + coeff[4]*x**0,6)"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "markdown",
|
|
"metadata": {},
|
|
"source": [
|
|
"### MPC Problem formulation\n",
|
|
"\n",
|
|
"**Model Predictive Control** refers to the control approach of **numerically** solving a optimization problem at each time step. \n",
|
|
"\n",
|
|
"The controller generates a control signal over a fixed lenght T (Horizon) at each time step."
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "markdown",
|
|
"metadata": {},
|
|
"source": [
|
|
"![mpc](img/mpc_block_diagram.png)\n",
|
|
"\n",
|
|
"![mpc](img/mpc_t.png)"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "markdown",
|
|
"metadata": {},
|
|
"source": [
|
|
"#### Linear MPC Formulation\n",
|
|
"\n",
|
|
"Linear MPC makes use of the **LTI** (Linear time invariant) discrete state space model, wich represents a motion model used for Prediction.\n",
|
|
"\n",
|
|
"$x_{t+1} = Ax_t + Bu_t$\n",
|
|
"\n",
|
|
"The LTI formulation means that **future states** are linearly related to the current state and actuator signal. Hence, the MPC seeks to find a **control policy** U over a finite lenght horizon.\n",
|
|
"\n",
|
|
"$U={u_{t|t}, u_{t+1|t}, ...,u_{t+T|t}}$\n",
|
|
"\n",
|
|
"The objective function used minimize (drive the state to 0) is:\n",
|
|
"\n",
|
|
"$\n",
|
|
"\\begin{equation}\n",
|
|
"\\begin{aligned}\n",
|
|
"\\min_{} \\quad & \\sum^{t+T-1}_{j=t} x^T_{j|t}Qx_{j|t} + u^T_{j|t}Ru_{j|t}\\\\\n",
|
|
"\\textrm{s.t.} \\quad & x(0) = x0\\\\\n",
|
|
" & x_{j+1|t} = Ax_{j|t}+Bu_{j|t}) \\quad \\textrm{for} \\quad t<j<t+T-1 \\\\\n",
|
|
"\\end{aligned}\n",
|
|
"\\end{equation}\n",
|
|
"$\n",
|
|
"\n",
|
|
"Other linear constrains may be applied,for instance on the control variable:\n",
|
|
"\n",
|
|
"$ U_{MIN} < u_{j|t} < U_{MAX} \\quad \\textrm{for} \\quad t<j<t+T-1 $\n",
|
|
"\n",
|
|
"The objective fuction accounts for quadratic error on deviation from 0 of the state and the control inputs sequences. Q and R are the **weight matrices** and are used to tune the response.\n",
|
|
"\n",
|
|
"Because the goal is tracking a **reference signal** such as a trajectory, the objective function is rewritten as:\n",
|
|
"\n",
|
|
"$\n",
|
|
"\\begin{equation}\n",
|
|
"\\begin{aligned}\n",
|
|
"\\min_{} \\quad & \\sum^{t+T-1}_{j=t} \\delta x^T_{j|t}Q\\delta x_{j|t} + u^T_{j|t}Ru_{j|t}\n",
|
|
"\\end{aligned}\n",
|
|
"\\end{equation}\n",
|
|
"$\n",
|
|
"\n",
|
|
"where the error w.r.t desired state is accounted for:\n",
|
|
"\n",
|
|
"$ \\delta x = x_{j,t,ref} - x_{j,t} $"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "markdown",
|
|
"metadata": {},
|
|
"source": [
|
|
"# Problem Formulation: Study case\n",
|
|
"\n",
|
|
"In this case, the objective function to minimize is given the sum of the **cross-track error** plus **heading error**\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} + 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",
|
|
"where R,P,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": 26,
|
|
"metadata": {},
|
|
"outputs": [
|
|
{
|
|
"name": "stdout",
|
|
"output_type": "stream",
|
|
"text": [
|
|
"-----------------------------------------------------------------\n",
|
|
" OSQP v0.6.0 - Operator Splitting QP Solver\n",
|
|
" (c) Bartolomeo Stellato, Goran Banjac\n",
|
|
" University of Oxford - Stanford University 2019\n",
|
|
"-----------------------------------------------------------------\n",
|
|
"problem: variables n = 241, constraints m = 281\n",
|
|
" nnz(P) + nnz(A) = 753\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.00e+00 1.06e+02 1.00e-01 2.96e-04s\n",
|
|
" 125 1.8119e+03 6.13e-05 5.69e-04 4.76e+01 1.06e-03s\n",
|
|
"\n",
|
|
"status: solved\n",
|
|
"solution polish: unsuccessful\n",
|
|
"number of iterations: 125\n",
|
|
"optimal objective: 1811.9387\n",
|
|
"run time: 1.27e-03s\n",
|
|
"optimal rho estimate: 4.81e+01\n",
|
|
"\n",
|
|
"CPU times: user 237 ms, sys: 4 ms, total: 241 ms\n",
|
|
"Wall time: 236 ms\n"
|
|
]
|
|
}
|
|
],
|
|
"source": [
|
|
"%%time\n",
|
|
"\n",
|
|
"x = cp.Variable((N, T + 1))\n",
|
|
"u = cp.Variable((M, T))\n",
|
|
"\n",
|
|
"# CVXPY Linear MPC problem statement\n",
|
|
"cost = 0\n",
|
|
"constr = []\n",
|
|
"\n",
|
|
"for t in range(T):\n",
|
|
"\n",
|
|
" # Cost function\n",
|
|
" # cost += 10*cp.sum_squares( x[3, t]) # psi\n",
|
|
" # cost += 500*cp.sum_squares( x[4, t]) # cte\n",
|
|
"\n",
|
|
" cost += 10 * cp.sum_squares(x[2, t] - np.arctan(df(x_bar[0, t], K))) # psi\n",
|
|
" cost += 500 * cp.sum_squares(f(x_bar[0, t], K) - x[1, t]) # cte\n",
|
|
" # Actuation effort\n",
|
|
" cost += cp.quad_form(u[:, t], 1 * np.eye(M))\n",
|
|
"\n",
|
|
" # Actuation rate of change\n",
|
|
" if t < (T - 1):\n",
|
|
" cost += cp.quad_form(u[:, t + 1] - u[:, t], 100 * np.eye(M))\n",
|
|
"\n",
|
|
" # KINEMATICS constrains\n",
|
|
" A, B, C = get_linear_model(x_bar[:, t], u_bar[:, t])\n",
|
|
" constr += [x[:, t + 1] == A @ x[:, t] + B @ u[:, t] + C.flatten()]\n",
|
|
"\n",
|
|
"# sums problem objectives and concatenates constraints.\n",
|
|
"constr += [x[:, 0] == x_bar[:, 0]] # <--watch out the start condition\n",
|
|
"constr += [u[0, :] <= MAX_SPEED]\n",
|
|
"constr += [u[0, :] >= MIN_SPEED]\n",
|
|
"constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED]\n",
|
|
"\n",
|
|
"prob = cp.Problem(cp.Minimize(cost), constr)\n",
|
|
"solution = prob.solve(solver=cp.OSQP, verbose=True)"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": 27,
|
|
"metadata": {},
|
|
"outputs": [
|
|
{
|
|
"data": {
|
|
"image/png": "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\n",
|
|
"text/plain": [
|
|
"<Figure size 432x288 with 2 Axes>"
|
|
]
|
|
},
|
|
"metadata": {},
|
|
"output_type": "display_data"
|
|
}
|
|
],
|
|
"source": [
|
|
"x_mpc = np.array(x.value[0, :]).flatten()\n",
|
|
"y_mpc = np.array(x.value[1, :]).flatten()\n",
|
|
"theta_mpc = np.array(x.value[2, :]).flatten()\n",
|
|
"v_mpc = np.array(u.value[0, :]).flatten()\n",
|
|
"w_mpc = np.array(u.value[1, :]).flatten()\n",
|
|
"\n",
|
|
"# simulate robot state trajectory for optimized U\n",
|
|
"x_traj = predict(x0, np.vstack((v_mpc, w_mpc)))\n",
|
|
"\n",
|
|
"# plt.figure(figsize=(15,10))\n",
|
|
"# plot trajectory\n",
|
|
"plt.subplot(2, 2, 1)\n",
|
|
"plt.plot(track[0, :], track[1, :], \"b+\")\n",
|
|
"plt.plot(x_traj[0, :], x_traj[1, :])\n",
|
|
"plt.axis(\"equal\")\n",
|
|
"plt.ylabel(\"y\")\n",
|
|
"plt.xlabel(\"x\")\n",
|
|
"\n",
|
|
"# plot v(t)\n",
|
|
"plt.subplot(2, 2, 2)\n",
|
|
"plt.plot(v_mpc)\n",
|
|
"plt.ylabel(\"v(t)\")\n",
|
|
"# plt.xlabel('time')\n",
|
|
"\n",
|
|
"# plot w(t)\n",
|
|
"# plt.subplot(2, 2, 3)\n",
|
|
"# plt.plot(w_mpc)\n",
|
|
"# plt.ylabel('w(t)')\n",
|
|
"# plt.xlabel('time')\n",
|
|
"\n",
|
|
"# plt.subplot(2, 2, 3)\n",
|
|
"# plt.plot(psi_mpc)\n",
|
|
"# plt.ylabel('psi(t)')\n",
|
|
"\n",
|
|
"# plt.subplot(2, 2, 4)\n",
|
|
"# plt.plot(cte_mpc)\n",
|
|
"# plt.ylabel('cte(t)')\n",
|
|
"\n",
|
|
"plt.tight_layout()\n",
|
|
"plt.show()"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "markdown",
|
|
"metadata": {},
|
|
"source": [
|
|
"full track demo"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": 28,
|
|
"metadata": {},
|
|
"outputs": [
|
|
{
|
|
"name": "stderr",
|
|
"output_type": "stream",
|
|
"text": [
|
|
"<ipython-input-25-0756f6b412cb>:29: RuntimeWarning: invalid value encountered in true_divide\n",
|
|
" v /= np.linalg.norm(v)\n",
|
|
"<ipython-input-28-79710852001d>:33: RankWarning: Polyfit may be poorly conditioned\n",
|
|
" K=road_curve(x_sim[:,sim_time],track)\n",
|
|
"<ipython-input-28-79710852001d>:33: 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.1897s Max: 0.2940s Min: 0.1666s\n"
|
|
]
|
|
},
|
|
{
|
|
"name": "stderr",
|
|
"output_type": "stream",
|
|
"text": [
|
|
"<ipython-input-28-79710852001d>:33: RankWarning: Polyfit may be poorly conditioned\n",
|
|
" K=road_curve(x_sim[:,sim_time],track)\n"
|
|
]
|
|
}
|
|
],
|
|
"source": [
|
|
"track = compute_path_from_wp([0, 3, 4, 6, 10, 13], [0, 0, 2, 4, 3, 3], 0.25)\n",
|
|
"\n",
|
|
"# track = compute_path_from_wp([0,5,7.5,10,12,13,13,10],\n",
|
|
"# [0,0,2.5,2.5,0,0,5,10],0.5)\n",
|
|
"\n",
|
|
"sim_duration = 80 # time steps\n",
|
|
"opt_time = []\n",
|
|
"\n",
|
|
"x_sim = np.zeros((N, sim_duration))\n",
|
|
"u_sim = np.zeros((M, sim_duration - 1))\n",
|
|
"\n",
|
|
"MAX_SPEED = 1.25\n",
|
|
"MIN_SPEED = 0.75\n",
|
|
"MAX_STEER_SPEED = 1.57\n",
|
|
"\n",
|
|
"# Starting Condition\n",
|
|
"x0 = np.zeros(N)\n",
|
|
"x0[0] = 0\n",
|
|
"x0[1] = -0.25\n",
|
|
"x0[2] = np.radians(-0)\n",
|
|
"x_sim[:, 0] = x0\n",
|
|
"\n",
|
|
"# starting guess\n",
|
|
"u_bar = np.zeros((M, T))\n",
|
|
"u_bar[0, :] = 0.5 * (MAX_SPEED + MIN_SPEED)\n",
|
|
"u_bar[1, :] = 0.00\n",
|
|
"\n",
|
|
"for sim_time in range(sim_duration - 1):\n",
|
|
"\n",
|
|
" iter_start = time.time()\n",
|
|
"\n",
|
|
" K = road_curve(x_sim[:, sim_time], track)\n",
|
|
"\n",
|
|
" # dynamics starting state w.r.t vehicle frame\n",
|
|
" x_bar = np.zeros((N, T + 1))\n",
|
|
"\n",
|
|
" # prediction for linearization of costrains\n",
|
|
" for t in range(1, T + 1):\n",
|
|
" xt = x_bar[:, t - 1].reshape(N, 1)\n",
|
|
" ut = u_bar[:, t - 1].reshape(M, 1)\n",
|
|
" A, B, C = get_linear_model(xt, ut)\n",
|
|
" xt_plus_one = np.squeeze(np.dot(A, xt) + np.dot(B, ut) + C)\n",
|
|
" x_bar[:, t] = xt_plus_one\n",
|
|
"\n",
|
|
" # CVXPY Linear MPC problem statement\n",
|
|
" cost = 0\n",
|
|
" constr = []\n",
|
|
" x = cp.Variable((N, T + 1))\n",
|
|
" u = cp.Variable((M, T))\n",
|
|
"\n",
|
|
" # 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(\n",
|
|
" x[2, t] - np.arctan2(df(x_bar[0, t], K), x_bar[0, t])\n",
|
|
" ) # psi\n",
|
|
" cost += 20 * cp.sum_squares(f(x_bar[0, t], K) - x[1, t]) # cte\n",
|
|
"\n",
|
|
" # Actuation rate of change\n",
|
|
" if t < (T - 1):\n",
|
|
" cost += cp.quad_form(u[:, t + 1] - u[:, t], 100 * np.eye(M))\n",
|
|
"\n",
|
|
" # Actuation effort\n",
|
|
" cost += cp.quad_form(u[:, t], 1 * np.eye(M))\n",
|
|
"\n",
|
|
" # Kinrmatics Constrains (Linearized model)\n",
|
|
" A, B, C = get_linear_model(x_bar[:, t], u_bar[:, t])\n",
|
|
" constr += [x[:, t + 1] == A @ x[:, t] + B @ u[:, t] + C.flatten()]\n",
|
|
"\n",
|
|
" # sums problem objectives and concatenates constraints.\n",
|
|
" constr += [x[:, 0] == x_bar[:, 0]] # <--watch out the start condition\n",
|
|
" constr += [u[0, :] <= MAX_SPEED]\n",
|
|
" constr += [u[0, :] >= MIN_SPEED]\n",
|
|
" constr += [cp.abs(u[1, :]) <= MAX_STEER_SPEED]\n",
|
|
"\n",
|
|
" # Solve\n",
|
|
" prob = cp.Problem(cp.Minimize(cost), constr)\n",
|
|
" solution = prob.solve(solver=cp.OSQP, verbose=False)\n",
|
|
"\n",
|
|
" # retrieved optimized U and assign to u_bar to linearize in next step\n",
|
|
" u_bar = np.vstack(\n",
|
|
" (np.array(u.value[0, :]).flatten(), (np.array(u.value[1, :]).flatten()))\n",
|
|
" )\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(\n",
|
|
" kinematics_model, x_sim[:, sim_time], tspan, args=(u_bar[:, 0],)\n",
|
|
" )[1]\n",
|
|
"\n",
|
|
"print(\n",
|
|
" \"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(\n",
|
|
" np.mean(opt_time), np.max(opt_time), np.min(opt_time)\n",
|
|
" )\n",
|
|
")"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": 29,
|
|
"metadata": {},
|
|
"outputs": [
|
|
{
|
|
"data": {
|
|
"image/png": "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\n",
|
|
"text/plain": [
|
|
"<Figure size 1080x720 with 3 Axes>"
|
|
]
|
|
},
|
|
"metadata": {},
|
|
"output_type": "display_data"
|
|
}
|
|
],
|
|
"source": [
|
|
"# plot trajectory\n",
|
|
"grid = plt.GridSpec(2, 3)\n",
|
|
"\n",
|
|
"plt.figure(figsize=(15, 10))\n",
|
|
"\n",
|
|
"plt.subplot(grid[0:2, 0:2])\n",
|
|
"plt.plot(track[0, :], track[1, :], \"b+\")\n",
|
|
"plt.plot(x_sim[0, :], x_sim[1, :])\n",
|
|
"plt.axis(\"equal\")\n",
|
|
"plt.ylabel(\"y\")\n",
|
|
"plt.xlabel(\"x\")\n",
|
|
"\n",
|
|
"plt.subplot(grid[0, 2])\n",
|
|
"plt.plot(u_sim[0, :])\n",
|
|
"plt.ylabel(\"v(t) [m/s]\")\n",
|
|
"\n",
|
|
"plt.subplot(grid[1, 2])\n",
|
|
"plt.plot(np.degrees(u_sim[1, :]))\n",
|
|
"plt.ylabel(\"w(t) [deg/s]\")\n",
|
|
"\n",
|
|
"plt.tight_layout()\n",
|
|
"plt.show()"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "markdown",
|
|
"metadata": {},
|
|
"source": [
|
|
"## OBSTACLE AVOIDANCE\n",
|
|
"see dccp paper for reference"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": 51,
|
|
"metadata": {},
|
|
"outputs": [
|
|
{
|
|
"name": "stderr",
|
|
"output_type": "stream",
|
|
"text": [
|
|
"<ipython-input-25-0756f6b412cb>:29: RuntimeWarning: invalid value encountered in true_divide\n",
|
|
" v /= np.linalg.norm(v)\n",
|
|
"<ipython-input-51-a1c8be923656>:44: RankWarning: Polyfit may be poorly conditioned\n",
|
|
" K=road_curve(x_sim[:,sim_time],track)\n",
|
|
"<ipython-input-51-a1c8be923656>:44: RankWarning: Polyfit may be poorly conditioned\n",
|
|
" K=road_curve(x_sim[:,sim_time],track)\n",
|
|
"<ipython-input-51-a1c8be923656>:44: RankWarning: Polyfit may be poorly conditioned\n",
|
|
" K=road_curve(x_sim[:,sim_time],track)\n",
|
|
"<ipython-input-51-a1c8be923656>:44: RankWarning: Polyfit may be poorly conditioned\n",
|
|
" K=road_curve(x_sim[:,sim_time],track)\n",
|
|
"<ipython-input-51-a1c8be923656>:44: RankWarning: Polyfit may be poorly conditioned\n",
|
|
" K=road_curve(x_sim[:,sim_time],track)\n",
|
|
"<ipython-input-51-a1c8be923656>:44: RankWarning: Polyfit may be poorly conditioned\n",
|
|
" K=road_curve(x_sim[:,sim_time],track)\n",
|
|
"<ipython-input-51-a1c8be923656>:44: 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: 21.4061s Max: 49.1719s Min: 1.2366s\n"
|
|
]
|
|
}
|
|
],
|
|
"source": [
|
|
"import dccp\n",
|
|
"\n",
|
|
"track = compute_path_from_wp([0, 3, 4, 6, 10, 13], [0, 0, 2, 4, 3, 3], 0.25)\n",
|
|
"\n",
|
|
"obstacles = np.array([[4, 6], [2, 4]])\n",
|
|
"obstacle_radius = 0.5\n",
|
|
"\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 [\n",
|
|
" dx * np.cos(-theta) - dy * np.sin(-theta),\n",
|
|
" dy * np.cos(-theta) + dx * np.sin(-theta),\n",
|
|
" ]\n",
|
|
"\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(\n",
|
|
" to_vehic_frame(\n",
|
|
" obstacles[:, j],\n",
|
|
" x_sim[0, sim_time],\n",
|
|
" x_sim[1, sim_time],\n",
|
|
" x_sim[2, sim_time],\n",
|
|
" )\n",
|
|
" )\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(\n",
|
|
" x[2, t] - np.arctan2(df(x_bar[0, t], K), x_bar[0, t])\n",
|
|
" ) # 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(\n",
|
|
" (np.array(u.value[0, :]).flatten(), (np.array(u.value[1, :]).flatten()))\n",
|
|
" )\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(\n",
|
|
" kinematics_model, x_sim[:, sim_time], tspan, args=(u_bar[:, 0],)\n",
|
|
" )[1]\n",
|
|
"\n",
|
|
"print(\n",
|
|
" \"CVXPY Optimization Time: Avrg: {:.4f}s Max: {:.4f}s Min: {:.4f}s\".format(\n",
|
|
" np.mean(opt_time), np.max(opt_time), np.min(opt_time)\n",
|
|
" )\n",
|
|
")"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": 52,
|
|
"metadata": {},
|
|
"outputs": [
|
|
{
|
|
"data": {
|
|
"image/png": "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\n",
|
|
"text/plain": [
|
|
"<Figure size 1080x720 with 3 Axes>"
|
|
]
|
|
},
|
|
"metadata": {},
|
|
"output_type": "display_data"
|
|
}
|
|
],
|
|
"source": [
|
|
"# plot trajectory\n",
|
|
"grid = plt.GridSpec(2, 3)\n",
|
|
"\n",
|
|
"plt.figure(figsize=(15, 10))\n",
|
|
"\n",
|
|
"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:jupyter] *",
|
|
"language": "python",
|
|
"name": "conda-env-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.3"
|
|
}
|
|
},
|
|
"nbformat": 4,
|
|
"nbformat_minor": 4
|
|
}
|