2 Create a simulation environment for a N-pendulum. 17 from numpy.linalg
import pinv,norm
18 import pinocchio
as pin
19 import gepetto.corbaserver
20 from display
import Display
21 from numpy.linalg
import pinv,norm,inv
27 Class representing one 3D mesh of the robot, to be attached to a joint. The class contains: 28 * the name of the 3D objects inside Gepetto viewer. 29 * the ID of the joint in the kinematic tree to which the body is attached. 30 * the placement of the body with respect to the joint frame. 31 This class is only used in the list Robot.visuals (see below). 37 def place(self,display,oMjoint):
39 display.place(self.
name,oMbody,
False)
43 Define a class Robot with 7DOF (shoulder=3 + elbow=1 + wrist=3). 44 The configuration is nq=7. The velocity is the same. 45 The members of the class are: 46 * viewer: a display encapsulating a gepetto viewer client to create 3D objects and place them. 47 * model: the kinematic tree of the robot. 48 * data: the temporary variables to be used by the kinematic algorithms. 49 * visuals: the list of all the 'visual' 3D objects to render the robot, each element of the list being 50 an object Visual (see above). 52 See tp1.py for an example of use. 56 '''Create a Pinocchio model of a N-pendulum, with N the argument <nbJoint>.''' 61 self.
data = self.model.createData()
73 color = [red,green,blue,transparency] = [1,1,0.78,1.0]
74 colorred = [1.0,0.0,0.0,1.0]
77 jointPlacement = jointPlacement
if jointPlacement!=
None else pin.SE3.Identity()
80 inertia = pin.Inertia(mass,
81 np.matrix([0.0,0.0,length/2]).T,
82 mass/5*np.diagflat([ 1e-2,length**2, 1e-2 ]) )
84 for i
in range(nbJoint):
86 name = prefix+
"joint"+istr
87 jointName,bodyName = [name+
"_joint",name+
"_body"]
88 jointId = self.model.addJoint(jointId,pin.JointModelRY(),jointPlacement,jointName)
89 self.model.appendBodyToJoint(jointId,inertia,pin.SE3.Identity())
90 try:self.viewer.viewer.gui.addSphere(
'world/'+prefix+
'sphere'+istr, 0.15,colorred)
92 self.visuals.append(
Visual(
'world/'+prefix+
'sphere'+istr,jointId,pin.SE3.Identity()) )
93 try:self.viewer.viewer.gui.addCapsule(
'world/'+prefix+
'arm'+istr, .1,.8*length,color)
95 self.visuals.append(
Visual(
'world/'+prefix+
'arm'+istr,jointId,
96 pin.SE3(
eye(3),np.matrix([0.,0.,length/2]))))
97 jointPlacement = pin.SE3(
eye(3),np.matrix([0.0,0.0,length]).T)
99 self.model.addFrame( pin.Frame(
'tip',jointId,0,jointPlacement,pin.FrameType.OP_FRAME) )
102 pin.forwardKinematics(self.
model,self.
data,q)
104 visual.place( self.
viewer,self.data.oMi[visual.jointParent] )
105 self.viewer.viewer.gui.refresh()
109 def nq(self):
return self.model.nq
111 def nv(self):
return self.model.nv
113 def nx(self):
return self.nq+self.
nv 117 def nu(self):
return self.nv
121 q0 = np.pi*(
rand(self.
nq)*2-1)
123 x0 = np.vstack([q0,v0])
124 assert len(x0)==self.
nx 127 return self.
obs(self.
x)
130 assert(len(u)==self.
nu)
132 return self.
obs(self.
x),self.
r 136 return np.vstack([ np.vstack([np.cos(qi),np.sin(qi)])
for qi
in x[:self.
nq] ]
138 else:
return x.copy()
141 '''Return the altitude of pendulum tip''' 142 pin.framesKinematics(self.
model,self.
data,q)
143 return self.data.oMf[1].translation[2,0]
147 Dynamic function: x,u -> xnext=f(x,y). 148 Put the result in x (the initial value is destroyed). 149 Also compute the cost of making this step. 150 Return x for convenience along with the cost. 153 modulePi =
lambda th: (th+np.pi)%(2*np.pi)-np.pi
154 sumsq =
lambda x : np.sum(np.square(x))
157 q = modulePi(x[:self.
nq])
159 u = np.clip(np.reshape(np.matrix(u),[self.
nu,1]),-self.
umax,self.
umax)
162 DT = self.
DT/self.
NDT 163 for i
in range(self.
NDT):
164 pin.computeAllTerms(self.
model,self.
data,q,v)
168 a = inv(M)*(u-self.
Kf*v-b)
172 cost += (sumsq(q) + 1e-1*sumsq(v) + 1e-3*sumsq(u))*DT
178 x[:self.
nq] = modulePi(q)
186 time.sleep(self.
DT/10)
def createPendulum(self, nbJoint, rootId=0, prefix='', jointPlacement=None)
def place(self, display, oMjoint)
def __init__(self, nbJoint=1)
def __init__(self, name, jointParent, placement)
def dynamics(self, x, u, display=False)