PyBullet: handle the switch from fixed base to floating base when changing mass from zero to non-zero

This commit is contained in:
Erwin Coumans 2019-01-03 17:35:12 -08:00
parent bf9efffa4b
commit 19aafd5221
4 changed files with 54 additions and 1 deletions

View File

@ -2652,7 +2652,7 @@ B3_SHARED_API int b3ChangeDynamicsInfoSetMass(b3SharedMemoryCommandHandle comman
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
b3Assert(command->m_type == CMD_CHANGE_DYNAMICS_INFO);
b3Assert(mass > 0);
b3Assert(mass >= 0);
command->m_changeDynamicsInfoArgs.m_bodyUniqueId = bodyUniqueId;
command->m_changeDynamicsInfoArgs.m_linkIndex = linkIndex;
command->m_changeDynamicsInfoArgs.m_mass = mass;

View File

@ -7461,6 +7461,39 @@ bool PhysicsServerCommandProcessor::processChangeDynamicsInfoCommand(const struc
mb->getBaseCollider()->getCollisionShape()->calculateLocalInertia(mass, localInertia);
mb->setBaseInertia(localInertia);
}
//handle switch from static/fixedBase to dynamic and vise-versa
if (mass > 0)
{
bool isDynamic = true;
if (mb->hasFixedBase())
{
int collisionFilterGroup = isDynamic ? int(btBroadphaseProxy::DefaultFilter) : int(btBroadphaseProxy::StaticFilter);
int collisionFilterMask = isDynamic ? int(btBroadphaseProxy::AllFilter) : int(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
m_data->m_dynamicsWorld->removeCollisionObject(mb->getBaseCollider());
int oldFlags = mb->getBaseCollider()->getCollisionFlags();
mb->getBaseCollider()->setCollisionFlags(oldFlags & ~btCollisionObject::CF_STATIC_OBJECT);
mb->setFixedBase(false);
m_data->m_dynamicsWorld->addCollisionObject(mb->getBaseCollider(), collisionFilterGroup, collisionFilterMask);
}
}
else
{
if (!mb->hasFixedBase())
{
bool isDynamic = false;
int collisionFilterGroup = isDynamic ? int(btBroadphaseProxy::DefaultFilter) : int(btBroadphaseProxy::StaticFilter);
int collisionFilterMask = isDynamic ? int(btBroadphaseProxy::AllFilter) : int(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
int oldFlags = mb->getBaseCollider()->getCollisionFlags();
mb->getBaseCollider()->setCollisionFlags(oldFlags | btCollisionObject::CF_STATIC_OBJECT);
m_data->m_dynamicsWorld->removeCollisionObject(mb->getBaseCollider());
mb->setFixedBase(true);
m_data->m_dynamicsWorld->addCollisionObject(mb->getBaseCollider(), collisionFilterGroup, collisionFilterMask);
}
}
}
if (clientCmd.m_updateFlags & CHANGE_DYNAMICS_INFO_SET_LOCAL_INERTIA_DIAGONAL)
{

View File

@ -0,0 +1,15 @@
import pybullet as p
import time
p.connect(p.GUI)
cube2 = p.loadURDF("cube.urdf",[0,0,3], useFixedBase=True)
cube = p.loadURDF("cube.urdf", useFixedBase=True)
p.setGravity(0,0,-10)
timeStep = 1./240.
p.setTimeStep(timeStep)
p.changeDynamics(cube2,-1,mass=1)
#now cube2 will have a floating base and move
while (p.isConnected()):
p.stepSimulation()
time.sleep(timeStep)

View File

@ -469,6 +469,11 @@ public:
return m_fixedBase;
}
void setFixedBase(bool fixedBase)
{
m_fixedBase = fixedBase;
}
int getCompanionId() const
{
return m_companionId;