mpc_python_learn/notebooks/2.3-MPC-simplified.ipynb

532 lines
119 KiB
Plaintext

{
"cells": [
{
"cell_type": "markdown",
"metadata": {},
"source": [
"# Simplified MPC\n",
"\n",
"Checking the implementation from [Reuben Ferrante](https://github.com/arex18/rocket-lander) \n",
"\n",
"Here the system dynamics matrices are evaluated only once given the current state, input -> So no more need to keep track of **x_bar** and **u_bar**.\n",
"\n",
"This should give less precise results but the computation time should be gratly reduced and the overall code is slimmer, worth checking out!"
]
},
{
"cell_type": "code",
"execution_count": 1,
"metadata": {},
"outputs": [],
"source": [
"import numpy as np\n",
"import cvxpy as opt\n",
"import time\n",
"from scipy.integrate import odeint\n",
"from scipy.interpolate import interp1d\n",
"import matplotlib.pyplot as plt\n",
"\n",
"plt.style.use(\"ggplot\")\n",
"\n",
"N = 4 # number of state variables\n",
"M = 2 # number of control variables\n",
"T = 10 # Prediction Horizon\n",
"DT = 0.2 # discretization step\n",
"\n",
"L = 0.3 # vehicle wheelbase\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",
"def get_linear_model_matrices(x_bar, u_bar):\n",
" \"\"\"\n",
" Computes the LTI approximated state space model x' = Ax + Bu + C\n",
" \"\"\"\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",
" ct = np.cos(theta)\n",
" st = np.sin(theta)\n",
" cd = np.cos(delta)\n",
" td = np.tan(delta)\n",
"\n",
" A = np.zeros((N, N))\n",
" A[0, 2] = ct\n",
" A[0, 3] = -v * st\n",
" A[1, 2] = st\n",
" A[1, 3] = v * ct\n",
" A[3, 2] = v * td / 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 * cd**2)\n",
" B_lin = DT * B\n",
"\n",
" f_xu = np.array([v * ct, v * st, a, v * td / L]).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",
" ) # .flatten()\n",
"\n",
" # return np.round(A_lin,6), np.round(B_lin,6), np.round(C_lin,6)\n",
" return A_lin, B_lin, C_lin\n",
"\n",
"\n",
"class MPC:\n",
" def __init__(self, N, M, Q, R):\n",
" \"\"\" \"\"\"\n",
" self.state_len = N\n",
" self.action_len = M\n",
" self.state_cost = Q\n",
" self.action_cost = R\n",
"\n",
" def optimize_linearized_model(\n",
" self,\n",
" A,\n",
" B,\n",
" C,\n",
" initial_state,\n",
" target,\n",
" time_horizon=10,\n",
" Q=None,\n",
" R=None,\n",
" verbose=False,\n",
" ):\n",
" \"\"\"\n",
" Optimisation problem defined for the linearised model,\n",
" :param A:\n",
" :param B:\n",
" :param C:\n",
" :param initial_state:\n",
" :param Q:\n",
" :param R:\n",
" :param target:\n",
" :param time_horizon:\n",
" :param verbose:\n",
" :return:\n",
" \"\"\"\n",
"\n",
" assert len(initial_state) == self.state_len\n",
"\n",
" if Q == None or R == None:\n",
" Q = self.state_cost\n",
" R = self.action_cost\n",
"\n",
" # Create variables\n",
" x = opt.Variable((self.state_len, time_horizon + 1), name=\"states\")\n",
" u = opt.Variable((self.action_len, time_horizon), name=\"actions\")\n",
"\n",
" # Loop through the entire time_horizon and append costs\n",
" cost_function = []\n",
"\n",
" for t in range(time_horizon):\n",
"\n",
" _cost = opt.quad_form(target[:, t + 1] - x[:, t + 1], Q) + opt.quad_form(\n",
" u[:, t], R\n",
" )\n",
"\n",
" _constraints = [\n",
" x[:, t + 1] == A @ x[:, t] + B @ u[:, t] + C,\n",
" u[0, t] >= -MAX_ACC,\n",
" u[0, t] <= MAX_ACC,\n",
" u[1, t] >= -MAX_STEER,\n",
" u[1, t] <= MAX_STEER,\n",
" ]\n",
" # opt.norm(target[:, t + 1] - x[:, t + 1], 1) <= 0.1]\n",
"\n",
" # Actuation rate of change\n",
" if t < (time_horizon - 1):\n",
" _cost += opt.quad_form(u[:, t + 1] - u[:, t], R * 1)\n",
" _constraints += [opt.abs(u[0, t + 1] - u[0, t]) / DT <= MAX_D_ACC]\n",
" _constraints += [opt.abs(u[1, t + 1] - u[1, t]) / DT <= MAX_D_STEER]\n",
"\n",
" if t == 0:\n",
" # _constraints += [opt.norm(target[:, time_horizon] - x[:, time_horizon], 1) <= 0.01,\n",
" # x[:, 0] == initial_state]\n",
" _constraints += [x[:, 0] == initial_state]\n",
"\n",
" cost_function.append(\n",
" opt.Problem(opt.Minimize(_cost), constraints=_constraints)\n",
" )\n",
"\n",
" # Add final cost\n",
" problem = sum(cost_function)\n",
"\n",
" # Minimize Problem\n",
" problem.solve(verbose=verbose, solver=opt.OSQP)\n",
" return x, u"
]
},
{
"cell_type": "code",
"execution_count": 2,
"metadata": {
"jupyter": {
"source_hidden": true
}
},
"outputs": [],
"source": [
"\"\"\"\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",
" For each step in the time horizon\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(1, 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": "code",
"execution_count": 3,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"CVXPY Optimization Time: Avrg: 0.0908s Max: 0.1129s Min: 0.0846s\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",
"x_sim = np.zeros((N, sim_duration))\n",
"u_sim = np.zeros((M, sim_duration - 1))\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",
"x_sim[:, 0] = x0 # simulation_starting conditions\n",
"\n",
"# starting guess\n",
"action = np.zeros(M)\n",
"action[0] = MAX_ACC / 2 # a\n",
"action[1] = 0.0 # delta\n",
"u_sim[:, 0] = action\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",
"mpc = MPC(N, M, Q, R)\n",
"REF_VEL = 1.0\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",
" start_state = np.array([0, 0, x_sim[2, sim_time], 0])\n",
"\n",
" # OPTIONAL: Add time delay to starting State- y\n",
"\n",
" current_action = np.array([u_sim[0, sim_time], u_sim[1, sim_time]])\n",
"\n",
" # State Matrices\n",
" A, B, C = get_linear_model_matrices(start_state, current_action)\n",
"\n",
" # Get Reference_traj -> inputs are in worldframe\n",
" target, _ = get_ref_trajectory(x_sim[:, sim_time], track, REF_VEL)\n",
"\n",
" x_mpc, u_mpc = mpc.optimize_linearized_model(\n",
" A, B, C, start_state, target, time_horizon=T, verbose=False\n",
" )\n",
"\n",
" # retrieved optimized U and assign to u_bar to linearize in next step\n",
" u_bar = np.vstack(\n",
" (np.array(u_mpc.value[0, :]).flatten(), (np.array(u_mpc.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": "markdown",
"metadata": {},
"source": [
"### RESUTS\n",
"\n",
"SCS -> Optimization Time: Avrg: 0.2139s Max: 0.3517s Min: 0.1913s\n",
"\n",
"OSQP -> Optimization Time: Avrg: 0.1035s Max: 0.1311s Min: 0.0959s\n",
"\n",
"ECOS -> Avrg: 0.2024s Max: 0.2313s Min: 0.1904s\n",
"\n",
"**Qualitative result** aka \"it drives?\" seems the same..."
]
},
{
"cell_type": "code",
"execution_count": 4,
"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
}