quadrotor-ocp.py
Go to the documentation of this file.
1 import sys
2 from os.path import abspath, dirname, join
3 
4 import casadi
5 import numpy as np
6 import pinocchio as pin
7 import pinocchio.casadi as cpin
8 
9 # This use the example-robot-data submodule, but if you have it already properly
10 # installed in your PYTHONPATH, there is no need for this sys.path thing
11 path = join(
12  dirname(dirname(dirname(abspath(__file__)))),
13  "models",
14  "example-robot-data",
15  "python",
16 )
17 sys.path.append(path)
18 import example_robot_data # noqa: E402
19 
20 # Problem parameters
21 x_goal = [1, 0, 1.5, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0]
22 x0 = [0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0]
23 nodes = 80
24 dt = 0.02
25 
26 # Quadcopter parameters
27 d_cog, cf, cm = 0.1525, 6.6e-5, 1e-6
28 
29 tau_f = np.array(
30  [
31  [0.0, 0.0, 0.0, 0.0],
32  [0.0, 0.0, 0.0, 0.0],
33  [1.0, 1.0, 1.0, 1.0],
34  [0.0, d_cog, 0.0, -d_cog],
35  [-d_cog, 0.0, d_cog, 0.0],
36  [-cm / cf, cm / cf, -cm / cf, cm / cf],
37  ]
38 )
39 
40 # Other variables
41 x_nom = [0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0]
42 
43 
45  u = casadi.SX.sym("u", 4) # rotor velocities
46  tau = tau_f @ u
47 
48  return casadi.Function("act_model", [u], [tau], ["u"], ["tau"])
49 
50 
51 def state_integrate(model):
52  q = casadi.SX.sym("dq", model.nq)
53  dq = casadi.SX.sym("q", model.nv)
54  v = casadi.SX.sym("v", model.nv)
55  dv = casadi.SX.sym("dv", model.nv)
56 
57  q_next = cpin.integrate(model, q, dq)
58  v_next = v + dv
59 
60  dx = casadi.vertcat(dq, dv)
61  x = casadi.vertcat(q, v)
62  x_next = casadi.vertcat(q_next, v_next)
63 
64  return casadi.Function("integrate", [x, dx], [x_next], ["x", "dx"], ["x_next"])
65 
66 
67 def state_difference(model):
68  q0 = casadi.SX.sym("q0", model.nq)
69  q1 = casadi.SX.sym("q1", model.nq)
70  v0 = casadi.SX.sym("v0", model.nv)
71  v1 = casadi.SX.sym("v1", model.nv)
72 
73  q_diff = cpin.difference(model, q0, q1)
74  v_diff = v1 - v0
75 
76  x0 = casadi.vertcat(q0, v0)
77  x1 = casadi.vertcat(q1, v1)
78  x_diff = casadi.vertcat(q_diff, v_diff)
79 
80  return casadi.Function("difference", [x0, x1], [x_diff], ["x0", "x1"], ["x_diff"])
81 
82 
83 def euler_integration(model, data, dt):
84  nu = 4
85  u = casadi.SX.sym("u", nu)
86 
87  # tau = casadi.vertcat(np.zeros(model.nv - nu), u)
88  tau = actuation_model()(u)
89 
90  q = casadi.SX.sym("q", model.nq)
91  v = casadi.SX.sym("v", model.nv)
92 
93  a = cpin.aba(model, data, q, v, tau)
94 
95  dq = v * dt + a * dt**2
96  dv = a * dt
97 
98  x = casadi.vertcat(q, v)
99  dx = casadi.vertcat(dq, dv)
100  x_next = state_integrate(model)(x, dx)
101 
102  return casadi.Function("int_dyn", [x, u], [x_next], ["x", "u"], ["x_next"])
103 
104 
106  dx = casadi.SX.sym("dx", model.nv * 2)
107 
108  x_N = state_integrate(model)(x_nom, dx)
109  e_goal = state_difference(model)(x_N, x_goal)
110 
111  cost = 0.5 * e_goal.T @ e_goal
112 
113  return casadi.Function("quad_cost", [dx], [cost], ["dx"], ["cost"])
114 
115 
117  def __init__(self, model, terminal_soft_constraint=False):
118  self.opti = casadi.Opti()
119 
120  self.model = model
121  self.data = self.model.createData()
122 
123  self.c_model = cpin.Model(self.model)
124  self.c_data = self.c_model.createData()
125 
126  nv = self.c_model.nv
127  nu = 4
128 
129  self.c_dxs = self.opti.variable(2 * nv, nodes + 1) # state trajectory
130  self.c_us = self.opti.variable(nu, nodes) # control trajectory
131 
132  # Objective function
133  obj = 0
134 
135  # State & Control regularization
136  for i in range(nodes):
137  x_i = state_integrate(self.c_model)(x_nom, self.c_dxs[:, i])
138  e_reg = state_difference(self.c_model)(x_nom, x_i)
139  obj += (
140  1e-5 * 0.5 * e_reg.T @ e_reg
141  + 1e-5 * 0.5 * self.c_us[:, i].T @ self.c_us[:, i]
142  )
143  if terminal_soft_constraint:
144  obj += 1000 * cost_quadratic_state_error(self.c_model)(self.c_dxs[:, nodes])
145 
146  self.opti.minimize(obj)
147 
148  # Dynamical constraints
149  for i in range(nodes):
150  x_i = state_integrate(self.c_model)(x_nom, self.c_dxs[:, i])
151  x_i_1 = state_integrate(self.c_model)(x_nom, self.c_dxs[:, i + 1])
152  f_x_u = euler_integration(self.c_model, self.c_data, dt)(
153  x_i, self.c_us[:, i]
154  )
155  gap = state_difference(self.c_model)(f_x_u, x_i_1)
156 
157  self.opti.subject_to(gap == [0] * 12)
158 
159  # Control constraints
160  self.opti.subject_to(self.opti.bounded(0, self.c_us, 5))
161 
162  # Final constraint
163  if not terminal_soft_constraint:
164  x_N = state_integrate(self.c_model)(x_nom, self.c_dxs[:, nodes])
165  e_goal = state_difference(self.c_model)(x_N, x_goal)
166  self.opti.subject_to(e_goal == [0] * 12)
167 
168  # Initial state
169  x_0 = state_integrate(self.c_model)(x_nom, self.c_dxs[:, 0])
170  self.opti.subject_to(state_difference(self.c_model)(x0, x_0) == [0] * 12)
171 
172  # Warm start
173  self.opti.set_initial(
174  self.c_dxs, np.vstack([np.zeros(12) for _ in range(nodes + 1)]).T
175  )
176  self.opti.set_initial(
177  self.c_us, np.vstack([np.zeros(4) for _ in range(nodes)]).T
178  )
179 
180  def solve(self, approx_hessian=True):
181  opts = {"verbose": False}
182  opts["ipopt"] = {
183  "max_iter": 1000,
184  "linear_solver": "mumps",
185  "tol": 3.82e-6,
186  "mu_strategy": "adaptive",
187  }
188 
189  if approx_hessian:
190  opts["ipopt"]["hessian_approximation"] = "limited-memory"
191 
192  # Solver initialization
193  self.opti.solver("ipopt", opts) # set numerical backend
194 
195  try:
196  self.sol = self.opti.solve()
197  except: # noqa: E722
198  self.sol = self.opti.debug
199 
200  if self.sol.stats()["return_status"] == "Solve_Succeeded":
201  self._retract_trajectory()
202  self._compute_gaps()
203 
205  self.xs = []
206  self.us = []
207  self.gaps = []
208 
209  nq = self.model.nq
210  nv = self.model.nv
211 
212  for idx, (dx_sol, u_sol) in enumerate(
213  zip(self.sol.value(self.c_dxs).T, self.sol.value(self.c_us).T)
214  ):
215  q = pin.integrate(self.model, np.array(x_nom)[:nq], dx_sol[:nv])
216  v = dx_sol[nv:]
217 
218  self.xs.append(np.concatenate([q, v]))
219  self.us.append(u_sol)
220 
221  q = pin.integrate(
222  self.model, np.array(x_nom)[:nq], self.sol.value(self.c_dxs).T[nodes, :nv]
223  )
224  v = self.sol.value(self.c_dxs).T[nodes, nv:]
225  self.xs.append(np.concatenate([q, v]))
226 
227  def _compute_gaps(self):
228  self.gaps = {"vector": [np.zeros(self.model.nv * 2)], "norm": [0]}
229 
230  nq = self.model.nq
231  _nv = self.model.nv
232 
233  for idx, (x, u) in enumerate(zip(self.xs, self.us)):
234  x_pin = self._simulate_step(x, u)
235 
236  gap_q = pin.difference(self.model, x_pin[:nq], self.xs[idx + 1][:nq])
237  gap_v = self.xs[idx + 1][nq:] - x_pin[nq:]
238 
239  gap = np.concatenate([gap_q, gap_v])
240  self.gaps["vector"].append(gap)
241  self.gaps["norm"].append(np.linalg.norm(gap))
242 
243  def _simulate_step(self, x, u):
244  nq = self.model.nq
245  _nv = self.model.nv
246 
247  q = x[:nq]
248  v = x[nq:]
249 
250  tau = tau_f @ u
251 
252  a = pin.aba(self.model, self.data, q, v, tau)
253 
254  dq = v * dt + a * dt**2
255  dv = a * dt
256 
257  q_next = pin.integrate(self.model, q, dq)
258  v_next = v + dv
259 
260  x_next = np.concatenate([q_next, v_next])
261 
262  return x_next
263 
264 
265 def main():
266  robot = example_robot_data.load("hector")
267  model = robot.model
268 
269  oc_problem = OptimalControlProblem(model, terminal_soft_constraint=False)
270 
271  oc_problem.solve(approx_hessian=True)
272 
273  # --------------PLOTS-----------
274  try:
275  import matplotlib.pyplot as plt
276 
277  _, axs0 = plt.subplots(nrows=2)
278 
279  xs = np.vstack(oc_problem.xs)
280  axs0[0].plot(xs[:, :3])
281  axs0[0].set_title("Quadcopter position")
282 
283  axs0[1].plot(oc_problem.gaps["norm"])
284  axs0[1].set_title("Multiple shooting node gaps")
285 
286  _, axs1 = plt.subplots(nrows=4)
287  us = np.vstack(oc_problem.us)
288 
289  for idx, ax in enumerate(axs1):
290  ax.plot(us[:, idx])
291 
292  plt.show(block=False)
293  except ImportError as err:
294  print(
295  "Error while initializing the viewer. "
296  "It seems you should install Python meshcat"
297  )
298  print(err)
299  sys.exit(0)
300 
301 
302 if __name__ == "__main__":
303  main()
quadrotor-ocp.OptimalControlProblem.us
us
Definition: quadrotor-ocp.py:206
quadrotor-ocp.OptimalControlProblem.c_model
c_model
Definition: quadrotor-ocp.py:123
quadrotor-ocp.OptimalControlProblem.gaps
gaps
Definition: quadrotor-ocp.py:207
quadrotor-ocp.euler_integration
def euler_integration(model, data, dt)
Definition: quadrotor-ocp.py:83
quadrotor-ocp.OptimalControlProblem.model
model
Definition: quadrotor-ocp.py:120
quadrotor-ocp.OptimalControlProblem.solve
def solve(self, approx_hessian=True)
Definition: quadrotor-ocp.py:180
quadrotor-ocp.OptimalControlProblem._compute_gaps
def _compute_gaps(self)
Definition: quadrotor-ocp.py:227
pinocchio.casadi
Definition: bindings/python/pinocchio/casadi/__init__.py:1
quadrotor-ocp.OptimalControlProblem.opti
opti
Definition: quadrotor-ocp.py:118
quadrotor-ocp.state_integrate
def state_integrate(model)
Definition: quadrotor-ocp.py:51
quadrotor-ocp.state_difference
def state_difference(model)
Definition: quadrotor-ocp.py:67
quadrotor-ocp.actuation_model
def actuation_model()
Definition: quadrotor-ocp.py:44
quadrotor-ocp.cost_quadratic_state_error
def cost_quadratic_state_error(model)
Definition: quadrotor-ocp.py:105
quadrotor-ocp.OptimalControlProblem.c_us
c_us
Definition: quadrotor-ocp.py:130
quadrotor-ocp.OptimalControlProblem.__init__
def __init__(self, model, terminal_soft_constraint=False)
Definition: quadrotor-ocp.py:117
pinocchio::createData
ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > createData(const ConstraintModelTpl< Scalar, Options, ConstraintCollectionTpl > &cmodel)
Definition: constraint-model-visitor.hpp:248
quadrotor-ocp.OptimalControlProblem.c_dxs
c_dxs
Definition: quadrotor-ocp.py:129
quadrotor-ocp.OptimalControlProblem._retract_trajectory
def _retract_trajectory(self)
Definition: quadrotor-ocp.py:204
quadrotor-ocp.OptimalControlProblem.sol
sol
Definition: quadrotor-ocp.py:196
quadrotor-ocp.OptimalControlProblem.c_data
c_data
Definition: quadrotor-ocp.py:124
quadrotor-ocp.OptimalControlProblem.data
data
Definition: quadrotor-ocp.py:121
quadrotor-ocp.OptimalControlProblem
Definition: quadrotor-ocp.py:116
boost::fusion::append
result_of::push_front< V const, T >::type append(T const &t, V const &v)
Append the element T at the front of boost fusion vector V.
Definition: fusion.hpp:32
quadrotor-ocp.OptimalControlProblem.xs
xs
Definition: quadrotor-ocp.py:205
quadrotor-ocp.main
def main()
Definition: quadrotor-ocp.py:265
quadrotor-ocp.OptimalControlProblem._simulate_step
def _simulate_step(self, x, u)
Definition: quadrotor-ocp.py:243


pinocchio
Author(s):
autogenerated on Wed Sep 25 2024 02:42:28