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

@@ -2,15 +2,15 @@ import pybullet as p
import struct
def readLogFile(filename, verbose = True):
def readLogFile(filename, verbose=True):
f = open(filename, 'rb')
print('Opened'),
print(filename)
keys = f.readline().decode('utf8').rstrip('\n').split(',')
fmt = f.readline().decode('utf8').rstrip('\n')
# The byte number of one record
sz = struct.calcsize(fmt)
# The type number of one record
@@ -41,11 +41,12 @@ def readLogFile(filename, verbose = True):
return log
#clid = p.connect(p.SHARED_MEMORY)
p.connect(p.GUI)
p.loadSDF("kuka_iiwa/kuka_with_gripper.sdf")
p.loadURDF("tray/tray.urdf",[0,0,0])
p.loadURDF("block.urdf",[0,0,2])
p.loadURDF("tray/tray.urdf", [0, 0, 0])
p.loadURDF("block.urdf", [0, 0, 2])
log = readLogFile("data/block_grasp_log.bin")
@@ -58,26 +59,26 @@ print(recordNum)
print('item num:'),
print(itemNum)
def Step(stepIndex):
for objectId in range(objectNum):
record = log[stepIndex*objectNum+objectId]
Id = record[2]
pos = [record[3],record[4],record[5]]
orn = [record[6],record[7],record[8],record[9]]
p.resetBasePositionAndOrientation(Id,pos,orn)
numJoints = p.getNumJoints(Id)
for i in range (numJoints):
jointInfo = p.getJointInfo(Id,i)
qIndex = jointInfo[3]
if qIndex > -1:
p.resetJointState(Id,i,record[qIndex-7+17])
for objectId in range(objectNum):
record = log[stepIndex * objectNum + objectId]
Id = record[2]
pos = [record[3], record[4], record[5]]
orn = [record[6], record[7], record[8], record[9]]
p.resetBasePositionAndOrientation(Id, pos, orn)
numJoints = p.getNumJoints(Id)
for i in range(numJoints):
jointInfo = p.getJointInfo(Id, i)
qIndex = jointInfo[3]
if qIndex > -1:
p.resetJointState(Id, i, record[qIndex - 7 + 17])
stepIndexId = p.addUserDebugParameter("stepIndex",0,recordNum/objectNum-1,0)
stepIndexId = p.addUserDebugParameter("stepIndex", 0, recordNum / objectNum - 1, 0)
while True:
stepIndex = int(p.readUserDebugParameter(stepIndexId))
Step(stepIndex)
p.stepSimulation()
Step(stepIndex)
stepIndex = int(p.readUserDebugParameter(stepIndexId))
Step(stepIndex)
p.stepSimulation()
Step(stepIndex)