22 from quadprog
import solve_qp
25 import LMPC_walking.second_order.constraints
as constraints
26 import LMPC_walking.second_order.cost_function
as cost_function
27 import LMPC_walking.second_order.motion_model
as motion_model
28 import LMPC_walking.second_order.plot_utils
as plot_utils
29 import LMPC_walking.second_order.reference_trajectories
as reference_trajectories
30 except ModuleNotFoundError
as e:
32 "Please download LMPC_walking from https://github.com/machines-in-motion/lmpc_walking."
36 import ex_4_conf
as conf
37 import matplotlib.pyplot
as plt
45 foot_length = conf.lxn + conf.lxp
46 foot_width = conf.lyn + conf.lyp
47 nb_dt_per_step = round(conf.T_step / conf.dt_mpc)
48 N = conf.nb_steps * nb_dt_per_step
53 x_0 = np.array([conf.foot_step_0[0], 0.0])
54 y_0 = np.array([conf.foot_step_0[1], 0.0])
56 step_width = 2 * np.absolute(y_0[0])
60 foot_steps = reference_trajectories.manual_foot_placement(
61 conf.foot_step_0, conf.step_length, conf.nb_steps
63 foot_steps[1:, 0] -= conf.step_length
64 cop_ref = reference_trajectories.create_CoP_trajectory(
65 conf.nb_steps, foot_steps, N, nb_dt_per_step
70 x_terminal = np.array(
71 [cop_ref[N - 1, 0], 0.0]
73 y_terminal = np.array(
74 [cop_ref[N - 1, 1], 0.0]
76 nb_terminal_constraints = 4
77 terminal_index = N - 1
81 [P_ps, P_vs, P_pu, P_vu] = motion_model.compute_recursive_matrices(
82 conf.dt_mpc, conf.g, conf.h, N
84 [Q, p_k] = cost_function.compute_objective_terms(
101 [A_zmp, b_zmp] = constraints.add_ZMP_constraints(
102 N, foot_length, foot_width, cop_ref, x_0, y_0
107 [A_terminal, b_terminal] = constraints.add_terminal_constraints(
108 N, terminal_index, x_0, y_0, x_terminal, y_terminal, P_ps, P_vs, P_pu, P_vu
110 A = np.concatenate((A_terminal, A_zmp), axis=0)
111 b = np.concatenate((b_terminal, b_zmp), axis=0)
115 U = solve_qp(Q, -p_k, A.T, b, nb_terminal_constraints)[
123 [com_state_x, com_state_y] = motion_model.compute_recursive_dynamics(
124 P_ps, P_vs, P_pu, P_vu, N, x_0, y_0, U
130 time = np.arange(0, round(N * conf.dt_mpc, 2), conf.dt_mpc)
131 min_admissible_CoP = cop_ref - np.tile([foot_length / 2, foot_width / 2], (N, 1))
132 max_admissible_cop = cop_ref + np.tile([foot_length / 2, foot_width / 2], (N, 1))
137 True, time, N, min_admissible_CoP, max_admissible_cop, cop_x, com_state_x, cop_ref
151 2 * max_admissible_cop,
157 time, N, foot_length, foot_width, cop_ref, cop_x, cop_y, com_state_x, com_state_y
160 plt.gca().set_xlim([cop_ref[0, 0] - 0.2, cop_ref[-1, 0] + 0.2])
161 plt.gca().set_ylim([cop_ref[0, 1] - 0.2, cop_ref[-1, 1] + 0.2])
163 com_state_x = np.vstack((x_0, com_state_x))
164 com_state_y = np.vstack((y_0, com_state_y))
167 com_state_x=com_state_x,
168 com_state_y=com_state_y,
172 foot_steps=foot_steps,