6 import pinocchio 
as pin
 
   17     base_sizes = (0.4, 0.2, 0.05)
 
   20     base_id = model.addJoint(0, base, pin.SE3.Identity(), 
"base")
 
   26     pole_id = model.addJoint(1, pole, pin.SE3.Identity(), 
"pole")
 
   28     base_inertia = pin.Inertia.FromBox(m1, *base_sizes)
 
   31         np.array([0.0, 0.0, length / 2]),
 
   32         m2 / 5 * np.diagflat([1e-2, length**2, 1e-2]),
 
   35     base_body_pl = pin.SE3.Identity()
 
   36     pole_body_pl = pin.SE3.Identity()
 
   37     pole_body_pl.translation = np.array([0.0, 0.0, length / 2])
 
   39     model.appendBodyToJoint(base_id, base_inertia, base_body_pl)
 
   40     model.appendBodyToJoint(pole_id, pole_inertia, pole_body_pl)
 
   44     shape_base = fcl.Box(*base_sizes)
 
   46     shape_pole = fcl.Capsule(radius, length)
 
   47     RED_COLOR = np.array([1, 0.0, 0.0, 1.0])
 
   48     WHITE_COLOR = np.array([1, 1.0, 1.0, 1.0])
 
   50     geom_base.meshColor = WHITE_COLOR
 
   52     geom_pole.meshColor = RED_COLOR
 
   54     collision_model.addGeometryObject(geom_base)
 
   55     collision_model.addGeometryObject(geom_pole)
 
   56     visual_model = collision_model
 
   57     return model, collision_model, visual_model
 
   61     """Take a Pinocchio model, turn it into a Casadi model 
   62     and define the appropriate graphs. 
   65     def __init__(self, model: pin.Model, timestep=0.05):
 
   74         """Create the acceleration expression and acceleration function.""" 
   78         q = casadi.SX.sym(
"q", nq)
 
   79         v = casadi.SX.sym(
"v", nv)
 
   80         u = casadi.SX.sym(
"u", nu)
 
   81         dq_ = casadi.SX.sym(
"dq_", nv)
 
   91         self.
acc_func = casadi.Function(
"acc", [q, v, u], [a], [
"q", 
"v", 
"u"], [
"a"])
 
   95         Create the map `(q,v) -> (qnext, vnext)` using semi-implicit Euler integration. 
  102         q_dq = cpin.integrate(self.
cmodel, q, dq_)
 
  109         qnext = cpin.integrate(self.
cmodel, self.
q_dq, dt * vnext)
 
  115             [
"q", 
"dq_", 
"v", 
"u"],
 
  126         xnext = np.concatenate((qnext, vnext))
 
  133         res = self.dyn_residual(x, u, xnext, dq, dqn)
 
  142         super().
__init__(model=model, timestep=timestep)
 
  147 model = cartpole.model
 
  151 q0 = np.array([0.0, 0.95, 0.01])
 
  153 v = np.zeros(model.nv)
 
  155 a0 = cartpole.acc_func(q0, v, u)
 
  159 x0 = np.append(q0, v)
 
  160 xnext = cartpole.forward(x0, u)
 
  164     states_ = [x0.copy()]
 
  165     for t 
in range(nsteps):
 
  167         xnext = cartpole.forward(states_[t], u).ravel()
 
  168         states_.append(xnext)
 
  173 states_ = np.stack(states_).T
 
  178         collision_model=cartpole.collision_model,
 
  179         visual_model=cartpole.visual_model,
 
  183     viz.loadViewerModel(
"pinocchio")
 
  185     qs_ = states_[: model.nq, :].T
 
  186     viz.play(q_trajectory=qs_, dt=dt)
 
  187 except ImportError 
as err:
 
  189         "Error while initializing the viewer. " 
  190         "It seems you should install Python meshcat"