summaryrefslogtreecommitdiff
path: root/examples/pybullet
diff options
context:
space:
mode:
authorerwincoumans <erwin.coumans@gmail.com>2019-02-28 17:52:59 -0800
committererwincoumans <erwin.coumans@gmail.com>2019-02-28 17:52:59 -0800
commit4d711ed41114ee7d91579f0ba7fe5201876abafc (patch)
tree78e3dea3e68e5ca1569ac8740029484390bbcd08 /examples/pybullet
parent208b38c51f987ccc424971642b199e7c0db75a33 (diff)
parenta9996088c81b8a632750db522470a5e6a3da408c (diff)
downloadbullet3-4d711ed41114ee7d91579f0ba7fe5201876abafc.tar.gz
Merge remote-tracking branch 'origin/physx' into physx_clean
Diffstat (limited to 'examples/pybullet')
-rw-r--r--examples/pybullet/examples/otherPhysicsEngine.py66
-rw-r--r--examples/pybullet/premake4.lua2
-rw-r--r--examples/pybullet/pybullet.c2
3 files changed, 59 insertions, 11 deletions
diff --git a/examples/pybullet/examples/otherPhysicsEngine.py b/examples/pybullet/examples/otherPhysicsEngine.py
index 3399cff4f..93f9fbe44 100644
--- a/examples/pybullet/examples/otherPhysicsEngine.py
+++ b/examples/pybullet/examples/otherPhysicsEngine.py
@@ -1,21 +1,64 @@
import pybullet as p
+import pybullet_data as pd
import time
import math
usePhysX = True
+useMaximalCoordinates = True
if usePhysX:
- p.connect(p.PhysX)
+ p.connect(p.PhysX,options="--numCores=8 --solver=pgs")
p.loadPlugin("eglRendererPlugin")
else:
p.connect(p.GUI)
-p.loadURDF("plane.urdf")
+p.setPhysicsEngineParameter(fixedTimeStep=1./240.,numSolverIterations=4, minimumSolverIslandSize=1024)
+p.setPhysicsEngineParameter(contactBreakingThreshold=0.01)
-for i in range (10):
- sphere = p.loadURDF("marble_cube.urdf",[0,-1,1+i*1], useMaximalCoordinates=False)
-p.changeDynamics(sphere ,-1, mass=1000)
+p.setAdditionalSearchPath(pd.getDataPath())
+#Always make ground plane maximal coordinates, to avoid performance drop in PhysX
+#See https://github.com/NVIDIAGameWorks/PhysX/issues/71
-door = p.loadURDF("door.urdf",[0,0,1])
+p.loadURDF("plane.urdf", useMaximalCoordinates=True)#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")
+jran = 50
+iran = 100
+
+num=64
+radius=0.1
+numDominoes=0
+
+for i in range (int(num*50)):
+ num=(radius*2*math.pi)/0.08
+ radius += 0.05/float(num)
+ orn = p.getQuaternionFromEuler([0,0,0.5*math.pi+math.pi*2*i/float(num)])
+ pos = [radius*math.cos(2*math.pi*(i/float(num))),radius*math.sin(2*math.pi*(i/float(num))), 0.03]
+ sphere = p.loadURDF("domino/domino.urdf",pos, orn, useMaximalCoordinates=useMaximalCoordinates)
+ numDominoes+=1
+
+pos=[pos[0],pos[1],pos[2]+0.3]
+orn = p.getQuaternionFromEuler([0,0,-math.pi/4.])
+sphere = p.loadURDF("domino/domino.urdf",pos, orn, useMaximalCoordinates=useMaximalCoordinates)
+
+print("numDominoes=",numDominoes)
+
+
+#for j in range (20):
+# for i in range (100):
+# if (i<99):
+# sphere = p.loadURDF("domino/domino.urdf",[i*0.04,1+j*.25,0.03], useMaximalCoordinates=useMaximalCoordinates)
+# else:
+# orn = p.getQuaternionFromEuler([0,-3.14*0.24,0])
+# sphere = p.loadURDF("domino/domino.urdf",[(i-1)*0.04,1+j*.25,0.03], orn, useMaximalCoordinates=useMaximalCoordinates)
+
+
+print("loaded!")
+
+
+#p.changeDynamics(sphere ,-1, mass=1000)
+
+door = p.loadURDF("door.urdf",[0,0,-11])
p.changeDynamics(door ,1, linearDamping=0, angularDamping=0, jointDamping=0, mass=1)
print("numJoints = ", p.getNumJoints(door))
@@ -31,8 +74,13 @@ prevTime = time.time()
angle = math.pi*0.5
+count=0
while (1):
-
+ count+=1
+ if (count==12):
+ p.stopStateLogging(logId)
+ p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
+
curTime = time.time()
diff = curTime - prevTime
@@ -45,5 +93,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)
p.stepSimulation()
- time.sleep(1./240.)
+ #time.sleep(1./240.)
diff --git a/examples/pybullet/premake4.lua b/examples/pybullet/premake4.lua
index f0c26eac5..1832dd205 100644
--- a/examples/pybullet/premake4.lua
+++ b/examples/pybullet/premake4.lua
@@ -223,12 +223,10 @@ if not _OPTIONS["no-enet"] then
"../../examples/SharedMemory/plugins/eglPlugin/eglRendererVisualShapeConverter.cpp",
"../../examples/SharedMemory/plugins/eglPlugin/eglRendererVisualShapeConverter.h",
"../../examples/SharedMemory/physx/PhysXC_API.cpp",
- "../../examples/SharedMemory/physx/PhysXClient.cpp",
"../../examples/SharedMemory/physx/PhysXServerCommandProcessor.cpp",
"../../examples/SharedMemory/physx/PhysXUrdfImporter.cpp",
"../../examples/SharedMemory/physx/URDF2PhysX.cpp",
"../../examples/SharedMemory/physx/PhysXC_API.h",
- "../../examples/SharedMemory/physx/PhysXClient.h",
"../../examples/SharedMemory/physx/PhysXServerCommandProcessor.h",
"../../examples/SharedMemory/physx/PhysXUrdfImporter.h",
"../../examples/SharedMemory/physx/URDF2PhysX.h",
diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c
index 9f226729e..7f800d40c 100644
--- a/examples/pybullet/pybullet.c
+++ b/examples/pybullet/pybullet.c
@@ -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