mpc_python_learn/notebooks/2.0-MPC-base.ipynb

748 lines
150 KiB
Plaintext

{
"cells": [
{
"cell_type": "markdown",
"metadata": {},
"source": [
"# 2 MPC\n",
"This notebook contains the CVXPY implementation of a MPC\n",
"This is the simplest one"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"### MPC Problem formulation\n",
"\n",
"**Model Predictive Control** refers to the control approach of **numerically** solving a optimization problem at each time step. \n",
"\n",
"The controller generates a control signal over a fixed lenght T (Horizon) at each time step."
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"![mpc](img/mpc_block_diagram.png)\n",
"\n",
"![mpc](img/mpc_t.png)"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"#### Linear MPC Formulation\n",
"\n",
"Linear MPC makes use of the **LTI** (Linear time invariant) discrete state space model, wich represents a motion model used for Prediction.\n",
"\n",
"$x_{t+1} = Ax_t + Bu_t$\n",
"\n",
"The LTI formulation means that **future states** are linearly related to the current state and actuator signal. Hence, the MPC seeks to find a **control policy** U over a finite lenght horizon.\n",
"\n",
"$U={u_{t|t}, u_{t+1|t}, ...,u_{t+T|t}}$\n",
"\n",
"The objective function used minimize (drive the state to 0) is:\n",
"\n",
"$\n",
"\\begin{equation}\n",
"\\begin{aligned}\n",
"\\min_{} \\quad & \\sum^{t+T-1}_{j=t} x^T_{j|t}Qx_{j|t} + u^T_{j|t}Ru_{j|t}\\\\\n",
"\\textrm{s.t.} \\quad & x(0) = x0\\\\\n",
" & x_{j+1|t} = Ax_{j|t}+Bu_{j|t}) \\quad \\textrm{for} \\quad t<j<t+T-1 \\\\\n",
"\\end{aligned}\n",
"\\end{equation}\n",
"$\n",
"\n",
"Other linear constrains may be applied,for instance on the control variable:\n",
"\n",
"$ U_{MIN} < u_{j|t} < U_{MAX} \\quad \\textrm{for} \\quad t<j<t+T-1 $\n",
"\n",
"The objective fuction accounts for quadratic error on deviation from 0 of the state and the control inputs sequences. Q and R are the **weight matrices** and are used to tune the response.\n",
"\n",
"Because the goal is tracking a **reference signal** such as a trajectory, the objective function is rewritten as:\n",
"\n",
"$\n",
"\\begin{equation}\n",
"\\begin{aligned}\n",
"\\min_{} \\quad & \\sum^{t+T-1}_{j=t} \\delta x^T_{j|t}Q\\delta x_{j|t} + u^T_{j|t}Ru_{j|t}\n",
"\\end{aligned}\n",
"\\end{equation}\n",
"$\n",
"\n",
"where the error w.r.t desired state is accounted for:\n",
"\n",
"$ \\delta x = x_{j,t,ref} - x_{j,t} $"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"# Problem Formulation: Study case\n",
"\n",
"In this case, the objective function to minimize is given by:\n",
"\n",
"https://borrelli.me.berkeley.edu/pdfpub/IV_KinematicMPC_jason.pdf\n",
"\n",
"$\n",
"\\begin{equation}\n",
"\\begin{aligned}\n",
"\\min_{} \\quad & \\sum^{t+T-1}_{j=t} (x_{j} - x_{j,ref})^TQ(x_{j} - x_{j,ref}) + \\sum^{t+T-1}_{j=t+1} u^T_{j}Ru_{j} + (u_{j} - u_{j-1})^TP(u_{j} - u_{j-1}) \\\\\n",
"\\textrm{s.t.} \\quad & x(0) = x0\\\\\n",
" & x_{j+1} = Ax_{j}+Bu_{j} \\quad \\textrm{for} \\quad t<j<t+T-1 \\\\\n",
" & u_{MIN} < u_{j} < u_{MAX} \\quad \\textrm{for} \\quad t<j<t+T-1 \\\\\n",
" & \\dot{u}_{MIN} < \\frac{(u_{j} - u_{j-1})}{ts} < \\dot{u}_{MAX} \\quad \\textrm{for} \\quad t+1<j<t+T-1 \\\\\n",
"\\end{aligned}\n",
"\\end{equation}\n",
"$\n",
"\n",
"\n",
"Where R,P,Q are the cost matrices used to tune the response.\n"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## PRELIMINARIES\n",
"\n",
"* linearized system dynamics\n",
"* function to represent the track\n",
"* function to represent the **reference trajectory** to track"
]
},
{
"cell_type": "code",
"execution_count": 1,
"metadata": {},
"outputs": [],
"source": [
"import numpy as np\n",
"from scipy.integrate import odeint\n",
"from scipy.interpolate import interp1d\n",
"import cvxpy as cp\n",
"\n",
"import matplotlib.pyplot as plt\n",
"\n",
"plt.style.use(\"ggplot\")\n",
"\n",
"import time"
]
},
{
"cell_type": "code",
"execution_count": 2,
"metadata": {},
"outputs": [],
"source": [
"\"\"\"\n",
"Control problem statement.\n",
"\"\"\"\n",
"\n",
"N = 4 # number of state variables\n",
"M = 2 # number of control variables\n",
"T = 20 # Prediction Horizon\n",
"DT = 0.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",
"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",
" final_xp = np.append(final_xp, fx(interp_range))\n",
" final_yp = np.append(final_yp, fy(interp_range))\n",
"\n",
" dx = np.append(0, np.diff(final_xp))\n",
" dy = np.append(0, np.diff(final_yp))\n",
" theta = np.arctan2(dy, dx)\n",
"\n",
" return np.vstack((final_xp, final_yp, theta))\n",
"\n",
"\n",
"def get_nn_idx(state, path):\n",
" \"\"\"\n",
" Computes the index of the waypoint closest to vehicle\n",
" \"\"\"\n",
"\n",
" dx = state[0] - path[0, :]\n",
" dy = state[1] - path[1, :]\n",
" dist = np.hypot(dx, dy)\n",
" nn_idx = np.argmin(dist)\n",
"\n",
" try:\n",
" v = [\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 get_ref_trajectory(state, path, target_v):\n",
" \"\"\"\n",
" Adapted from pythonrobotics\n",
" \"\"\"\n",
" xref = np.zeros((N, T + 1))\n",
" dref = np.zeros((1, T + 1))\n",
"\n",
" # sp = np.ones((1,T +1))*target_v #speed profile\n",
"\n",
" ncourse = path.shape[1]\n",
"\n",
" ind = get_nn_idx(state, path)\n",
"\n",
" xref[0, 0] = path[0, ind] # X\n",
" xref[1, 0] = path[1, ind] # Y\n",
" xref[2, 0] = target_v # sp[ind] #V\n",
" xref[3, 0] = path[2, ind] # Theta\n",
" dref[0, 0] = 0.0 # steer operational point should be 0\n",
"\n",
" dl = 0.05 # Waypoints spacing [m]\n",
" travel = 0.0\n",
"\n",
" for i in range(T + 1):\n",
" travel += abs(target_v) * DT # current V or target V?\n",
" dind = int(round(travel / dl))\n",
"\n",
" if (ind + dind) < ncourse:\n",
" xref[0, i] = path[0, ind + dind]\n",
" xref[1, i] = path[1, ind + dind]\n",
" xref[2, i] = target_v # sp[ind + dind]\n",
" xref[3, i] = path[2, ind + dind]\n",
" dref[0, i] = 0.0\n",
" else:\n",
" xref[0, i] = path[0, ncourse - 1]\n",
" xref[1, i] = path[1, ncourse - 1]\n",
" xref[2, i] = 0.0 # stop? #sp[ncourse - 1]\n",
" xref[3, i] = path[2, ncourse - 1]\n",
" dref[0, i] = 0.0\n",
"\n",
" return xref, dref"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## MPC \n",
"\n",
"test single iteration"
]
},
{
"cell_type": "code",
"execution_count": 3,
"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 = 326, constraints m = 408\n",
" nnz(P) + nnz(A) = 1063\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 4.27e+00 4.67e+02 1.00e-01 4.07e-04s\n",
" 175 1.6965e+02 2.63e-05 3.49e-05 7.14e+00 1.86e-03s\n",
"\n",
"status: solved\n",
"solution polish: unsuccessful\n",
"number of iterations: 175\n",
"optimal objective: 169.6454\n",
"run time: 2.50e-03s\n",
"optimal rho estimate: 6.34e+00\n",
"\n",
"CPU times: user 122 ms, sys: 75 µs, total: 122 ms\n",
"Wall time: 119 ms\n"
]
}
],
"source": [
"%%time\n",
"\n",
"MAX_SPEED = 1.5 # m/s\n",
"MAX_STEER = np.radians(30) # rad\n",
"MAX_ACC = 1.0\n",
"REF_VEL = 1.0\n",
"\n",
"track = compute_path_from_wp([0, 3, 6], [0, 0, 0], 0.05)\n",
"\n",
"# Starting Condition\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0 # x\n",
"x0[1] = -0.25 # y\n",
"x0[2] = 0.0 # v\n",
"x0[3] = np.radians(-0) # yaw\n",
"\n",
"# starting guess\n",
"u_bar = np.zeros((M, T))\n",
"u_bar[0, :] = MAX_ACC / 2 # a\n",
"u_bar[1, :] = 0.1 # delta\n",
"\n",
"# dynamics starting state w.r.t world frame\n",
"x_bar = np.zeros((N, T + 1))\n",
"x_bar[:, 0] = x0\n",
"\n",
"# prediction for linearization of costrains\n",
"for t in range(1, T + 1):\n",
" xt = x_bar[:, t - 1].reshape(N, 1)\n",
" ut = u_bar[:, t - 1].reshape(M, 1)\n",
" A, B, C = get_linear_model(xt, ut)\n",
" xt_plus_one = np.squeeze(np.dot(A, xt) + np.dot(B, ut) + C)\n",
" x_bar[:, t] = xt_plus_one\n",
"\n",
"# CVXPY Linear MPC problem statement\n",
"x = cp.Variable((N, T + 1))\n",
"u = cp.Variable((M, T))\n",
"cost = 0\n",
"constr = []\n",
"\n",
"# Cost Matrices\n",
"Q = np.diag([10, 10, 10, 10]) # state error cost\n",
"Qf = np.diag([10, 10, 10, 10]) # state final error cost\n",
"R = np.diag([10, 10]) # input cost\n",
"R_ = np.diag([10, 10]) # input rate of change cost\n",
"\n",
"# Get Reference_traj\n",
"x_ref, d_ref = get_ref_trajectory(x_bar[:, 0], track, REF_VEL)\n",
"\n",
"# Prediction Horizon\n",
"for t in range(T):\n",
"\n",
" # Tracking Error\n",
" cost += cp.quad_form(x[:, t] - x_ref[:, t], Q)\n",
"\n",
" # Actuation effort\n",
" cost += cp.quad_form(u[:, t], R)\n",
"\n",
" # Actuation rate of change\n",
" if t < (T - 1):\n",
" cost += cp.quad_form(u[:, t + 1] - u[:, t], R_)\n",
"\n",
" # Kinrmatics Constrains (Linearized model)\n",
" A, B, C = get_linear_model(x_bar[:, t], u_bar[:, t])\n",
" constr += [x[:, t + 1] == A @ x[:, t] + B @ u[:, t] + C.flatten()]\n",
"\n",
"# 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",
"# for t in range(T):\n",
"# if t < (T - 1):\n",
"# constr += [cp.abs(u[0,t] - u[0,t-1])/DT <= MAX_ACC] #max acc\n",
"# constr += [cp.abs(u[1,t] - u[1,t-1])/DT <= MAX_STEER] #max steer\n",
"\n",
"prob = cp.Problem(cp.Minimize(cost), constr)\n",
"solution = prob.solve(solver=cp.OSQP, verbose=True)"
]
},
{
"cell_type": "code",
"execution_count": 4,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 432x288 with 4 Axes>"
]
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"x_mpc = np.array(x.value[0, :]).flatten()\n",
"y_mpc = np.array(x.value[1, :]).flatten()\n",
"v_mpc = np.array(x.value[2, :]).flatten()\n",
"theta_mpc = np.array(x.value[3, :]).flatten()\n",
"a_mpc = np.array(u.value[0, :]).flatten()\n",
"delta_mpc = np.array(u.value[1, :]).flatten()\n",
"\n",
"# simulate robot state trajectory for optimized U\n",
"x_traj = predict(x0, np.vstack((a_mpc, delta_mpc)))\n",
"\n",
"# plt.figure(figsize=(15,10))\n",
"# plot trajectory\n",
"plt.subplot(2, 2, 1)\n",
"plt.plot(track[0, :], track[1, :], \"b\")\n",
"plt.plot(x_ref[0, :], x_ref[1, :], \"g+\")\n",
"plt.plot(x_traj[0, :], x_traj[1, :])\n",
"plt.axis(\"equal\")\n",
"plt.ylabel(\"y\")\n",
"plt.xlabel(\"x\")\n",
"\n",
"# plot v(t)\n",
"plt.subplot(2, 2, 3)\n",
"plt.plot(a_mpc)\n",
"plt.ylabel(\"a_in(t)\")\n",
"# plt.xlabel('time')\n",
"\n",
"\n",
"plt.subplot(2, 2, 2)\n",
"plt.plot(theta_mpc)\n",
"plt.ylabel(\"theta(t)\")\n",
"\n",
"plt.subplot(2, 2, 4)\n",
"plt.plot(delta_mpc)\n",
"plt.ylabel(\"d_in(t)\")\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
},
{
"cell_type": "markdown",
"metadata": {},
"source": [
"## full track demo"
]
},
{
"cell_type": "code",
"execution_count": 5,
"metadata": {},
"outputs": [
{
"name": "stderr",
"output_type": "stream",
"text": [
"/home/marcello/.conda/envs/jupyter/lib/python3.8/site-packages/cvxpy/problems/problem.py:1054: UserWarning: Solution may be inaccurate. Try another solver, adjusting the solver settings, or solve with verbose=True for more information.\n",
" warnings.warn(\n"
]
},
{
"name": "stdout",
"output_type": "stream",
"text": [
"CVXPY Optimization Time: Avrg: 0.1677s Max: 0.2731s Min: 0.1438s\n"
]
}
],
"source": [
"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",
"# track = compute_path_from_wp([0,10,10,0],\n",
"# [0,0,1,1],0.05)\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",
"REF_VEL = 1.0 # m/s\n",
"\n",
"# Starting Condition\n",
"x0 = np.zeros(N)\n",
"x0[0] = 0 # x\n",
"x0[1] = -0.25 # y\n",
"x0[2] = 0.0 # v\n",
"x0[3] = np.radians(-0) # yaw\n",
"\n",
"# starting guess\n",
"u_bar = np.zeros((M, T))\n",
"u_bar[0, :] = MAX_ACC / 2 # a\n",
"u_bar[1, :] = 0.0 # delta\n",
"\n",
"for sim_time in range(sim_duration - 1):\n",
"\n",
" iter_start = time.time()\n",
"\n",
" # dynamics starting state\n",
" x_bar = np.zeros((N, T + 1))\n",
" x_bar[:, 0] = x_sim[:, sim_time]\n",
"\n",
" # prediction for linearization of costrains\n",
" for t in range(1, T + 1):\n",
" xt = x_bar[:, t - 1].reshape(N, 1)\n",
" ut = u_bar[:, t - 1].reshape(M, 1)\n",
" A, B, C = get_linear_model(xt, ut)\n",
" xt_plus_one = np.squeeze(np.dot(A, xt) + np.dot(B, ut) + C)\n",
" x_bar[:, t] = xt_plus_one\n",
"\n",
" # CVXPY Linear MPC problem statement\n",
" x = cp.Variable((N, T + 1))\n",
" u = cp.Variable((M, T))\n",
" cost = 0\n",
" constr = []\n",
"\n",
" # Cost Matrices\n",
" Q = np.diag([20, 20, 10, 0]) # state error cost\n",
" Qf = np.diag([30, 30, 30, 0]) # state final error cost\n",
" R = np.diag([10, 10]) # input cost\n",
" R_ = np.diag([10, 10]) # input rate of change cost\n",
"\n",
" # Get Reference_traj\n",
" x_ref, d_ref = get_ref_trajectory(x_bar[:, 0], track, REF_VEL)\n",
"\n",
" # Prediction Horizon\n",
" for t in range(T):\n",
"\n",
" # Tracking Error\n",
" cost += cp.quad_form(x[:, t] - x_ref[:, t], Q)\n",
"\n",
" # Actuation effort\n",
" cost += cp.quad_form(u[:, t], R)\n",
"\n",
" # Actuation rate of change\n",
" if t < (T - 1):\n",
" cost += cp.quad_form(u[:, t + 1] - u[:, t], R_)\n",
" 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": 6,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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\n",
"text/plain": [
"<Figure size 1080x720 with 5 Axes>"
]
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"# plot trajectory\n",
"grid = plt.GridSpec(4, 5)\n",
"\n",
"plt.figure(figsize=(15, 10))\n",
"\n",
"plt.subplot(grid[0:4, 0:4])\n",
"plt.plot(track[0, :], track[1, :], \"b+\")\n",
"plt.plot(x_sim[0, :], x_sim[1, :])\n",
"plt.axis(\"equal\")\n",
"plt.ylabel(\"y\")\n",
"plt.xlabel(\"x\")\n",
"\n",
"plt.subplot(grid[0, 4])\n",
"plt.plot(u_sim[0, :])\n",
"plt.ylabel(\"a(t) [m/ss]\")\n",
"\n",
"plt.subplot(grid[1, 4])\n",
"plt.plot(x_sim[2, :])\n",
"plt.ylabel(\"v(t) [m/s]\")\n",
"\n",
"plt.subplot(grid[2, 4])\n",
"plt.plot(np.degrees(u_sim[1, :]))\n",
"plt.ylabel(\"delta(t) [rad]\")\n",
"\n",
"plt.subplot(grid[3, 4])\n",
"plt.plot(x_sim[3, :])\n",
"plt.ylabel(\"theta(t) [rad]\")\n",
"\n",
"plt.tight_layout()\n",
"plt.show()"
]
}
],
"metadata": {
"kernelspec": {
"display_name": "Python [conda env:.conda-jupyter] *",
"language": "python",
"name": "conda-env-.conda-jupyter-py"
},
"language_info": {
"codemirror_mode": {
"name": "ipython",
"version": 3
},
"file_extension": ".py",
"mimetype": "text/x-python",
"name": "python",
"nbconvert_exporter": "python",
"pygments_lexer": "ipython3",
"version": "3.8.5"
}
},
"nbformat": 4,
"nbformat_minor": 4
}