PyBullet: rename sleepObjectAutoDeactivation -> sleeping.py

PyBullet: allow maximal coordinate rigid bodies to sleep/deactivate
This commit is contained in:
erwincoumans
2018-05-30 21:14:35 -07:00
parent 150a0e050e
commit 8567f6bb7c
3 changed files with 10 additions and 4 deletions

View File

@@ -337,6 +337,12 @@ void ConvertURDF2BulletInternal(
if (!createMultiBody)
{
btRigidBody* body = creation.allocateRigidBody(urdfLinkIndex, mass, localInertiaDiagonal, inertialFrameInWorldSpace, compoundShape);
bool canSleep = (flags & CUF_ENABLE_SLEEPING)!=0;
if (!canSleep)
{
body->forceActivationState(DISABLE_DEACTIVATION);
}
linkRigidBody = body;
world1->addRigidBody(body);