expose PyBullet API to wakeup/put objects to sleep, enable/disable deactivation
fix wakeup -> reset deactivation clock
This commit is contained in:
@@ -9,12 +9,18 @@ p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||
|
||||
p.loadURDF("plane100.urdf",flags=flags, useMaximalCoordinates=useMaximalCoordinates)
|
||||
#p.loadURDF("cube_small.urdf", [0,0,0.5], flags=flags)
|
||||
r2d2 = -1
|
||||
for k in range (5):
|
||||
for i in range (5):
|
||||
r2d2=p.loadURDF("r2d2.urdf",[k*2,i*2,1], useMaximalCoordinates=useMaximalCoordinates, flags=p.URDF_ENABLE_CACHED_GRAPHICS_SHAPES+flags)
|
||||
|
||||
#enable sleeping: you can pass the flag during URDF loading, or do it afterwards
|
||||
#p.changeDynamics(r2d2,-1,activationState=p.ACTIVATION_STATE_ENABLE_SLEEPING)
|
||||
|
||||
|
||||
for j in range (p.getNumJoints(r2d2)):
|
||||
p.setJointMotorControl2(r2d2,j,p.VELOCITY_CONTROL,targetVelocity=0)
|
||||
|
||||
print("r2d2=",r2d2)
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
|
||||
timestep = 1./240.
|
||||
p.setTimeStep(timestep)
|
||||
@@ -23,3 +29,6 @@ p.setGravity(0,0,-10)
|
||||
while p.isConnected():
|
||||
p.stepSimulation()
|
||||
time.sleep(timestep)
|
||||
#force the object to wake up
|
||||
p.changeDynamics(r2d2,-1,activationState=p.ACTIVATION_STATE_WAKE_UP)
|
||||
|
||||
@@ -1183,14 +1183,15 @@ static PyObject* pybullet_changeDynamicsInfo(PyObject* self, PyObject* args, PyO
|
||||
double ccdSweptSphereRadius=-1;
|
||||
int frictionAnchor = -1;
|
||||
double contactProcessingThreshold = -1;
|
||||
int activationState = -1;
|
||||
|
||||
PyObject* localInertiaDiagonalObj=0;
|
||||
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
|
||||
int physicsClientId = 0;
|
||||
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "mass", "lateralFriction", "spinningFriction", "rollingFriction","restitution", "linearDamping", "angularDamping", "contactStiffness", "contactDamping", "frictionAnchor", "localInertiaDiagonal", "ccdSweptSphereRadius", "contactProcessingThreshold", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|dddddddddiOddi", kwlist, &bodyUniqueId, &linkIndex,&mass, &lateralFriction, &spinningFriction, &rollingFriction, &restitution,&linearDamping, &angularDamping, &contactStiffness, &contactDamping, &frictionAnchor, &localInertiaDiagonalObj, &ccdSweptSphereRadius, &contactProcessingThreshold, &physicsClientId))
|
||||
static char* kwlist[] = {"bodyUniqueId", "linkIndex", "mass", "lateralFriction", "spinningFriction", "rollingFriction","restitution", "linearDamping", "angularDamping", "contactStiffness", "contactDamping", "frictionAnchor", "localInertiaDiagonal", "ccdSweptSphereRadius", "contactProcessingThreshold", "activationState", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|dddddddddiOddii", kwlist, &bodyUniqueId, &linkIndex,&mass, &lateralFriction, &spinningFriction, &rollingFriction, &restitution,&linearDamping, &angularDamping, &contactStiffness, &contactDamping, &frictionAnchor, &localInertiaDiagonalObj, &ccdSweptSphereRadius, &contactProcessingThreshold,&activationState, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@@ -1260,6 +1261,10 @@ static PyObject* pybullet_changeDynamicsInfo(PyObject* self, PyObject* args, PyO
|
||||
{
|
||||
b3ChangeDynamicsInfoSetCcdSweptSphereRadius(command,bodyUniqueId,linkIndex, ccdSweptSphereRadius);
|
||||
}
|
||||
if (activationState >= 0)
|
||||
{
|
||||
b3ChangeDynamicsInfoSetActivationState(command, bodyUniqueId, activationState);
|
||||
}
|
||||
if (contactProcessingThreshold >= 0)
|
||||
{
|
||||
b3ChangeDynamicsInfoSetContactProcessingThreshold(command, bodyUniqueId, linkIndex, contactProcessingThreshold);
|
||||
@@ -9617,7 +9622,11 @@ initpybullet(void)
|
||||
PyModule_AddIntConstant(m, "URDF_ENABLE_CACHED_GRAPHICS_SHAPES", URDF_ENABLE_CACHED_GRAPHICS_SHAPES);
|
||||
PyModule_AddIntConstant(m, "URDF_ENABLE_SLEEPING", URDF_ENABLE_SLEEPING);
|
||||
PyModule_AddIntConstant(m, "URDF_INITIALIZE_SAT_FEATURES", URDF_INITIALIZE_SAT_FEATURES);
|
||||
|
||||
|
||||
PyModule_AddIntConstant(m, "ACTIVATION_STATE_ENABLE_SLEEPING", eActivationStateEnableSleeping);
|
||||
PyModule_AddIntConstant(m, "ACTIVATION_STATE_DISABLE_SLEEPING", eActivationStateDisableSleeping);
|
||||
PyModule_AddIntConstant(m, "ACTIVATION_STATE_WAKE_UP", eActivationStateWakeUp);
|
||||
PyModule_AddIntConstant(m, "ACTIVATION_STATE_SLEEP", eActivationStateSleep);
|
||||
|
||||
PyModule_AddIntConstant(m, "URDF_USE_SELF_COLLISION", URDF_USE_SELF_COLLISION);
|
||||
PyModule_AddIntConstant(m, "URDF_USE_SELF_COLLISION_EXCLUDE_PARENT", URDF_USE_SELF_COLLISION_EXCLUDE_PARENT);
|
||||
|
||||
Reference in New Issue
Block a user