Implement PyBullet.getCameraImage for PhysX backend.

PhysX backend, allow arbitrary plane normal, a few other fixes.
This commit is contained in:
erwincoumans
2019-02-24 14:09:42 -08:00
parent 9ecc1cc485
commit a9996088c8
7 changed files with 481 additions and 104 deletions

View File

@@ -15,7 +15,13 @@ image = plt.imshow(img,interpolation='none',animated=True,label="blah")
ax = plt.gca()
pybullet.connect(pybullet.DIRECT)
usePhysX = True
useMaximalCoordinates = True
if usePhysX:
pybullet.connect(pybullet.PhysX,options="--numCores=8 --solver=pgs")
pybullet.loadPlugin("eglRendererPlugin")
else:
pybullet.connect(pybullet.GUI)
#pybullet.loadPlugin("eglRendererPlugin")
pybullet.loadURDF("plane.urdf",[0,0,-1])