1240 lines
612 KiB
Plaintext
1240 lines
612 KiB
Plaintext
{
|
|
"cells": [
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": 1,
|
|
"metadata": {
|
|
"ExecuteTime": {
|
|
"end_time": "2024-10-23T09:24:14.711190Z",
|
|
"start_time": "2024-10-23T09:24:13.777868Z"
|
|
}
|
|
},
|
|
"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": "code",
|
|
"execution_count": 2,
|
|
"metadata": {
|
|
"ExecuteTime": {
|
|
"end_time": "2024-10-23T09:24:14.748515Z",
|
|
"start_time": "2024-10-23T09:24:14.746753Z"
|
|
}
|
|
},
|
|
"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.2 # discretization step\n",
|
|
"\n",
|
|
"\n",
|
|
"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(\n",
|
|
" [v * np.cos(theta), v * np.sin(theta), a, v * np.tan(delta) / L]\n",
|
|
" ).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 np.round(A_lin, 4), np.round(B_lin, 4), np.round(C_lin, 4)\n",
|
|
"\n",
|
|
"\n",
|
|
"\"\"\"\n",
|
|
"the ODE is used to update the simulation given the mpc results\n",
|
|
"I use this insted of using the LTI twice\n",
|
|
"\"\"\"\n",
|
|
"\n",
|
|
"\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, dydt, dvdt, dthetadt]\n",
|
|
"\n",
|
|
" return dqdt\n",
|
|
"\n",
|
|
"\n",
|
|
"def predict(x0, u):\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, x0, tspan, args=(u[:, t - 1],))\n",
|
|
"\n",
|
|
" x0 = x_next[1]\n",
|
|
" x_[:, t] = x_next[1]\n",
|
|
"\n",
|
|
" return x_\n",
|
|
"\n",
|
|
"\n",
|
|
"\"\"\"\n",
|
|
"MODIFIED TO INCLUDE FRAME TRANSFORMATION\n",
|
|
"\"\"\"\n",
|
|
"\n",
|
|
"\n",
|
|
"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(\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",
|
|
" # watch out to duplicate points!\n",
|
|
" final_xp = np.append(final_xp, fx(interp_range)[1:])\n",
|
|
" final_yp = np.append(final_yp, fy(interp_range)[1:])\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 = [\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 normalize_angle(angle):\n",
|
|
" \"\"\"\n",
|
|
" Normalize an angle to [-pi, pi]\n",
|
|
" \"\"\"\n",
|
|
" while angle > np.pi:\n",
|
|
" angle -= 2.0 * np.pi\n",
|
|
"\n",
|
|
" while angle < -np.pi:\n",
|
|
" angle += 2.0 * np.pi\n",
|
|
"\n",
|
|
" return angle\n",
|
|
"\n",
|
|
"\n",
|
|
"def get_ref_trajectory(state, path, target_v):\n",
|
|
" \"\"\"\n",
|
|
" modified reference in robot frame\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",
|
|
" dx = path[0, ind] - state[0]\n",
|
|
" dy = path[1, ind] - state[1]\n",
|
|
"\n",
|
|
" xref[0, 0] = dx * np.cos(-state[3]) - dy * np.sin(-state[3]) # X\n",
|
|
" xref[1, 0] = dy * np.cos(-state[3]) + dx * np.sin(-state[3]) # Y\n",
|
|
" xref[2, 0] = target_v # V\n",
|
|
" xref[3, 0] = normalize_angle(path[2, ind] - state[3]) # 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",
|
|
" dx = path[0, ind + dind] - state[0]\n",
|
|
" dy = path[1, ind + dind] - state[1]\n",
|
|
"\n",
|
|
" xref[0, i] = dx * np.cos(-state[3]) - dy * np.sin(-state[3])\n",
|
|
" xref[1, i] = dy * np.cos(-state[3]) + dx * np.sin(-state[3])\n",
|
|
" xref[2, i] = target_v # sp[ind + dind]\n",
|
|
" xref[3, i] = normalize_angle(path[2, ind + dind] - state[3])\n",
|
|
" dref[0, i] = 0.0\n",
|
|
" else:\n",
|
|
" dx = path[0, ncourse - 1] - state[0]\n",
|
|
" dy = path[1, ncourse - 1] - state[1]\n",
|
|
"\n",
|
|
" xref[0, i] = dx * np.cos(-state[3]) - dy * np.sin(-state[3])\n",
|
|
" xref[1, i] = dy * np.cos(-state[3]) + dx * np.sin(-state[3])\n",
|
|
" xref[2, i] = 0.0 # stop? #sp[ncourse - 1]\n",
|
|
" xref[3, i] = normalize_angle(path[2, ncourse - 1] - state[3])\n",
|
|
" dref[0, i] = 0.0\n",
|
|
"\n",
|
|
" return xref, dref"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "markdown",
|
|
"metadata": {},
|
|
"source": [
|
|
"## SMOOTHEN PATH 平滑曲线\n",
|
|
"\n",
|
|
"I use a corner smoothing tecnique to help the line-finding proplem -> this way the line does not change from 0 to pi/2 instantly\n",
|
|
"我使用了一种转角平滑技术来帮助解决找线问题 -> 通过这种方式,线不会从 0 瞬间变为 𝜋/2"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": 3,
|
|
"metadata": {
|
|
"ExecuteTime": {
|
|
"end_time": "2024-10-23T09:25:04.148826Z",
|
|
"start_time": "2024-10-23T09:25:04.116482Z"
|
|
}
|
|
},
|
|
"outputs": [],
|
|
"source": [
|
|
"from scipy.signal import savgol_filter\n",
|
|
"\n",
|
|
"\n",
|
|
"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(\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",
|
|
" # watch out to duplicate points!\n",
|
|
" final_xp = np.append(final_xp, fx(interp_range)[1:])\n",
|
|
" final_yp = np.append(final_yp, fy(interp_range)[1:])\n",
|
|
"\n",
|
|
" \"\"\"this smoothens up corners\"\"\"\n",
|
|
" window_size = 7 # Smoothening filter window\n",
|
|
" final_xp = savgol_filter(final_xp, window_size, 1)\n",
|
|
" final_yp = savgol_filter(final_yp, window_size, 1)\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))"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "markdown",
|
|
"metadata": {},
|
|
"source": [
|
|
"## V3 Add track constraints 添加轨迹约束\n",
|
|
"inspried from -> https://arxiv.org/pdf/1711.07300.pdf\n",
|
|
"\n",
|
|
"explanation here...\n",
|
|
"\n",
|
|
"benefits:\n",
|
|
"* add a soft form of obstacle aoidance 添加了一种软障碍物避免形式"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": 4,
|
|
"metadata": {
|
|
"ExecuteTime": {
|
|
"end_time": "2024-10-23T09:25:27.470304Z",
|
|
"start_time": "2024-10-23T09:25:27.366214Z"
|
|
}
|
|
},
|
|
"outputs": [
|
|
{
|
|
"data": {
|
|
"text/plain": "[<matplotlib.lines.Line2D at 0x11d851f40>]"
|
|
},
|
|
"execution_count": 4,
|
|
"metadata": {},
|
|
"output_type": "execute_result"
|
|
},
|
|
{
|
|
"data": {
|
|
"text/plain": "<Figure size 1500x1000 with 1 Axes>",
|
|
"image/png": "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"
|
|
},
|
|
"metadata": {},
|
|
"output_type": "display_data"
|
|
}
|
|
],
|
|
"source": [
|
|
"def generate_track_bounds(track, width=0.5):\n",
|
|
" \"\"\"\n",
|
|
" in world frame\n",
|
|
" \"\"\"\n",
|
|
" bounds_low = np.zeros((2, track.shape[1]))\n",
|
|
" bounds_upp = np.zeros((2, track.shape[1]))\n",
|
|
"\n",
|
|
" for idx in range(track.shape[1]):\n",
|
|
" x = track[0, idx]\n",
|
|
" y = track[1, idx]\n",
|
|
" th = track[2, idx]\n",
|
|
"\n",
|
|
" \"\"\"\n",
|
|
" trasform the points\n",
|
|
" \"\"\"\n",
|
|
" bounds_upp[0, idx] = 0 * np.cos(th) - width * np.sin(th) + x # X\n",
|
|
" bounds_upp[1, idx] = 0 * np.sin(th) + width * np.cos(th) + y # Y\n",
|
|
"\n",
|
|
" bounds_low[0, idx] = 0 * np.cos(th) - (-width) * np.sin(th) + x # X\n",
|
|
" bounds_low[1, idx] = 0 * np.sin(th) + (-width) * np.cos(th) + y # Y\n",
|
|
"\n",
|
|
" return bounds_low, bounds_upp\n",
|
|
"\n",
|
|
"\n",
|
|
"track = compute_path_from_wp(\n",
|
|
" [0, 3, 4, 6, 10, 12, 14, 6, 1, 0], [0, 0, 2, 4, 3, 3, -2, -6, -2, -2], 0.05\n",
|
|
")\n",
|
|
"\n",
|
|
"lower, upper = generate_track_bounds(track)\n",
|
|
"\n",
|
|
"plt.figure(figsize=(15, 10))\n",
|
|
"\n",
|
|
"plt.plot(track[0, :], track[1, :], \"b-\")\n",
|
|
"plt.plot(lower[0, :], lower[1, :], \"g-\")\n",
|
|
"plt.plot(upper[0, :], upper[1, :], \"r-\")"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "markdown",
|
|
"metadata": {},
|
|
"source": [
|
|
"the points can be used to generate the **halfplane constrains** for each reference point.\n",
|
|
"the issues (outliers points) should be gone after we are in vehicle frame...\n",
|
|
"\n",
|
|
"the halfplane constrains are defined given the line equation:\n",
|
|
"\n",
|
|
"**lower halfplane**\n",
|
|
"$$ a1x_1 + b1x_2 = c1 \\rightarrow a1x_1 + b1x_2 \\leq c1$$\n",
|
|
"\n",
|
|
"**upper halfplane**\n",
|
|
"$$ a2x_1 - b2x_2 = c2 \\rightarrow a2x_1 + b2x_2 \\leq c2$$\n",
|
|
"\n",
|
|
"we want to combine this in matrix form:\n",
|
|
"\n",
|
|
"$$\n",
|
|
"\\begin{bmatrix}\n",
|
|
"x_1 \\\\\n",
|
|
"x_2 \n",
|
|
"\\end{bmatrix}\n",
|
|
"\\begin{bmatrix}\n",
|
|
"a_1 & a_2\\\\\n",
|
|
"b_1 & b_2\n",
|
|
"\\end{bmatrix}\n",
|
|
"\\leq\n",
|
|
"\\begin{bmatrix}\n",
|
|
"c_1 \\\\\n",
|
|
"c_2 \n",
|
|
"\\end{bmatrix}\n",
|
|
"$$\n",
|
|
"\n",
|
|
"becouse our track points have known heading the coefficients can be computed from:\n",
|
|
"\n",
|
|
"$$ y - y' = \\frac{sin(\\theta)}{cos(\\theta)}(x - x') $$\n",
|
|
"\n",
|
|
"we have:\n",
|
|
"\n",
|
|
"$$\n",
|
|
"-tan(\\theta)x + y = - tan(\\theta)x' + y'\n",
|
|
"$$\n",
|
|
"where:\n",
|
|
"* $ a = -tan(\\theta) $\n",
|
|
"* $ b = 1 $\n",
|
|
"* $ c = - tan(\\theta)x' + y' $"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": 5,
|
|
"metadata": {
|
|
"ExecuteTime": {
|
|
"end_time": "2024-10-23T09:25:41.213106Z",
|
|
"start_time": "2024-10-23T09:25:41.152165Z"
|
|
}
|
|
},
|
|
"outputs": [
|
|
{
|
|
"data": {
|
|
"text/plain": "(-2.0, 2.0)"
|
|
},
|
|
"execution_count": 5,
|
|
"metadata": {},
|
|
"output_type": "execute_result"
|
|
},
|
|
{
|
|
"data": {
|
|
"text/plain": "<Figure size 500x500 with 1 Axes>",
|
|
"image/png": "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"
|
|
},
|
|
"metadata": {},
|
|
"output_type": "display_data"
|
|
}
|
|
],
|
|
"source": [
|
|
"import numpy as np\n",
|
|
"import matplotlib.pyplot as plt\n",
|
|
"\n",
|
|
"plt.style.use(\"ggplot\")\n",
|
|
"\n",
|
|
"\n",
|
|
"def get_coeff(x, y, theta):\n",
|
|
" m = np.sin(theta) / np.cos(theta)\n",
|
|
" return (-m, 1, y - m * x)\n",
|
|
"\n",
|
|
"\n",
|
|
"# test -> assume point 10,1,pi/6\n",
|
|
"# coeff = get_coeff(1,-1, np.pi/2)\n",
|
|
"coeff = get_coeff(1, -1, np.pi / 4)\n",
|
|
"y = []\n",
|
|
"pts = np.linspace(0, 20, 100)\n",
|
|
"\n",
|
|
"for x in pts:\n",
|
|
" y.append((-coeff[0] * x + coeff[2]) / coeff[1])\n",
|
|
"\n",
|
|
"plt.figure(figsize=(5, 5))\n",
|
|
"plt.plot(pts, y, \"b-\")\n",
|
|
"\n",
|
|
"plt.xlim((-2, 2))\n",
|
|
"plt.ylim((-2, 2))"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "markdown",
|
|
"metadata": {},
|
|
"source": [
|
|
"## WARN TANGENT BREAKS AROUND PI/2?\n",
|
|
"force the equation to x = val"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": 6,
|
|
"metadata": {
|
|
"ExecuteTime": {
|
|
"end_time": "2024-10-23T09:25:48.168113Z",
|
|
"start_time": "2024-10-23T09:25:48.117783Z"
|
|
}
|
|
},
|
|
"outputs": [
|
|
{
|
|
"data": {
|
|
"text/plain": "(-2.0, 2.0)"
|
|
},
|
|
"execution_count": 6,
|
|
"metadata": {},
|
|
"output_type": "execute_result"
|
|
},
|
|
{
|
|
"data": {
|
|
"text/plain": "<Figure size 500x500 with 1 Axes>",
|
|
"image/png": "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"
|
|
},
|
|
"metadata": {},
|
|
"output_type": "display_data"
|
|
}
|
|
],
|
|
"source": [
|
|
"# def get_coeff(x,y,theta):\n",
|
|
"\n",
|
|
"# if (theta - np.pi/2) < 0.01:\n",
|
|
"# #print (\"WARN -> theta is 90, tan is: \" + str(theta))\n",
|
|
"# # eq is x = val\n",
|
|
"# m = 0\n",
|
|
"# return (1,1e-6,x)\n",
|
|
"# else:\n",
|
|
"# m = np.sin(theta)/np.cos(theta)\n",
|
|
"# return(-m,1,y-m*x)\n",
|
|
"\n",
|
|
"# test -> assume point 10,1,pi/6\n",
|
|
"coeff = get_coeff(1, -1, np.pi / 2)\n",
|
|
"y = []\n",
|
|
"pts = np.linspace(0, 20, 100)\n",
|
|
"\n",
|
|
"for x in pts:\n",
|
|
" y.append((-coeff[0] * x + coeff[2]) / coeff[1])\n",
|
|
"\n",
|
|
"plt.figure(figsize=(5, 5))\n",
|
|
"\n",
|
|
"plt.plot(pts, y, \"b-\")\n",
|
|
"plt.axis(\"equal\")\n",
|
|
"plt.xlim((-2, 2))\n",
|
|
"plt.ylim((-2, 2))"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "markdown",
|
|
"metadata": {},
|
|
"source": [
|
|
"becouse the controller uses vhicle reference frame this rquire adapting -> the semiplane constraints must be gathetered from **x_ref points**\n",
|
|
"\n",
|
|
"*low and up are w.r.t vehicle y axis*"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": 7,
|
|
"metadata": {
|
|
"ExecuteTime": {
|
|
"end_time": "2024-10-23T09:25:50.882261Z",
|
|
"start_time": "2024-10-23T09:25:50.874762Z"
|
|
}
|
|
},
|
|
"outputs": [],
|
|
"source": [
|
|
"def get_track_constrains(x_ref, width=0.5):\n",
|
|
" \"\"\"\n",
|
|
" x_ref has hape (4,T) -> [x,y,v,theta]_ref\n",
|
|
" \"\"\"\n",
|
|
"\n",
|
|
" # 1-> get the upper and lower points\n",
|
|
" pts_low = np.zeros((3, x_ref.shape[1]))\n",
|
|
" pts_upp = np.zeros((3, x_ref.shape[1]))\n",
|
|
"\n",
|
|
" for idx in range(x_ref.shape[1]):\n",
|
|
" x = x_ref[0, idx]\n",
|
|
" y = x_ref[1, idx]\n",
|
|
" th = x_ref[3, idx]\n",
|
|
"\n",
|
|
" \"\"\"\n",
|
|
" trasform the points\n",
|
|
" \"\"\"\n",
|
|
" pts_upp[0, idx] = 0 * np.cos(th) - width * np.sin(th) + x # X\n",
|
|
" pts_upp[1, idx] = 0 * np.sin(th) + width * np.cos(th) + y # Y\n",
|
|
" pts_upp[2, idx] = th # heading\n",
|
|
"\n",
|
|
" pts_low[0, idx] = 0 * np.cos(th) - (-width) * np.sin(th) + x # X\n",
|
|
" pts_low[1, idx] = 0 * np.sin(th) + (-width) * np.cos(th) + y # Y\n",
|
|
" pts_low[2, idx] = th # heading\n",
|
|
"\n",
|
|
" # get coefficients ->(a,b,c)\n",
|
|
" coeff_low = np.zeros((3, x_ref.shape[1]))\n",
|
|
" coeff_upp = np.zeros((3, x_ref.shape[1]))\n",
|
|
"\n",
|
|
" for idx in range(pts_upp.shape[1]):\n",
|
|
" f = get_coeff(pts_low[0, idx], pts_low[1, idx], pts_low[2, idx])\n",
|
|
" coeff_low[0, idx] = f[0]\n",
|
|
" coeff_low[1, idx] = f[1]\n",
|
|
" coeff_low[2, idx] = f[2]\n",
|
|
"\n",
|
|
" f = get_coeff(pts_upp[0, idx], pts_upp[1, idx], pts_upp[2, idx])\n",
|
|
" coeff_upp[0, idx] = f[0]\n",
|
|
" coeff_upp[1, idx] = f[1]\n",
|
|
" coeff_upp[2, idx] = f[2]\n",
|
|
"\n",
|
|
" return coeff_low, coeff_upp"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "markdown",
|
|
"metadata": {},
|
|
"source": [
|
|
"## MPC INTEGRATION\n",
|
|
"\n",
|
|
"compare the results with and without"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "markdown",
|
|
"metadata": {},
|
|
"source": [
|
|
"simpe u-turn test\n",
|
|
"\n",
|
|
"## 1-> NO BOUNDS"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": 8,
|
|
"metadata": {
|
|
"ExecuteTime": {
|
|
"end_time": "2024-10-23T09:25:57.020073Z",
|
|
"start_time": "2024-10-23T09:25:53.799988Z"
|
|
}
|
|
},
|
|
"outputs": [
|
|
{
|
|
"name": "stderr",
|
|
"output_type": "stream",
|
|
"text": [
|
|
"/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_24294/4187762036.py:27: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n",
|
|
" A[0, 2] = np.cos(theta)\n",
|
|
"/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_24294/4187762036.py:28: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n",
|
|
" A[0, 3] = -v * np.sin(theta)\n",
|
|
"/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_24294/4187762036.py:29: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n",
|
|
" A[1, 2] = np.sin(theta)\n",
|
|
"/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_24294/4187762036.py:30: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n",
|
|
" A[1, 3] = v * np.cos(theta)\n",
|
|
"/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_24294/4187762036.py:31: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n",
|
|
" A[3, 2] = v * np.tan(delta) / L\n",
|
|
"/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_24294/4187762036.py:36: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n",
|
|
" B[3, 1] = v / (L * np.cos(delta) ** 2)\n"
|
|
]
|
|
},
|
|
{
|
|
"name": "stdout",
|
|
"output_type": "stream",
|
|
"text": [
|
|
"CVXPY Optimization Time: Avrg: 0.0656s Max: 0.0909s Min: 0.0533s\n"
|
|
]
|
|
}
|
|
],
|
|
"source": [
|
|
"track = compute_path_from_wp([0, 3, 3, 0], [0, 0, 1, 1], 0.05)\n",
|
|
"\n",
|
|
"track_lower, track_upper = generate_track_bounds(track, 0.12)\n",
|
|
"\n",
|
|
"sim_duration = 50 # 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_ACC = 1.0 # m/ss\n",
|
|
"MAX_D_ACC = 1.0 # m/sss\n",
|
|
"MAX_STEER = np.radians(30) # rad\n",
|
|
"MAX_D_STEER = np.radians(30) # rad/s\n",
|
|
"\n",
|
|
"REF_VEL = 0.5 # m/s\n",
|
|
"\n",
|
|
"# Starting Condition\n",
|
|
"x0 = np.zeros(N)\n",
|
|
"x0[0] = 0 # x\n",
|
|
"x0[1] = -0.05 # y\n",
|
|
"x0[2] = 0.0 # v\n",
|
|
"x0[3] = np.radians(-0) # yaw\n",
|
|
"x_sim[:, 0] = x0 # simulation_starting conditions\n",
|
|
"\n",
|
|
"# starting guess\n",
|
|
"u_bar = np.zeros((M, T))\n",
|
|
"u_bar[0, :] = MAX_ACC / 2 # a\n",
|
|
"u_bar[1, :] = 0.0 # delta\n",
|
|
"\n",
|
|
"for sim_time in range(sim_duration - 1):\n",
|
|
"\n",
|
|
" iter_start = time.time()\n",
|
|
"\n",
|
|
" # dynamics starting state w.r.t. robot are always null except vel\n",
|
|
" x_bar = np.zeros((N, T + 1))\n",
|
|
" x_bar[2, 0] = x_sim[2, sim_time]\n",
|
|
"\n",
|
|
" # prediction for linearization of costrains\n",
|
|
" for t in range(1, T + 1):\n",
|
|
" xt = x_bar[:, t - 1].reshape(N, 1)\n",
|
|
" ut = u_bar[:, t - 1].reshape(M, 1)\n",
|
|
" A, B, C = get_linear_model(xt, ut)\n",
|
|
" xt_plus_one = np.squeeze(np.dot(A, xt) + np.dot(B, ut) + C)\n",
|
|
" x_bar[:, t] = xt_plus_one\n",
|
|
"\n",
|
|
" # CVXPY Linear MPC problem statement\n",
|
|
" 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, 20]) # state error cost\n",
|
|
" Qf = np.diag([30, 30, 30, 30]) # 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",
|
|
" # dont use x0 in this case\n",
|
|
" x_ref, d_ref = get_ref_trajectory(x_sim[:, sim_time], 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",
|
|
" constr += [\n",
|
|
" cp.abs(u[0, t + 1] - u[0, t]) / DT <= MAX_D_ACC\n",
|
|
" ] # max acc rate of change\n",
|
|
" constr += [\n",
|
|
" cp.abs(u[1, t + 1] - u[1, t]) / DT <= MAX_D_STEER\n",
|
|
" ] # max steer rate of change\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",
|
|
" # Final Point tracking\n",
|
|
" cost += cp.quad_form(x[:, T] - x_ref[:, T], Qf)\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(\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": 9,
|
|
"metadata": {
|
|
"ExecuteTime": {
|
|
"end_time": "2024-10-23T09:25:59.769712Z",
|
|
"start_time": "2024-10-23T09:25:59.600540Z"
|
|
}
|
|
},
|
|
"outputs": [
|
|
{
|
|
"data": {
|
|
"text/plain": "<Figure size 1500x1000 with 5 Axes>",
|
|
"image/png": "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"
|
|
},
|
|
"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(track_lower[0, :], track_lower[1, :], \"g-\")\n",
|
|
"plt.plot(track_upper[0, :], track_upper[1, :], \"r-\")\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": [
|
|
"## 2-> WITH BOUNDS\n",
|
|
"if there is 90 deg turn the optimization fails!\n",
|
|
"if speed is too high it also fails ..."
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": 10,
|
|
"metadata": {
|
|
"ExecuteTime": {
|
|
"end_time": "2024-10-23T09:26:36.831723Z",
|
|
"start_time": "2024-10-23T09:26:14.421549Z"
|
|
}
|
|
},
|
|
"outputs": [
|
|
{
|
|
"name": "stderr",
|
|
"output_type": "stream",
|
|
"text": [
|
|
"/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_24294/4187762036.py:27: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n",
|
|
" A[0, 2] = np.cos(theta)\n",
|
|
"/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_24294/4187762036.py:28: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n",
|
|
" A[0, 3] = -v * np.sin(theta)\n",
|
|
"/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_24294/4187762036.py:29: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n",
|
|
" A[1, 2] = np.sin(theta)\n",
|
|
"/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_24294/4187762036.py:30: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n",
|
|
" A[1, 3] = v * np.cos(theta)\n",
|
|
"/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_24294/4187762036.py:31: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n",
|
|
" A[3, 2] = v * np.tan(delta) / L\n",
|
|
"/var/folders/hd/8kg_jtmd6svgg_sc384pbcdm0000gn/T/ipykernel_24294/4187762036.py:36: DeprecationWarning: Conversion of an array with ndim > 0 to a scalar is deprecated, and will error in future. Ensure you extract a single element from your array before performing this operation. (Deprecated NumPy 1.25.)\n",
|
|
" B[3, 1] = v / (L * np.cos(delta) ** 2)\n",
|
|
"/Users/qp/Applications/miniforge3/envs/mpc_python12/lib/python3.12/site-packages/cvxpy/reductions/solvers/solving_chain.py:356: FutureWarning: \n",
|
|
" You specified your problem should be solved by ECOS. Starting in\n",
|
|
" CXVPY 1.6.0, ECOS will no longer be installed by default with CVXPY.\n",
|
|
" Please either add ECOS as an explicit install dependency to your project\n",
|
|
" or switch to our new default solver, Clarabel, by either not specifying a\n",
|
|
" solver argument or specifying ``solver=cp.CLARABEL``. To suppress this\n",
|
|
" warning while continuing to use ECOS, you can filter this warning using\n",
|
|
" Python's ``warnings`` module until you are using 1.6.0.\n",
|
|
" \n",
|
|
" warnings.warn(ECOS_DEP_DEPRECATION_MSG, FutureWarning)\n"
|
|
]
|
|
},
|
|
{
|
|
"name": "stdout",
|
|
"output_type": "stream",
|
|
"text": [
|
|
"CVXPY Optimization Time: Avrg: 0.1127s Max: 0.1371s Min: 0.0927s\n"
|
|
]
|
|
}
|
|
],
|
|
"source": [
|
|
"WIDTH = 0.18\n",
|
|
"REF_VEL = 0.4 # m/s\n",
|
|
"\n",
|
|
"computed_coeff = []\n",
|
|
"\n",
|
|
"track = compute_path_from_wp([0, 3, 3, 0], [0, 0, -1, -1], 0.05)\n",
|
|
"\n",
|
|
"track_lower, track_upper = generate_track_bounds(track, WIDTH)\n",
|
|
"\n",
|
|
"sim_duration = 200 # 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_ACC = 1.0 # m/ss\n",
|
|
"MAX_D_ACC = 1.0 # m/sss\n",
|
|
"MAX_STEER = np.radians(30) # rad\n",
|
|
"MAX_D_STEER = np.radians(30) # rad/s\n",
|
|
"\n",
|
|
"\n",
|
|
"# Starting Condition\n",
|
|
"x0 = np.zeros(N)\n",
|
|
"x0[0] = 0 # x\n",
|
|
"x0[1] = WIDTH / 2 # y\n",
|
|
"x0[2] = 0.0 # v\n",
|
|
"x0[3] = np.radians(-0) # yaw\n",
|
|
"x_sim[:, 0] = x0 # simulation_starting conditions\n",
|
|
"\n",
|
|
"# starting guess\n",
|
|
"u_bar = np.zeros((M, T))\n",
|
|
"u_bar[0, :] = MAX_ACC / 2 # a\n",
|
|
"u_bar[1, :] = 0.0 # delta\n",
|
|
"\n",
|
|
"for sim_time in range(sim_duration - 1):\n",
|
|
"\n",
|
|
" iter_start = time.time()\n",
|
|
"\n",
|
|
" # dynamics starting state w.r.t. robot are always null except vel\n",
|
|
" x_bar = np.zeros((N, T + 1))\n",
|
|
" x_bar[2, 0] = x_sim[2, sim_time]\n",
|
|
"\n",
|
|
" # prediction for linearization of costrains\n",
|
|
" for t in range(1, T + 1):\n",
|
|
" xt = x_bar[:, t - 1].reshape(N, 1)\n",
|
|
" ut = u_bar[:, t - 1].reshape(M, 1)\n",
|
|
" A, B, C = get_linear_model(xt, ut)\n",
|
|
" xt_plus_one = np.squeeze(np.dot(A, xt) + np.dot(B, ut) + C)\n",
|
|
" x_bar[:, t] = xt_plus_one\n",
|
|
"\n",
|
|
" # CVXPY Linear MPC problem statement\n",
|
|
" 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, 20]) # state error cost\n",
|
|
" Qf = np.diag([30, 30, 30, 30]) # 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",
|
|
" # dont use x0 in this case\n",
|
|
" x_ref, d_ref = get_ref_trajectory(x_sim[:, sim_time], 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",
|
|
" constr += [\n",
|
|
" cp.abs(u[0, t + 1] - u[0, t]) / DT <= MAX_D_ACC\n",
|
|
" ] # max acc rate of change\n",
|
|
" constr += [\n",
|
|
" cp.abs(u[1, t + 1] - u[1, t]) / DT <= MAX_D_STEER\n",
|
|
" ] # max steer rate of change\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",
|
|
" # Final Point tracking\n",
|
|
" cost += cp.quad_form(x[:, T] - x_ref[:, T], Qf)\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",
|
|
" # Track constrains\n",
|
|
" low, upp = get_track_constrains(x_ref, WIDTH)\n",
|
|
" computed_coeff.append((low, upp))\n",
|
|
" for ii in range(low.shape[1]):\n",
|
|
" # constr += [low[0,ii]*x[0,ii] + x[1,ii] >= low[2,ii]]\n",
|
|
" constr += [\n",
|
|
" upp[0, ii] * x[0, ii] + x[1, ii] <= upp[2, ii]\n",
|
|
" ] # <-- CAUSES ISSUES Y?\n",
|
|
"\n",
|
|
" # Solve\n",
|
|
" prob = cp.Problem(cp.Minimize(cost), constr)\n",
|
|
" solution = prob.solve(solver=cp.ECOS, 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": 11,
|
|
"metadata": {
|
|
"ExecuteTime": {
|
|
"end_time": "2024-10-23T09:26:42.544764Z",
|
|
"start_time": "2024-10-23T09:26:42.368460Z"
|
|
}
|
|
},
|
|
"outputs": [
|
|
{
|
|
"data": {
|
|
"text/plain": "<Figure size 1500x1000 with 5 Axes>",
|
|
"image/png": "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"
|
|
},
|
|
"metadata": {},
|
|
"output_type": "display_data"
|
|
}
|
|
],
|
|
"source": [
|
|
"%matplotlib inline\n",
|
|
"# 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(track_lower[0, :], track_lower[1, :], \"g.\")\n",
|
|
"plt.plot(track_upper[0, :], track_upper[1, :], \"r.\")\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",
|
|
"\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": [
|
|
"## VISUALIZE THE COMPUTED HALF-PLANES"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": 12,
|
|
"metadata": {
|
|
"ExecuteTime": {
|
|
"end_time": "2024-10-23T09:26:48.629815Z",
|
|
"start_time": "2024-10-23T09:26:47.949306Z"
|
|
}
|
|
},
|
|
"outputs": [
|
|
{
|
|
"data": {
|
|
"text/plain": "<Figure size 1500x1500 with 9 Axes>",
|
|
"image/png": "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"
|
|
},
|
|
"metadata": {},
|
|
"output_type": "display_data"
|
|
}
|
|
],
|
|
"source": [
|
|
"import numpy as np\n",
|
|
"import matplotlib.pyplot as plt\n",
|
|
"\n",
|
|
"plt.style.use(\"ggplot\")\n",
|
|
"\n",
|
|
"\n",
|
|
"def plot_low_upp(low, up):\n",
|
|
" \"\"\"\n",
|
|
" low and upp arre arrays of shape (3,N)\n",
|
|
" each column represent the couefficient at each\n",
|
|
" step of the optimization\n",
|
|
" \"\"\"\n",
|
|
"\n",
|
|
" # for low,up in zip(low, up):\n",
|
|
" for idx in range(low.shape[1]):\n",
|
|
"\n",
|
|
" ll = low[:, idx]\n",
|
|
" uu = up[:, idx]\n",
|
|
"\n",
|
|
" x = np.linspace(-2, 2, 100)\n",
|
|
"\n",
|
|
" # low\n",
|
|
" y = []\n",
|
|
" for xx in x:\n",
|
|
" y.append((-ll[0] * xx + ll[2]) / ll[1])\n",
|
|
"\n",
|
|
" plt.plot(x, y, \"b-\")\n",
|
|
"\n",
|
|
" # high\n",
|
|
" y = []\n",
|
|
" for xx in x:\n",
|
|
" y.append((-uu[0] * xx + uu[2]) / uu[1])\n",
|
|
"\n",
|
|
" plt.plot(x, y, \"r-\")\n",
|
|
"\n",
|
|
" plt.xlim((-2, 2))\n",
|
|
" plt.ylim((-2, 2))\n",
|
|
"\n",
|
|
"\n",
|
|
"def plot_lines():\n",
|
|
" \"\"\"\n",
|
|
" sample randomly from computed coeff\n",
|
|
" and plot grid\n",
|
|
" \"\"\"\n",
|
|
"\n",
|
|
" plt.figure(figsize=(15, 15))\n",
|
|
" indices = np.random.choice(len(computed_coeff), 9)\n",
|
|
"\n",
|
|
" for i in range(len(indices)):\n",
|
|
" plt.subplot(3, 3, i + 1)\n",
|
|
" plt.title(\"t = \" + str(indices[i]))\n",
|
|
" plot_low_upp(computed_coeff[indices[i]][0], computed_coeff[indices[i]][1])\n",
|
|
"\n",
|
|
" plt.tight_layout()\n",
|
|
" plt.show()\n",
|
|
"\n",
|
|
"\n",
|
|
"plot_lines()"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "markdown",
|
|
"metadata": {},
|
|
"source": [
|
|
"### NOTE \n",
|
|
"There seems to be some flaws in the impementation\n",
|
|
"实现中似乎存在一些缺陷\n",
|
|
"the plane to the LEFT of the vehicle causes issues in the optimization...\n",
|
|
"车辆左侧的平面会导致优化问题...\n",
|
|
"\n",
|
|
"*maybe the \"hanging\" points?*\n",
|
|
"*也许是“悬挂”点?*\n",
|
|
"\n",
|
|
"different approach -> compute those points from the path directly ? Then from contour get semiplanes consrtains?\n",
|
|
"不同的方法 -> 直接从路径计算这些点?然后从轮廓中获取半平面约束?"
|
|
]
|
|
},
|
|
{
|
|
"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.3"
|
|
}
|
|
},
|
|
"nbformat": 4,
|
|
"nbformat_minor": 4
|
|
}
|