expose pybullet changeDynamics(spinningFriction=..., rollingFriction=..., restitution=...)
Bullet C-API b3ChangeDynamicsInfoSetSpinningFriction/RollingFriction/Resitution b3PhysicsParamSetRestitutionVelocityThreshold, / pybullet.setPhysicsEngineParameter restitutionVelocityThreshold: if the velocity is below this threshhold, the restitution is zero (this prevents energy buildup at near-resting state) pybullet restitution.py example.
This commit is contained in:
38
examples/pybullet/examples/restitution.py
Normal file
38
examples/pybullet/examples/restitution.py
Normal file
@@ -0,0 +1,38 @@
|
||||
#you can set the restitution (bouncyness) of an object in the URDF file
|
||||
#or using changeDynamics
|
||||
|
||||
import pybullet as p
|
||||
import time
|
||||
|
||||
p.connect(p.GUI)
|
||||
restitutionId = p.addUserDebugParameter("restitution",0,1,1)
|
||||
restitutionVelocityThresholdId = p.addUserDebugParameter("res. vel. threshold",0,3,0.2)
|
||||
|
||||
lateralFrictionId = p.addUserDebugParameter("lateral friction",0,1,0.5)
|
||||
spinningFrictionId = p.addUserDebugParameter("spinning friction",0,1,0.03)
|
||||
rollingFrictionId = p.addUserDebugParameter("rolling friction",0,1,0.03)
|
||||
|
||||
plane = p.loadURDF("plane_with_restitution.urdf")
|
||||
sphere = p.loadURDF("sphere_with_restitution.urdf",[0,0,2])
|
||||
|
||||
p.setRealTimeSimulation(1)
|
||||
p.setGravity(0,0,-10)
|
||||
while (1):
|
||||
restitution = p.readUserDebugParameter(restitutionId)
|
||||
restitutionVelocityThreshold = p.readUserDebugParameter(restitutionVelocityThresholdId)
|
||||
p.setPhysicsEngineParameter(restitutionVelocityThreshold=restitutionVelocityThreshold)
|
||||
|
||||
lateralFriction = p.readUserDebugParameter(lateralFrictionId)
|
||||
spinningFriction = p.readUserDebugParameter(spinningFrictionId)
|
||||
rollingFriction = p.readUserDebugParameter(rollingFrictionId)
|
||||
p.changeDynamics(plane,-1,lateralFriction=1)
|
||||
p.changeDynamics(sphere,-1,lateralFriction=lateralFriction)
|
||||
p.changeDynamics(sphere,-1,spinningFriction=spinningFriction)
|
||||
p.changeDynamics(sphere,-1,rollingFriction=rollingFriction)
|
||||
|
||||
p.changeDynamics(plane,-1,restitution=restitution)
|
||||
p.changeDynamics(sphere,-1,restitution=restitution)
|
||||
pos,orn=p.getBasePositionAndOrientation(sphere)
|
||||
#print("pos=")
|
||||
#print(pos)
|
||||
time.sleep(0.01)
|
||||
@@ -620,11 +620,15 @@ static PyObject* pybullet_changeDynamicsInfo(PyObject* self, PyObject* args, PyO
|
||||
int linkIndex = -2;
|
||||
double mass = -1;
|
||||
double lateralFriction = -1;
|
||||
double spinningFriction= -1;
|
||||
double rollingFriction = -1;
|
||||
double restitution = -1;
|
||||
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
|
||||
int physicsClientId = 0;
|
||||
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "mass", "lateralFriction", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|ddi", kwlist, &bodyUniqueId, &linkIndex,&mass, &lateralFriction, &physicsClientId))
|
||||
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "mass", "lateralFriction", "spinningFriction", "rollingFriction","restitution", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|dddddi", kwlist, &bodyUniqueId, &linkIndex,&mass, &lateralFriction, &spinningFriction, &rollingFriction, &restitution, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@@ -644,12 +648,23 @@ static PyObject* pybullet_changeDynamicsInfo(PyObject* self, PyObject* args, PyO
|
||||
{
|
||||
b3ChangeDynamicsInfoSetMass(command, bodyUniqueId, linkIndex, mass);
|
||||
}
|
||||
|
||||
if (lateralFriction >= 0)
|
||||
{
|
||||
b3ChangeDynamicsInfoSetLateralFriction(command, bodyUniqueId, linkIndex, lateralFriction);
|
||||
}
|
||||
|
||||
if (spinningFriction>=0)
|
||||
{
|
||||
b3ChangeDynamicsInfoSetSpinningFriction(command, bodyUniqueId, linkIndex,spinningFriction);
|
||||
}
|
||||
if (rollingFriction>=0)
|
||||
{
|
||||
b3ChangeDynamicsInfoSetRollingFriction(command, bodyUniqueId, linkIndex,rollingFriction);
|
||||
}
|
||||
|
||||
if (restitution>=0)
|
||||
{
|
||||
b3ChangeDynamicsInfoSetRestitution(command, bodyUniqueId, linkIndex, restitution);
|
||||
}
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
|
||||
}
|
||||
|
||||
@@ -725,14 +740,14 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
|
||||
double contactBreakingThreshold = -1;
|
||||
int maxNumCmdPer1ms = -2;
|
||||
int enableFileCaching = -1;
|
||||
|
||||
double restitutionVelocityThreshold=-1;
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
|
||||
int physicsClientId = 0;
|
||||
static char* kwlist[] = {"fixedTimeStep", "numSolverIterations", "useSplitImpulse", "splitImpulsePenetrationThreshold", "numSubSteps", "collisionFilterMode", "contactBreakingThreshold", "maxNumCmdPer1ms", "enableFileCaching","physicsClientId", NULL};
|
||||
static char* kwlist[] = {"fixedTimeStep", "numSolverIterations", "useSplitImpulse", "splitImpulsePenetrationThreshold", "numSubSteps", "collisionFilterMode", "contactBreakingThreshold", "maxNumCmdPer1ms", "enableFileCaching","restitutionVelocityThreshold", "physicsClientId", NULL};
|
||||
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidiidiii", kwlist, &fixedTimeStep, &numSolverIterations, &useSplitImpulse, &splitImpulsePenetrationThreshold, &numSubSteps,
|
||||
&collisionFilterMode, &contactBreakingThreshold, &maxNumCmdPer1ms, &enableFileCaching, &physicsClientId))
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidiidiidi", kwlist, &fixedTimeStep, &numSolverIterations, &useSplitImpulse, &splitImpulsePenetrationThreshold, &numSubSteps,
|
||||
&collisionFilterMode, &contactBreakingThreshold, &maxNumCmdPer1ms, &enableFileCaching, &restitutionVelocityThreshold, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@@ -783,6 +798,10 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
|
||||
b3PhysicsParamSetMaxNumCommandsPer1ms(command, maxNumCmdPer1ms);
|
||||
}
|
||||
|
||||
if (restitutionVelocityThreshold>=0)
|
||||
{
|
||||
b3PhysicsParamSetRestitutionVelocityThreshold(command, restitutionVelocityThreshold);
|
||||
}
|
||||
if (enableFileCaching>=0)
|
||||
{
|
||||
b3PhysicsParamSetEnableFileCaching(command, enableFileCaching);
|
||||
@@ -921,7 +940,7 @@ static PyObject* pybullet_loadURDF(PyObject* self, PyObject* args, PyObject* key
|
||||
startOrnZ, startOrnW);
|
||||
if (useMaximalCoordinates>=0)
|
||||
{
|
||||
b3LoadUrdfCommandSetUseMultiBody(command, useMaximalCoordinates);
|
||||
b3LoadUrdfCommandSetUseMultiBody(command, useMaximalCoordinates==0);
|
||||
}
|
||||
if (useFixedBase)
|
||||
{
|
||||
|
||||
Reference in New Issue
Block a user