add python dumpLog.py utility to view log files created using 'startStateLogging'
don't enable <CTRL> for hotkeys yet
add some more profile markers
log objectId and linkIndex as signed int ('i') and not unsigned int 'I'
fix issue in startStateLogging: number of parameters was wrong
This commit is contained in:
74
examples/pybullet/examples/dumpLog.py
Normal file
74
examples/pybullet/examples/dumpLog.py
Normal file
@@ -0,0 +1,74 @@
|
||||
import time
|
||||
import math
|
||||
from datetime import datetime
|
||||
import struct
|
||||
import sys
|
||||
import os, fnmatch
|
||||
import argparse
|
||||
from time import sleep
|
||||
|
||||
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
|
||||
ncols = len(fmt)
|
||||
|
||||
if verbose:
|
||||
print('Keys:'),
|
||||
print(keys)
|
||||
print('Format:'),
|
||||
print(fmt)
|
||||
print('Size:'),
|
||||
print(sz)
|
||||
print('Columns:'),
|
||||
print(ncols)
|
||||
|
||||
# Read data
|
||||
wholeFile = f.read()
|
||||
# split by alignment word
|
||||
chunks = wholeFile.split(b'\xaa\xbb')
|
||||
log = list()
|
||||
if verbose:
|
||||
print("num chunks:")
|
||||
print(len(chunks))
|
||||
chunkIndex = 0
|
||||
for chunk in chunks:
|
||||
print("len(chunk)=",len(chunk)," sz = ", sz)
|
||||
if len(chunk) == sz:
|
||||
print("chunk #",chunkIndex)
|
||||
chunkIndex=chunkIndex+1
|
||||
values = struct.unpack(fmt, chunk)
|
||||
record = list()
|
||||
for i in range(ncols):
|
||||
record.append(values[i])
|
||||
if verbose:
|
||||
print(" ",keys[i],"=",values[i])
|
||||
|
||||
log.append(record)
|
||||
|
||||
return log
|
||||
|
||||
|
||||
numArgs = len(sys.argv)
|
||||
|
||||
print ('Number of arguments:', numArgs, 'arguments.')
|
||||
print ('Argument List:', str(sys.argv))
|
||||
fileName = "log.bin"
|
||||
|
||||
if (numArgs>1):
|
||||
fileName = sys.argv[1]
|
||||
|
||||
print("filename=")
|
||||
print(fileName)
|
||||
|
||||
verbose = True
|
||||
|
||||
readLogFile(fileName,verbose)
|
||||
@@ -1,7 +1,13 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
|
||||
p.connect(p.GUI)
|
||||
conid = p.connect(p.SHARED_MEMORY)
|
||||
if (conid<0):
|
||||
p.connect(p.GUI)
|
||||
|
||||
p.setInternalSimFlags(0)
|
||||
p.resetSimulation()
|
||||
|
||||
p.loadURDF("plane.urdf",useMaximalCoordinates=True)
|
||||
p.loadURDF("tray/traybox.urdf",useMaximalCoordinates=True)
|
||||
|
||||
@@ -12,7 +18,7 @@ p.setPhysicsEngineParameter(numSolverIterations=10)
|
||||
p.setPhysicsEngineParameter(contactBreakingThreshold=0.001)
|
||||
for i in range (10):
|
||||
for j in range (10):
|
||||
for k in range (5):
|
||||
for k in range (10):
|
||||
ob = p.loadURDF("sphere_1cm.urdf",[0.02*i,0.02*j,0.2+0.02*k],useMaximalCoordinates=True)
|
||||
p.setGravity(0,0,-10)
|
||||
p.setRealTimeSimulation(1)
|
||||
|
||||
@@ -143,7 +143,7 @@ p.setRealTimeSimulation(useRealTime)
|
||||
print("quadruped Id = ")
|
||||
print(quadruped)
|
||||
p.saveWorld("quadru.py")
|
||||
logId = p.startStateLogging(p.STATE_LOGGING_MINITAUR,"quadrupedLog.txt",[quadruped])
|
||||
logId = p.startStateLogging(p.STATE_LOGGING_MINITAUR,"quadrupedLog.bin",[quadruped])
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -1,6 +1,9 @@
|
||||
import pybullet as p
|
||||
#p.connect(p.UDP,"192.168.86.100")
|
||||
p.connect(p.SHARED_MEMORY)
|
||||
|
||||
cid = p.connect(p.SHARED_MEMORY)
|
||||
if (cid<0):
|
||||
p.connect(p.GUI)
|
||||
p.resetSimulation()
|
||||
|
||||
objects = [p.loadURDF("plane.urdf", 0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,1.000000)]
|
||||
|
||||
@@ -19,6 +19,9 @@ if (c<0):
|
||||
p.setInternalSimFlags(0)#don't load default robot assets etc
|
||||
p.resetSimulation()
|
||||
p.loadURDF("plane.urdf")
|
||||
p.loadURDF("cube.urdf",0,0,1)
|
||||
p.setGravity(0,0,-10)
|
||||
p.setRealTimeSimulation(1)
|
||||
|
||||
prevPosition=[None]*p.VR_MAX_CONTROLLERS
|
||||
colors=[0.,0.5,0.5]*p.VR_MAX_CONTROLLERS
|
||||
@@ -32,6 +35,10 @@ colors[3] = [0,0,0.5]
|
||||
colors[4] = [0.5,0.5,0.]
|
||||
colors[5] = [.5,.5,.5]
|
||||
|
||||
p.startStateLogging(p.STATE_LOGGING_VR_CONTROLLERS, "vr_hmd.bin",deviceTypeFilter=p.VR_DEVICE_HMD)
|
||||
p.startStateLogging(p.STATE_LOGGING_GENERIC_ROBOT, "generic_data.bin")
|
||||
p.startStateLogging(p.STATE_LOGGING_CONTACT_POINTS, "contact_points.bin")
|
||||
|
||||
while True:
|
||||
events = p.getVREvents(p.VR_DEVICE_HMD+p.VR_DEVICE_GENERIC_TRACKER)
|
||||
for e in (events):
|
||||
|
||||
@@ -2697,8 +2697,8 @@ static PyObject* pybullet_startStateLogging(PyObject* self, PyObject* args, PyOb
|
||||
static char* kwlist[] = {"loggingType", "fileName", "objectUniqueIds", "maxLogDof", "bodyUniqueIdA", "bodyUniqueIdB", "linkIndexA", "linkIndexB", "deviceTypeFilter", "physicsClientId", NULL};
|
||||
int physicsClientId = 0;
|
||||
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "is|Oiiiiii", kwlist,
|
||||
&loggingType, &fileName, &objectUniqueIdsObj, &maxLogDof, &bodyUniqueIdA, &bodyUniqueIdB, &linkIndexA, &linkIndexB, &physicsClientId))
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "is|Oiiiiiii", kwlist,
|
||||
&loggingType, &fileName, &objectUniqueIdsObj, &maxLogDof, &bodyUniqueIdA, &bodyUniqueIdB, &linkIndexA, &linkIndexB, &deviceTypeFilter, &physicsClientId))
|
||||
return NULL;
|
||||
|
||||
sm = getPhysicsClient(physicsClientId);
|
||||
|
||||
Reference in New Issue
Block a user