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


pinocchio
Author(s):
autogenerated on Tue Jun 25 2024 02:42:34