Projet4MA/Code/robotleg.py
2022-02-08 00:24:50 +01:00

69 lines
3.3 KiB
Python

from pinocchio.utils import *
from pinocchio.explog import exp,log
from numpy.linalg import pinv,norm
from pinocchio import forwardKinematics, Inertia, JointModelRX, Model, SE3
import gepetto.corbaserver
from display import Display
import eigenpy
eigenpy.switchToNumpyArray()
class Visual:
def __init__(self,name,jointParent,placement):
self.name = name # Name in gepetto viewer
self.jointParent = jointParent # ID (int) of the joint
self.placement = placement # placement of the body wrt joint, i.e. bodyMjoint
def place(self,display,oMjoint):
oMbody = oMjoint*self.placement
display.place(self.name,oMbody,False)
class Leg():
def __init__(self,name=''):
self.name = name
self.viewer = Display()
self.visuals = []
self.model = Model ()
self.CreateLeg()
self.data = self.model.createData()
self.q0 = zero(self.model.nq)
def CreateLeg(self,rootId=0,jointPlacement=SE3.Identity()):
color = [red,green,blue,transparency] = [1,1,0.78,1.0]
colorred = [1.0,0.0,0.0,1.0]
jointId = rootId
jointId = rootId
jointName = self.name+"hip_joint"
joint = JointModelRX()
jointId = self.model.addJoint(jointId,joint,jointPlacement,jointName)
self.model.appendBodyToJoint(jointId,Inertia.Random(),SE3.Identity())
self.viewer.viewer.gui.addSphere('world/' +self.name+ 'hip', 0.3,colorred)
self.visuals.append( Visual('world/' + self.name+'hip',jointId,SE3.Identity()) )
self.viewer.viewer.gui.addBox('world/' +self.name+ 'thigh', .1,.1,.5,color)
self.visuals.append( Visual('world/' + self.name+'thigh',jointId,SE3(eye(3),np.array([0., 0., -.5]))))
jointName = self.name+"knee_joint"
jointPlacement = SE3(eye(3),np.array( [0, 0, -1.0] ))
joint = JointModelRX()
jointId = self.model.addJoint(jointId,joint,jointPlacement,jointName)
self.model.appendBodyToJoint(jointId,Inertia.Random(),SE3.Identity())
self.viewer.viewer.gui.addSphere('world/' +self.name+ 'knee', 0.3,colorred)
self.visuals.append( Visual('world/' + self.name+'knee',jointId,SE3.Identity()) )
self.viewer.viewer.gui.addBox('world/' +self.name+ 'tibia', .1,.1,.5,color)
self.visuals.append( Visual('world/' +self.name+ 'tibia',jointId,SE3(eye(3),np.array([0., 0., -.5]))))
jointName = self.name+"ankle_joint"
jointPlacement = SE3(eye(3),np.array( [0, 0, -1.0] ))
joint = JointModelRX()
jointId = self.model.addJoint(jointId,joint,jointPlacement,jointName)
self.model.appendBodyToJoint(jointId,Inertia.Random(),SE3.Identity())
self.viewer.viewer.gui.addSphere('world/' + self.name+'ankle', 0.3,colorred)
self.visuals.append( Visual('world/' + self.name+'ankle',jointId,SE3.Identity()) )
self.viewer.viewer.gui.addBox('world/' +self.name+ 'feet', .25,.5,.1,color)
self.visuals.append( Visual('world/' +self.name+ 'feet',jointId,SE3(eye(3),np.array([0., .1, -.25]))))
def display(self,q):
forwardKinematics(self.model,self.data,q)
for visual in self.visuals:
visual.place( self.viewer,self.data.oMi[visual.jointParent] )
self.viewer.viewer.gui.refresh()