2 Create a simulation environment for a N-pendulum. 
   17 import pinocchio 
as pin
 
   18 from display 
import Display
 
   19 from numpy.linalg 
import inv
 
   25     Class representing one 3D mesh of the robot, to be attached to a joint. The class 
   27     * the name of the 3D objects inside Gepetto viewer. 
   28     * the ID of the joint in the kinematic tree to which the body is attached. 
   29     * the placement of the body with respect to the joint frame. 
   30     This class is only used in the list Robot.visuals (see below). 
   33     def __init__(self, name, jointParent, placement):
 
   38     def place(self, display, oMjoint):
 
   40         display.place(self.
name, oMbody, 
False)
 
   45     Define a class Robot with 7DOF (shoulder=3 + elbow=1 + wrist=3). 
   46     The configuration is nq=7. The velocity is the same. 
   47     The members of the class are: 
   48     * viewer: a display encapsulating a gepetto viewer client to create 3D objects and 
   50     * model: the kinematic tree of the robot. 
   51     * data: the temporary variables to be used by the kinematic algorithms. 
   52     * visuals: the list of all the 'visual' 3D objects to render the robot, each element 
   53       of the list being an object Visual (see above). 
   55     See tp1.py for an example of use. 
   59         """Create a Pinocchio model of a N-pendulum, with N the argument <nbJoint>.""" 
   76         color = [red, green, blue, transparency] = [1, 1, 0.78, 1.0]
 
   77         colorred = [1.0, 0.0, 0.0, 1.0]
 
   81             jointPlacement 
if jointPlacement 
is not None else pin.SE3.Identity()
 
   87             np.array([0.0, 0.0, length / 2]),
 
   88             mass / 5 * np.diagflat([1e-2, length**2, 1e-2]),
 
   91         for i 
in range(nbJoint):
 
   93             name = prefix + 
"joint" + istr
 
   94             jointName, _bodyName = [name + 
"_joint", name + 
"_body"]
 
   95             jointId = self.
model.addJoint(
 
   98             self.
model.appendBodyToJoint(jointId, inertia, pin.SE3.Identity())
 
  100                 self.
viewer.viewer.gui.addSphere(
 
  101                     "world/" + prefix + 
"sphere" + istr, 0.15, colorred
 
  106                 Visual(
"world/" + prefix + 
"sphere" + istr, jointId, pin.SE3.Identity())
 
  109                 self.
viewer.viewer.gui.addCapsule(
 
  110                     "world/" + prefix + 
"arm" + istr, 0.1, 0.8 * length, color
 
  116                     "world/" + prefix + 
"arm" + istr,
 
  118                     pin.SE3(np.eye(3), np.array([0.0, 0.0, length / 2])),
 
  121             jointPlacement = 
pin.SE3(np.eye(3), np.array([0.0, 0.0, length]))
 
  124             pin.Frame(
"tip", jointId, 0, jointPlacement, pin.FrameType.OP_FRAME)
 
  130             visual.place(self.
viewer, self.
data.oMi[visual.jointParent])
 
  131         self.
viewer.viewer.gui.refresh()
 
  143         return self.
nq + self.
nv 
  155             q0 = np.pi * (
rand(self.
nq) * 2 - 1)
 
  156             v0 = 
rand(self.
nv) * 2 - 1
 
  157             x0 = np.vstack([q0, v0])
 
  158         assert len(x0) == self.
nx 
  161         return self.
obs(self.
x)
 
  164         assert len(u) == self.
nu 
  166         return self.
obs(self.
x), self.
r 
  171                 [np.vstack([np.cos(qi), np.sin(qi)]) 
for qi 
in x[: self.
nq]]
 
  178         """Return the altitude of pendulum tip""" 
  179         pin.framesKinematics(self.
model, self.
data, q)
 
  180         return self.
data.oMf[1].translation[2, 0]
 
  184         Dynamic function: x,u -> xnext=f(x,y). 
  185         Put the result in x (the initial value is destroyed). 
  186         Also compute the cost of making this step. 
  187         Return x for convenience along with the cost. 
  191             return (th + np.pi) % (2 * np.pi) - np.pi
 
  194             return np.sum(np.square(x))
 
  197         q = modulePi(x[: self.
nq])
 
  199         u = np.clip(np.reshape(np.array(u), [self.
nu, 1]), -self.
umax, self.
umax)
 
  201         DT = self.
DT / self.
NDT 
  202         for i 
in range(self.
NDT):
 
  207             a = inv(M) * (u - self.
Kf * v - b)
 
  211             cost += (sumsq(q) + 1e-1 * sumsq(v) + 1e-3 * sumsq(u)) * DT
 
  217         x[: self.
nq] = modulePi(q)
 
  218         x[self.
nq :] = np.clip(v, -self.
vmax, self.
vmax)
 
  223         q = self.
x[: self.
nq]
 
  225         time.sleep(self.
DT / 10)