add yapf style and apply yapf to format all Python files

This recreates pull request #2192
This commit is contained in:
Erwin Coumans
2019-04-27 07:31:15 -07:00
parent c591735042
commit ef9570c315
347 changed files with 70304 additions and 22752 deletions

View File

@@ -1,7 +1,9 @@
import pybullet as p
import numpy as np
class Minitaur:
def __init__(self, urdfRootPath=''):
self.urdfRootPath = urdfRootPath
self.reset()
@@ -26,9 +28,8 @@ class Minitaur:
self.motorIdList.append(self.jointNameToId['motor_back_rightL_joint'])
self.motorIdList.append(self.jointNameToId['motor_back_rightR_joint'])
def reset(self):
self.quadruped = p.loadURDF("%s/quadruped/minitaur.urdf" % self.urdfRootPath,0,0,.2)
self.quadruped = p.loadURDF("%s/quadruped/minitaur.urdf" % self.urdfRootPath, 0, 0, .2)
self.kp = 1
self.kd = 0.1
self.maxForce = 3.5
@@ -38,10 +39,14 @@ class Minitaur:
self.buildJointNameToIdDict()
self.buildMotorIdList()
def setMotorAngleById(self, motorId, desiredAngle):
p.setJointMotorControl2(bodyIndex=self.quadruped, jointIndex=motorId, controlMode=p.POSITION_CONTROL, targetPosition=desiredAngle, positionGain=self.kp, velocityGain=self.kd, force=self.maxForce)
p.setJointMotorControl2(bodyIndex=self.quadruped,
jointIndex=motorId,
controlMode=p.POSITION_CONTROL,
targetPosition=desiredAngle,
positionGain=self.kp,
velocityGain=self.kd,
force=self.maxForce)
def setMotorAngleByName(self, motorName, desiredAngle):
self.setMotorAngleById(self.jointNameToId[motorName], desiredAngle)
@@ -49,53 +54,107 @@ class Minitaur:
def resetPose(self):
kneeFrictionForce = 0
halfpi = 1.57079632679
kneeangle = -2.1834 #halfpi - acos(upper_leg_length / lower_leg_length)
kneeangle = -2.1834 #halfpi - acos(upper_leg_length / lower_leg_length)
#left front leg
p.resetJointState(self.quadruped,self.jointNameToId['motor_front_leftL_joint'],self.motorDir[0]*halfpi)
p.resetJointState(self.quadruped,self.jointNameToId['knee_front_leftL_link'],self.motorDir[0]*kneeangle)
p.resetJointState(self.quadruped,self.jointNameToId['motor_front_leftR_joint'],self.motorDir[1]*halfpi)
p.resetJointState(self.quadruped,self.jointNameToId['knee_front_leftR_link'],self.motorDir[1]*kneeangle)
p.createConstraint(self.quadruped,self.jointNameToId['knee_front_leftR_link'],self.quadruped,self.jointNameToId['knee_front_leftL_link'],p.JOINT_POINT2POINT,[0,0,0],[0,0.005,0.2],[0,0.01,0.2])
self.setMotorAngleByName('motor_front_leftL_joint', self.motorDir[0]*halfpi)
self.setMotorAngleByName('motor_front_leftR_joint', self.motorDir[1]*halfpi)
p.setJointMotorControl2(bodyIndex=self.quadruped,jointIndex=self.jointNameToId['knee_front_leftL_link'],controlMode=p.VELOCITY_CONTROL,targetVelocity=0,force=kneeFrictionForce)
p.setJointMotorControl2(bodyIndex=self.quadruped,jointIndex=self.jointNameToId['knee_front_leftR_link'],controlMode=p.VELOCITY_CONTROL,targetVelocity=0,force=kneeFrictionForce)
p.resetJointState(self.quadruped, self.jointNameToId['motor_front_leftL_joint'],
self.motorDir[0] * halfpi)
p.resetJointState(self.quadruped, self.jointNameToId['knee_front_leftL_link'],
self.motorDir[0] * kneeangle)
p.resetJointState(self.quadruped, self.jointNameToId['motor_front_leftR_joint'],
self.motorDir[1] * halfpi)
p.resetJointState(self.quadruped, self.jointNameToId['knee_front_leftR_link'],
self.motorDir[1] * kneeangle)
p.createConstraint(self.quadruped, self.jointNameToId['knee_front_leftR_link'], self.quadruped,
self.jointNameToId['knee_front_leftL_link'], p.JOINT_POINT2POINT, [0, 0, 0],
[0, 0.005, 0.2], [0, 0.01, 0.2])
self.setMotorAngleByName('motor_front_leftL_joint', self.motorDir[0] * halfpi)
self.setMotorAngleByName('motor_front_leftR_joint', self.motorDir[1] * halfpi)
p.setJointMotorControl2(bodyIndex=self.quadruped,
jointIndex=self.jointNameToId['knee_front_leftL_link'],
controlMode=p.VELOCITY_CONTROL,
targetVelocity=0,
force=kneeFrictionForce)
p.setJointMotorControl2(bodyIndex=self.quadruped,
jointIndex=self.jointNameToId['knee_front_leftR_link'],
controlMode=p.VELOCITY_CONTROL,
targetVelocity=0,
force=kneeFrictionForce)
#left back leg
p.resetJointState(self.quadruped,self.jointNameToId['motor_back_leftL_joint'],self.motorDir[2]*halfpi)
p.resetJointState(self.quadruped,self.jointNameToId['knee_back_leftL_link'],self.motorDir[2]*kneeangle)
p.resetJointState(self.quadruped,self.jointNameToId['motor_back_leftR_joint'],self.motorDir[3]*halfpi)
p.resetJointState(self.quadruped,self.jointNameToId['knee_back_leftR_link'],self.motorDir[3]*kneeangle)
p.createConstraint(self.quadruped,self.jointNameToId['knee_back_leftR_link'],self.quadruped,self.jointNameToId['knee_back_leftL_link'],p.JOINT_POINT2POINT,[0,0,0],[0,0.005,0.2],[0,0.01,0.2])
self.setMotorAngleByName('motor_back_leftL_joint',self.motorDir[2]*halfpi)
self.setMotorAngleByName('motor_back_leftR_joint',self.motorDir[3]*halfpi)
p.setJointMotorControl2(bodyIndex=self.quadruped,jointIndex=self.jointNameToId['knee_back_leftL_link'],controlMode=p.VELOCITY_CONTROL,targetVelocity=0,force=kneeFrictionForce)
p.setJointMotorControl2(bodyIndex=self.quadruped,jointIndex=self.jointNameToId['knee_back_leftR_link'],controlMode=p.VELOCITY_CONTROL,targetVelocity=0,force=kneeFrictionForce)
p.resetJointState(self.quadruped, self.jointNameToId['motor_back_leftL_joint'],
self.motorDir[2] * halfpi)
p.resetJointState(self.quadruped, self.jointNameToId['knee_back_leftL_link'],
self.motorDir[2] * kneeangle)
p.resetJointState(self.quadruped, self.jointNameToId['motor_back_leftR_joint'],
self.motorDir[3] * halfpi)
p.resetJointState(self.quadruped, self.jointNameToId['knee_back_leftR_link'],
self.motorDir[3] * kneeangle)
p.createConstraint(self.quadruped, self.jointNameToId['knee_back_leftR_link'], self.quadruped,
self.jointNameToId['knee_back_leftL_link'], p.JOINT_POINT2POINT, [0, 0, 0],
[0, 0.005, 0.2], [0, 0.01, 0.2])
self.setMotorAngleByName('motor_back_leftL_joint', self.motorDir[2] * halfpi)
self.setMotorAngleByName('motor_back_leftR_joint', self.motorDir[3] * halfpi)
p.setJointMotorControl2(bodyIndex=self.quadruped,
jointIndex=self.jointNameToId['knee_back_leftL_link'],
controlMode=p.VELOCITY_CONTROL,
targetVelocity=0,
force=kneeFrictionForce)
p.setJointMotorControl2(bodyIndex=self.quadruped,
jointIndex=self.jointNameToId['knee_back_leftR_link'],
controlMode=p.VELOCITY_CONTROL,
targetVelocity=0,
force=kneeFrictionForce)
#right front leg
p.resetJointState(self.quadruped,self.jointNameToId['motor_front_rightL_joint'],self.motorDir[4]*halfpi)
p.resetJointState(self.quadruped,self.jointNameToId['knee_front_rightL_link'],self.motorDir[4]*kneeangle)
p.resetJointState(self.quadruped,self.jointNameToId['motor_front_rightR_joint'],self.motorDir[5]*halfpi)
p.resetJointState(self.quadruped,self.jointNameToId['knee_front_rightR_link'],self.motorDir[5]*kneeangle)
p.createConstraint(self.quadruped,self.jointNameToId['knee_front_rightR_link'],self.quadruped,self.jointNameToId['knee_front_rightL_link'],p.JOINT_POINT2POINT,[0,0,0],[0,0.005,0.2],[0,0.01,0.2])
self.setMotorAngleByName('motor_front_rightL_joint',self.motorDir[4]*halfpi)
self.setMotorAngleByName('motor_front_rightR_joint',self.motorDir[5]*halfpi)
p.setJointMotorControl2(bodyIndex=self.quadruped,jointIndex=self.jointNameToId['knee_front_rightL_link'],controlMode=p.VELOCITY_CONTROL,targetVelocity=0,force=kneeFrictionForce)
p.setJointMotorControl2(bodyIndex=self.quadruped,jointIndex=self.jointNameToId['knee_front_rightR_link'],controlMode=p.VELOCITY_CONTROL,targetVelocity=0,force=kneeFrictionForce)
p.resetJointState(self.quadruped, self.jointNameToId['motor_front_rightL_joint'],
self.motorDir[4] * halfpi)
p.resetJointState(self.quadruped, self.jointNameToId['knee_front_rightL_link'],
self.motorDir[4] * kneeangle)
p.resetJointState(self.quadruped, self.jointNameToId['motor_front_rightR_joint'],
self.motorDir[5] * halfpi)
p.resetJointState(self.quadruped, self.jointNameToId['knee_front_rightR_link'],
self.motorDir[5] * kneeangle)
p.createConstraint(self.quadruped, self.jointNameToId['knee_front_rightR_link'],
self.quadruped, self.jointNameToId['knee_front_rightL_link'],
p.JOINT_POINT2POINT, [0, 0, 0], [0, 0.005, 0.2], [0, 0.01, 0.2])
self.setMotorAngleByName('motor_front_rightL_joint', self.motorDir[4] * halfpi)
self.setMotorAngleByName('motor_front_rightR_joint', self.motorDir[5] * halfpi)
p.setJointMotorControl2(bodyIndex=self.quadruped,
jointIndex=self.jointNameToId['knee_front_rightL_link'],
controlMode=p.VELOCITY_CONTROL,
targetVelocity=0,
force=kneeFrictionForce)
p.setJointMotorControl2(bodyIndex=self.quadruped,
jointIndex=self.jointNameToId['knee_front_rightR_link'],
controlMode=p.VELOCITY_CONTROL,
targetVelocity=0,
force=kneeFrictionForce)
#right back leg
p.resetJointState(self.quadruped,self.jointNameToId['motor_back_rightL_joint'],self.motorDir[6]*halfpi)
p.resetJointState(self.quadruped,self.jointNameToId['knee_back_rightL_link'],self.motorDir[6]*kneeangle)
p.resetJointState(self.quadruped,self.jointNameToId['motor_back_rightR_joint'],self.motorDir[7]*halfpi)
p.resetJointState(self.quadruped,self.jointNameToId['knee_back_rightR_link'],self.motorDir[7]*kneeangle)
p.createConstraint(self.quadruped,self.jointNameToId['knee_back_rightR_link'],self.quadruped,self.jointNameToId['knee_back_rightL_link'],p.JOINT_POINT2POINT,[0,0,0],[0,0.005,0.2],[0,0.01,0.2])
self.setMotorAngleByName('motor_back_rightL_joint',self.motorDir[6]*halfpi)
self.setMotorAngleByName('motor_back_rightR_joint',self.motorDir[7]*halfpi)
p.setJointMotorControl2(bodyIndex=self.quadruped,jointIndex=self.jointNameToId['knee_back_rightL_link'],controlMode=p.VELOCITY_CONTROL,targetVelocity=0,force=kneeFrictionForce)
p.setJointMotorControl2(bodyIndex=self.quadruped,jointIndex=self.jointNameToId['knee_back_rightR_link'],controlMode=p.VELOCITY_CONTROL,targetVelocity=0,force=kneeFrictionForce)
p.resetJointState(self.quadruped, self.jointNameToId['motor_back_rightL_joint'],
self.motorDir[6] * halfpi)
p.resetJointState(self.quadruped, self.jointNameToId['knee_back_rightL_link'],
self.motorDir[6] * kneeangle)
p.resetJointState(self.quadruped, self.jointNameToId['motor_back_rightR_joint'],
self.motorDir[7] * halfpi)
p.resetJointState(self.quadruped, self.jointNameToId['knee_back_rightR_link'],
self.motorDir[7] * kneeangle)
p.createConstraint(self.quadruped, self.jointNameToId['knee_back_rightR_link'], self.quadruped,
self.jointNameToId['knee_back_rightL_link'], p.JOINT_POINT2POINT, [0, 0, 0],
[0, 0.005, 0.2], [0, 0.01, 0.2])
self.setMotorAngleByName('motor_back_rightL_joint', self.motorDir[6] * halfpi)
self.setMotorAngleByName('motor_back_rightR_joint', self.motorDir[7] * halfpi)
p.setJointMotorControl2(bodyIndex=self.quadruped,
jointIndex=self.jointNameToId['knee_back_rightL_link'],
controlMode=p.VELOCITY_CONTROL,
targetVelocity=0,
force=kneeFrictionForce)
p.setJointMotorControl2(bodyIndex=self.quadruped,
jointIndex=self.jointNameToId['knee_back_rightR_link'],
controlMode=p.VELOCITY_CONTROL,
targetVelocity=0,
force=kneeFrictionForce)
def getBasePosition(self):
position, orientation = p.getBasePositionAndOrientation(self.quadruped)