export object auto-deactivation (sleeping) to pybullet (needs some more testing/configuring)

This commit is contained in:
Erwin Coumans
2018-05-30 18:37:08 -07:00
parent 14c6dee6a3
commit 491ecf2a20
5 changed files with 29 additions and 1 deletions

View File

@@ -359,7 +359,7 @@ void ConvertURDF2BulletInternal(
if (cache.m_bulletMultiBody==0)
{
bool canSleep = false;
bool canSleep = (flags & CUF_ENABLE_SLEEPING)!=0;
bool isFixedBase = (mass==0);//todo: figure out when base is fixed
int totalNumJoints = cache.m_totalNumJoints1;
cache.m_bulletMultiBody = creation.allocateMultiBody(urdfLinkIndex, totalNumJoints,mass, localInertiaDiagonal, isFixedBase, canSleep);

View File

@@ -29,6 +29,7 @@ enum ConvertURDFFlags {
CUF_GLOBAL_VELOCITIES_MB=256,
CUF_MJCF_COLORS_FROM_FILE=512,
CUF_ENABLE_CACHED_GRAPHICS_SHAPES = 1024,
CUF_ENABLE_SLEEPING=2048,
};
struct UrdfVisualShapeCache