ex_4_plan_LIPM_romeo.py
Go to the documentation of this file.
1 # LMPC_walking is a python software implementation of some of the linear MPC
2 # algorithms based presented in:
3 # https://groups.csail.mit.edu/robotics-center/public_papers/Wieber15.pdf
4 # Copyright (C) 2019 @ahmad gazar
5 
6 # LMPC_walking is free software: you can redistribute it and/or modify
7 # it under the terms of the GNU General Public License as published by
8 # the Free Software Foundation, either version 3 of the License, or
9 # (at your option) any later version.
10 
11 # LMPC_walking is distributed in the hope that it will be useful,
12 # but WITHOUT ANY WARRANTY; without even the implied warranty of
13 # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 # GNU General Public License for more details.
15 
16 # You should have received a copy of the GNU General Public License
17 # along with this program. If not, see <https://www.gnu.org/licenses/>.
18 
19 # headers:
20 # -------
21 import numpy as np
22 from quadprog import solve_qp
23 
24 try:
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:
31  print(
32  "Please download LMPC_walking from https://github.com/machines-in-motion/lmpc_walking."
33  )
34  raise e
35 
36 import ex_4_conf as conf
37 import matplotlib.pyplot as plt
38 
39 # from plot_utils import *
40 
41 # import ex_4_long_conf as conf
42 
43 # Inverted pendulum parameters:
44 # ----------------------------
45 foot_length = conf.lxn + conf.lxp # foot size in the x-direction
46 foot_width = conf.lyn + conf.lyp # foot size in the y-direciton
47 nb_dt_per_step = round(conf.T_step / conf.dt_mpc)
48 N = conf.nb_steps * nb_dt_per_step # number of desired walking intervals
49 
50 # CoM initial state: [x_0, xdot_0].T
51 # [y_0, ydot_0].T
52 # ----------------------------------
53 x_0 = np.array([conf.foot_step_0[0], 0.0])
54 y_0 = np.array([conf.foot_step_0[1], 0.0])
55 
56 step_width = 2 * np.absolute(y_0[0])
57 
58 # compute CoP reference trajectory:
59 # --------------------------------
60 foot_steps = reference_trajectories.manual_foot_placement(
61  conf.foot_step_0, conf.step_length, conf.nb_steps
62 )
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
66 )
67 
68 # used in case you want to have terminal constraints
69 # -------------------------------------------------
70 x_terminal = np.array(
71  [cop_ref[N - 1, 0], 0.0]
72 ) # CoM terminal constraint in x : [x, xdot].T
73 y_terminal = np.array(
74  [cop_ref[N - 1, 1], 0.0]
75 ) # CoM terminal constraint in y : [y, ydot].T
76 nb_terminal_constraints = 4
77 terminal_index = N - 1
78 
79 # construct your preview system: 'Go pokemon !'
80 # --------------------------------------------
81 [P_ps, P_vs, P_pu, P_vu] = motion_model.compute_recursive_matrices(
82  conf.dt_mpc, conf.g, conf.h, N
83 )
84 [Q, p_k] = cost_function.compute_objective_terms(
85  conf.alpha,
86  conf.beta,
87  conf.gamma,
88  conf.T_step,
89  nb_dt_per_step,
90  N,
91  conf.step_length,
92  step_width,
93  P_ps,
94  P_pu,
95  P_vs,
96  P_vu,
97  x_0,
98  y_0,
99  cop_ref,
100 )
101 [A_zmp, b_zmp] = constraints.add_ZMP_constraints(
102  N, foot_length, foot_width, cop_ref, x_0, y_0
103 )
104 
105 # used in case you want to add both terminal add_ZMP_constraints
106 # --------------------------------------------------------------
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
109 )
110 A = np.concatenate((A_terminal, A_zmp), axis=0)
111 b = np.concatenate((b_terminal, b_zmp), axis=0)
112 
113 # call quadprog solver:
114 # --------------------
115 U = solve_qp(Q, -p_k, A.T, b, nb_terminal_constraints)[
116  0
117 ] # uncomment to solve with 4 equality terminal constraints
118 cop_x = U[0:N]
119 cop_y = U[N : 2 * N]
120 
121 # Trajectory optimization: (based on the initial state x_hat_0, y_hat_0)
122 # -------------------------------------------------------------------------
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
125 )
126 
127 # ------------------------------------------------------------------------------
128 # visualize your open-loop trajectory:
129 # ------------------------------------------------------------------------------
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))
133 
134 # time vs CoP and CoM in x: 'A.K.A run rabbit run !'
135 # -------------------------------------------------
136 plot_utils.plot_x(
137  True, time, N, min_admissible_CoP, max_admissible_cop, cop_x, com_state_x, cop_ref
138 )
139 
140 # time VS CoP and CoM in y: 'A.K.A what goes up must go down'
141 # ----------------------------------------------------------
142 plot_utils.plot_y(
143  True,
144  time,
145  N,
146  min_admissible_CoP,
147  max_admissible_cop,
148  cop_y,
149  com_state_y,
150  cop_ref,
151  2 * max_admissible_cop,
152 )
153 
154 # plot CoP, CoM in x Vs Cop, CoM in y:
155 # -----------------------------------
156 plot_utils.plot_xy(
157  time, N, foot_length, foot_width, cop_ref, cop_x, cop_y, com_state_x, com_state_y
158 )
159 
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])
162 
163 com_state_x = np.vstack((x_0, com_state_x))
164 com_state_y = np.vstack((y_0, com_state_y))
165 np.savez(
166  conf.DATA_FILE_LIPM,
167  com_state_x=com_state_x,
168  com_state_y=com_state_y,
169  cop_ref=cop_ref,
170  cop_x=cop_x,
171  cop_y=cop_y,
172  foot_steps=foot_steps,
173 )


tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Sat May 3 2025 02:48:16