texture caching and geometry caching (PhysX) for much faster loading of many same objects, helps benchmarking/comparison.

add command-line args for PhysX (numCores=..., solver=tgs, )
This commit is contained in:
erwincoumans
2019-02-21 19:24:18 -08:00
parent 3bf27cf8f2
commit 71b1191947
10 changed files with 220 additions and 117 deletions

View File

@@ -1,18 +1,27 @@
import pybullet as p
import pybullet_data as pd
import time
import math
usePhysX = True
if usePhysX:
p.connect(p.PhysX)
p.connect(p.PhysX,options="--numCores=1 --solver=pgs")
p.loadPlugin("eglRendererPlugin")
else:
p.connect(p.GUI)
p.loadURDF("plane.urdf")
useMaximalCoordinates = False
p.setAdditionalSearchPath(pd.getDataPath())
p.loadURDF("plane.urdf", useMaximalCoordinates=useMaximalCoordinates)
p.configureDebugVisualizer(p.COV_ENABLE_TINY_RENDERER,0)
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS,"physx_create_dominoes.json")
for j in range (50):
for i in range (100):
sphere = p.loadURDF("domino/domino.urdf",[i*0.04,1+j*.25,0.03], useMaximalCoordinates=useMaximalCoordinates)
print("loaded!")
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
for i in range (10):
sphere = p.loadURDF("marble_cube.urdf",[0,-1,1+i*1], useMaximalCoordinates=False)
p.changeDynamics(sphere ,-1, mass=1000)
door = p.loadURDF("door.urdf",[0,0,1])
@@ -31,8 +40,12 @@ prevTime = time.time()
angle = math.pi*0.5
count=0
while (1):
count+=1
if (count==10):
p.stopStateLogging(logId)
curTime = time.time()
diff = curTime - prevTime
@@ -45,7 +58,7 @@ while (1):
p.setJointMotorControl2(door,1,p.POSITION_CONTROL, targetPosition = angle, positionGain=10.1, velocityGain=1, force=11.001)
else:
p.setJointMotorControl2(door,1,p.VELOCITY_CONTROL, targetVelocity=1, force=1011)
contacts = p.getContactPoints()
print("contacts=",contacts)
#contacts = p.getContactPoints()
#print("contacts=",contacts)
p.stepSimulation()
time.sleep(1./240.)

View File

@@ -456,7 +456,7 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
#ifdef BT_ENABLE_PHYSX
case eCONNECT_PHYSX:
{
sm = b3ConnectPhysX();
sm = b3ConnectPhysX(argc, argv);
break;
}
#endif