2 from pathlib
import Path
6 import pinocchio
as pin
11 path = Path(__file__).parent.parent.parent /
"models" /
"example-robot-data" /
"python"
12 sys.path.append(str(path))
13 import example_robot_data
16 x_goal = [1, 0, 1.5, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0]
17 x0 = [0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0]
22 d_cog, cf, cm = 0.1525, 6.6e-5, 1e-6
29 [0.0, d_cog, 0.0, -d_cog],
30 [-d_cog, 0.0, d_cog, 0.0],
31 [-cm / cf, cm / cf, -cm / cf, cm / cf],
36 x_nom = [0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0]
40 u = casadi.SX.sym(
"u", 4)
43 return casadi.Function(
"act_model", [u], [tau], [
"u"], [
"tau"])
47 q = casadi.SX.sym(
"dq", model.nq)
48 dq = casadi.SX.sym(
"q", model.nv)
49 v = casadi.SX.sym(
"v", model.nv)
50 dv = casadi.SX.sym(
"dv", model.nv)
52 q_next = cpin.integrate(model, q, dq)
55 dx = casadi.vertcat(dq, dv)
56 x = casadi.vertcat(q, v)
57 x_next = casadi.vertcat(q_next, v_next)
59 return casadi.Function(
"integrate", [x, dx], [x_next], [
"x",
"dx"], [
"x_next"])
63 q0 = casadi.SX.sym(
"q0", model.nq)
64 q1 = casadi.SX.sym(
"q1", model.nq)
65 v0 = casadi.SX.sym(
"v0", model.nv)
66 v1 = casadi.SX.sym(
"v1", model.nv)
68 q_diff = cpin.difference(model, q0, q1)
71 x0 = casadi.vertcat(q0, v0)
72 x1 = casadi.vertcat(q1, v1)
73 x_diff = casadi.vertcat(q_diff, v_diff)
75 return casadi.Function(
"difference", [x0, x1], [x_diff], [
"x0",
"x1"], [
"x_diff"])
80 u = casadi.SX.sym(
"u", nu)
85 q = casadi.SX.sym(
"q", model.nq)
86 v = casadi.SX.sym(
"v", model.nv)
88 a = cpin.aba(model, data, q, v, tau)
90 dq = v * dt + a * dt**2
93 x = casadi.vertcat(q, v)
94 dx = casadi.vertcat(dq, dv)
97 return casadi.Function(
"int_dyn", [x, u], [x_next], [
"x",
"u"], [
"x_next"])
101 dx = casadi.SX.sym(
"dx", model.nv * 2)
106 cost = 0.5 * e_goal.T @ e_goal
108 return casadi.Function(
"quad_cost", [dx], [cost], [
"dx"], [
"cost"])
112 def __init__(self, model, terminal_soft_constraint=False):
131 for i
in range(nodes):
135 1e-5 * 0.5 * e_reg.T @ e_reg
136 + 1e-5 * 0.5 * self.
c_us[:, i].T @ self.
c_us[:, i]
138 if terminal_soft_constraint:
141 self.
opti.minimize(obj)
144 for i
in range(nodes):
152 self.
opti.subject_to(gap == [0] * 12)
155 self.
opti.subject_to(self.
opti.bounded(0, self.
c_us, 5))
158 if not terminal_soft_constraint:
161 self.
opti.subject_to(e_goal == [0] * 12)
168 self.
opti.set_initial(
169 self.
c_dxs, np.vstack([np.zeros(12)
for _
in range(nodes + 1)]).T
171 self.
opti.set_initial(
172 self.
c_us, np.vstack([np.zeros(4)
for _
in range(nodes)]).T
175 def solve(self, approx_hessian=True):
176 opts = {
"verbose":
False}
179 "linear_solver":
"mumps",
181 "mu_strategy":
"adaptive",
185 opts[
"ipopt"][
"hessian_approximation"] =
"limited-memory"
188 self.
opti.solver(
"ipopt", opts)
206 for idx, (dx_sol, u_sol)
in enumerate(
209 q = pin.integrate(self.
model, np.array(x_nom)[:nq], dx_sol[:nv])
212 self.
xs.
append(np.concatenate([q, v]))
216 self.
model, np.array(x_nom)[:nq], self.
sol.value(self.
c_dxs).T[nodes, :nv]
218 v = self.
sol.value(self.
c_dxs).T[nodes, nv:]
219 self.
xs.
append(np.concatenate([q, v]))
222 self.
gaps = {
"vector": [np.zeros(self.
model.nv * 2)],
"norm": [0]}
227 for idx, (x, u)
in enumerate(zip(self.
xs, self.
us)):
230 gap_q = pin.difference(self.
model, x_pin[:nq], self.
xs[idx + 1][:nq])
231 gap_v = self.
xs[idx + 1][nq:] - x_pin[nq:]
233 gap = np.concatenate([gap_q, gap_v])
246 a = pin.aba(self.
model, self.
data, q, v, tau)
248 dq = v * dt + a * dt**2
251 q_next = pin.integrate(self.
model, q, dq)
254 x_next = np.concatenate([q_next, v_next])
260 robot = example_robot_data.load(
"hector")
265 oc_problem.solve(approx_hessian=
True)
269 import matplotlib.pyplot
as plt
271 _, axs0 = plt.subplots(nrows=2)
273 xs = np.vstack(oc_problem.xs)
274 axs0[0].plot(xs[:, :3])
275 axs0[0].set_title(
"Quadcopter position")
277 axs0[1].plot(oc_problem.gaps[
"norm"])
278 axs0[1].set_title(
"Multiple shooting node gaps")
280 _, axs1 = plt.subplots(nrows=4)
281 us = np.vstack(oc_problem.us)
283 for idx, ax
in enumerate(axs1):
286 plt.show(block=
False)
287 except ImportError
as err:
289 "Error while initializing the viewer. "
290 "It seems you should install Python meshcat"
296 if __name__ ==
"__main__":