Merge remote-tracking branch 'bp/master' into pullRequest
This commit is contained in:
25
examples/pybullet/manyspheres.py
Normal file
25
examples/pybullet/manyspheres.py
Normal file
@@ -0,0 +1,25 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.loadURDF("plane.urdf",useMaximalCoordinates=True)
|
||||
p.loadURDF("tray/traybox.urdf",useMaximalCoordinates=True)
|
||||
|
||||
gravXid = p.addUserDebugParameter("gravityX",-10,10,0)
|
||||
gravYid = p.addUserDebugParameter("gravityY",-10,10,0)
|
||||
gravZid = p.addUserDebugParameter("gravityZ",-10,10,-10)
|
||||
p.setPhysicsEngineParameter(numSolverIterations=10)
|
||||
p.setPhysicsEngineParameter(contactBreakingThreshold=0.001)
|
||||
for i in range (10):
|
||||
for j in range (10):
|
||||
for k in range (5):
|
||||
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)
|
||||
while True:
|
||||
gravX = p.readUserDebugParameter(gravXid)
|
||||
gravY = p.readUserDebugParameter(gravYid)
|
||||
gravZ = p.readUserDebugParameter(gravZid)
|
||||
p.setGravity(gravX,gravY,gravZ)
|
||||
time.sleep(0.01)
|
||||
|
||||
@@ -583,14 +583,15 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
|
||||
double splitImpulsePenetrationThreshold = -1;
|
||||
int numSubSteps = -1;
|
||||
int collisionFilterMode = -1;
|
||||
double contactBreakingThreshold = -1;
|
||||
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
|
||||
int physicsClientId = 0;
|
||||
static char *kwlist[] = { "fixedTimeStep", "numSolverIterations","useSplitImpulse","splitImpulsePenetrationThreshold", "numSubSteps","collisionFilterMode", "physicsClientId", NULL };
|
||||
static char *kwlist[] = { "fixedTimeStep", "numSolverIterations","useSplitImpulse","splitImpulsePenetrationThreshold", "numSubSteps","collisionFilterMode", "contactBreakingThreshold", "physicsClientId", NULL };
|
||||
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidiii", kwlist,&fixedTimeStep,&numSolverIterations,&useSplitImpulse,&splitImpulsePenetrationThreshold,&numSubSteps,
|
||||
&collisionFilterMode, &physicsClientId))
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidiidi", kwlist,&fixedTimeStep,&numSolverIterations,&useSplitImpulse,&splitImpulsePenetrationThreshold,&numSubSteps,
|
||||
&collisionFilterMode, &contactBreakingThreshold, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@@ -610,6 +611,7 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
|
||||
{
|
||||
b3PhysicsParamSetNumSolverIterations(command, numSolverIterations);
|
||||
}
|
||||
|
||||
if (collisionFilterMode>=0)
|
||||
{
|
||||
b3PhysicsParamSetCollisionFilterMode(command, collisionFilterMode);
|
||||
@@ -630,6 +632,11 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
|
||||
{
|
||||
b3PhysicsParamSetSplitImpulsePenetrationThreshold(command, splitImpulsePenetrationThreshold);
|
||||
}
|
||||
if (contactBreakingThreshold>=0)
|
||||
{
|
||||
b3PhysicsParamSetContactBreakingThreshold(command,contactBreakingThreshold);
|
||||
}
|
||||
|
||||
|
||||
//ret = b3PhysicsParamSetRealTimeSimulation(command, enableRealTimeSimulation);
|
||||
|
||||
|
||||
26
examples/pybullet/rollPitchYaw.py
Normal file
26
examples/pybullet/rollPitchYaw.py
Normal file
@@ -0,0 +1,26 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
|
||||
cid = p.connect(p.SHARED_MEMORY)
|
||||
if (cid<0):
|
||||
p.connect(p.GUI)
|
||||
q = p.loadURDF("quadruped/quadruped.urdf",useFixedBase=True)
|
||||
rollId = p.addUserDebugParameter("roll",-1.5,1.5,0)
|
||||
pitchId = p.addUserDebugParameter("pitch",-1.5,1.5,0)
|
||||
yawId = p.addUserDebugParameter("yaw",-1.5,1.5,0)
|
||||
fwdxId = p.addUserDebugParameter("fwd_x",-1,1,0)
|
||||
fwdyId = p.addUserDebugParameter("fwd_y",-1,1,0)
|
||||
fwdzId = p.addUserDebugParameter("fwd_z",-1,1,0)
|
||||
|
||||
while True:
|
||||
roll = p.readUserDebugParameter(rollId)
|
||||
pitch = p.readUserDebugParameter(pitchId)
|
||||
yaw = p.readUserDebugParameter(yawId)
|
||||
x = p.readUserDebugParameter(fwdxId)
|
||||
y = p.readUserDebugParameter(fwdyId)
|
||||
z = p.readUserDebugParameter(fwdzId)
|
||||
|
||||
orn = p.getQuaternionFromEuler([roll,pitch,yaw])
|
||||
p.resetBasePositionAndOrientation(q,[x,y,z],orn)
|
||||
#p.stepSimulation()#not really necessary for this demo, no physics used
|
||||
|
||||
Reference in New Issue
Block a user